ROS Resources: Documentation | Support | Discussion Forum | Index | Service Status | ros @ Robotics Stack Exchange
Ask Your Question

Revision history [back]

click to hide/show revision 1
initial version

There's no function to do this for you right now.

One thing that is different in ROS 2 is that there's no notion of a "Serializer" class that handles serialization for all configurations, instead serialization is handled by the middleware through an abstraction layer. This is nice because it allows us to use different serialization formats if we want or need to do so, but due to the abstraction layer you don't actually know how big it will be on the wire without asking the middleware implementation.

We already have functions for asking the current middle implementation to do serializing and deserializing of messages:

  • https://github.com/ros2/rmw/blob/e185d65f02acccd5388cd664ae990d5227398f5f/rmw/include/rmw/rmw.h#L210-L229
  • https://github.com/ros2/rmw/blob/e185d65f02acccd5388cd664ae990d5227398f5f/rmw/include/rmw/rmw.h#L231-L253

So specifically for your use case you could try serializing messages yourself, checking the resulting size of the serialized message, and then publishing it as normal

The serialized type is in rmw, but it is actually a typedef in to a general purpose data structure in our C utility package called rcutils:

https://github.com/ros2/rmw/blob/e185d65f02acccd5388cd664ae990d5227398f5f/rmw/include/rmw/serialized_message.h#L31

The rcutils data structure has the size of the serialized result though:

https://github.com/ros2/rcutils/blob/1bb9cc611fe63ef83d6e4335c3f4800328492272/include/rcutils/types/char_array.h#L30

Doing it this way might actually even be preferred, because determining what the serialized size would be might take almost as long as just serializing it and you'll be serializing it anyways (most likely).

There is, however, no way to ask the middleware right now to "predict" the serialized size of a message given the ROS data structure, e.g. an instance of std_msgs::msg::String, without first serializing it. It is probably possible to implement such a function, but we'd need to add it to our middleware interface.

There is also no C++ class that wraps up these related functions or C++ versions of the functions for that matter, but it's something that we'd be interested in having and if you're interested in helping with that I'd suggest starting a discussion on an issue in the rclcpp repository to have an equivalent to the Serializer<T> class from roscpp.


In a related subject, we do have these traits for each message:

https://github.com/ros2/rosidl/blob/ac4ac643d55cd7fb6c9604d0e67dc86dcd8d8d53/rosidl_generator_cpp/resource/msg__traits.hpp.em#L50-L107

Among them is the is_fixed_size trait and the is_bounded_size trait. If the is_fixed_size is true then there is a single size for the message in memory and on the wire (I'm pretty sure about the wire part but not 100%). And if is_bounded_size is true then there is a fixed upper bound on the size of the message in memory and/or on the wire.

There's no function to do this for you right now.

One thing that is different in ROS 2 is that there's no notion of a "Serializer" class that handles serialization for all configurations, instead serialization is handled by the middleware through an abstraction layer. This is nice because it allows us to use different serialization formats if we want or need to do so, but due to the abstraction layer you don't actually know how big it will be on the wire without asking the middleware implementation.

We already have functions for asking the current middle implementation to do serializing and deserializing of messages:

  • https://github.com/ros2/rmw/blob/e185d65f02acccd5388cd664ae990d5227398f5f/rmw/include/rmw/rmw.h#L210-L229
  • https://github.com/ros2/rmw/blob/e185d65f02acccd5388cd664ae990d5227398f5f/rmw/include/rmw/rmw.h#L231-L253

So specifically for your use case you could try serializing messages yourself, checking the resulting size of the serialized message, and then publishing it as normal

The serialized type is in rmw, but it is actually a typedef in to a general purpose data structure in our C utility package called rcutils:

https://github.com/ros2/rmw/blob/e185d65f02acccd5388cd664ae990d5227398f5f/rmw/include/rmw/serialized_message.h#L31

The rcutils data structure has the size of the serialized result though:

https://github.com/ros2/rcutils/blob/1bb9cc611fe63ef83d6e4335c3f4800328492272/include/rcutils/types/char_array.h#L30

Doing it this way might actually even be preferred, because determining what the serialized size would be might take almost as long as just serializing it and you'll be serializing it anyways (most likely).

There is, however, no way to ask the middleware right now to "predict" the serialized size of a message given the ROS data structure, e.g. an instance of std_msgs::msg::String, without first serializing it. It is probably possible to implement such a function, but we'd need to add it to our middleware interface.

There is also no C++ class that wraps up these related functions or C++ versions of the functions for that matter, but it's something that we'd be interested in having and if you're interested in helping with that I'd suggest starting a discussion on an issue in the rclcpp repository to have an equivalent to the Serializer<T> class from roscpp.


In a related subject, we do have these traits for each message:

https://github.com/ros2/rosidl/blob/ac4ac643d55cd7fb6c9604d0e67dc86dcd8d8d53/rosidl_generator_cpp/resource/msg__traits.hpp.em#L50-L107

Among them is the is_fixed_size trait and the is_bounded_size trait. If the is_fixed_size is true then there is a single size for the message in memory and on the wire (I'm pretty sure about the wire part but not 100%). And if is_bounded_size is true then there is a fixed upper bound on the size of the message in memory and/or on the wire.

But again, there's not yet a function to actually calculate the fixed size or bounded size for messages.