roscpp overview: Initialization and Shutdown | Basics | Advanced: Traits [ROS C Turtle] | Advanced: Custom Allocators [ROS C Turtle] | Advanced: Serialization and Adapting Types [ROS C Turtle] | Publishers and Subscribers | Services | Parameter Server | Timers (Periodic Callbacks) | NodeHandles | Callbacks and Spinning | Logging | Names and Node Information | Time | Exceptions | Compilation Options | Advanced: Internals | tf/Overview | tf/Tutorials | C++ Style Guide

Serializing to Memory

New in C Turtle

roscpp messages can be serialized to memory easily using the ros::serialization::serialize() function.

For example:

   1 namespace ser = ros::serialization;
   2 
   3 std_msgs::UInt32 my_value;
   4 my_value.data = 5;
   5 
   6 uint32_t serial_size = ros::serialization::serializationLength(my_value);
   7 boost::shared_array<uint8_t> buffer(new uint8_t[serial_size]);
   8 
   9 ser::OStream stream(buffer.get(), serial_size);
  10 ser::serialize(stream, my_value);

Deserializing from Memory

New in C Turtle

roscpp messages can also be deserialized from memory quite easily.

For example:

   1 namespace ser = ros::serialization;
   2 
   3 std_msgs::UInt32 my_value;
   4 
   5 uint32_t serial_size = ros::serialization::serializationLength(my_value);
   6 boost::shared_array<uint8_t> buffer(new uint8_t[serial_size]);
   7 
   8 // Fill buffer with a serialized UInt32
   9 ser::IStream stream(buffer.get(), serial_size);
  10 ser::deserialize(stream, my_value);

Note: the above leads to a deprecation warning in recent versions of ROS (Diamondback and beyond). The solution seems to be to replace the last line with:

   1 ros::serialization::Serializer<std_msgs::UInt32>::read(stream, my_value);

Adapting C++ Types

New in C Turtle

Due to the template-based serialization system used by roscpp since ROS 1.1, it is possible to adapt an external type for use with ROS publish/subscribe without modifying that type at all. This is done through a set of specialized traits classes, as well as a specialized Serializer class.

Trait Specialization

The traits required for publish/subscribe are detailed at the message traits page.

Serializer Specialization

To define serialization for a type you must define a specialization of the ros::serialization::Serializer class:

   1 template<typename T>
   2 struct Serializer
   3 {
   4   template<typename Stream>
   5   inline static void write(Stream& stream, typename boost::call_traits<T>::param_type t);
   6   template<typename Stream>
   7   inline static void read(Stream& stream, typename boost::call_traits<T>::reference t);
   8   inline static uint32_t serializedLength(typename boost::call_traits<T>::param_type t);
   9 };

Alternatively, you can define an "all-in-one" serializer:

   1 template<typename T>
   2 struct Serializer
   3 {
   4   template<typename Stream, typename M>
   5   inline static void allInOne(Stream& stream, M t);
   6   ROS_DECLARE_ALLINONE_SERIALIZER;
   7 };

Note that if you're using an all-in-one serializer, you are not allowed to use anything but stream.next(). Anything requiring more complicated behavior should use the 3-function split version.

Example: Adapting a custom Vector3

Say you want to adapt your own vector struct for use with roscpp that is compatible with geometry_msgs/Vector3:

   1 #include <ros/message_traits.h>
   2 #include <ros/serialization.h>
   3 
   4 struct MyVector3
   5 {
   6   double x;
   7   double y;
   8   double z;
   9 };
  10 // compile-time assert that sizeof(MyVector3) == serializationLength(x) + serializationLength(y) + serializationLength(z)
  11 ROS_STATIC_ASSERT(sizeof(MyVector3) == 24);
  12 
  13 namespace ros
  14 {
  15 namespace message_traits
  16 {
  17 // This type is fixed-size (24-bytes)
  18 template<> struct IsFixedSize<MyVector3> : public TrueType {};
  19 // This type is memcpyable
  20 template<> struct IsSimple<MyVector3> : public TrueType {};
  21 
  22 template<>
  23 struct MD5Sum<MyVector3>
  24 {
  25   static const char* value()
  26   {
  27     // Ensure that if the definition of geometry_msgs/Vector3 changes we have a compile error here.
  28     ROS_STATIC_ASSERT(MD5Sum<geometry_msgs::Vector3>::static_value1 == 0x4a842b65f413084dULL);
  29     ROS_STATIC_ASSERT(MD5Sum<geometry_msgs::Vector3>::static_value2 == 0xc2b10fb484ea7f17ULL);
  30     return MD5Sum<geometry_msgs::Vector3>::value();
  31   }
  32 
  33   static const char* value(const MyVector3& m)
  34   {
  35     return MD5Sum<geometry_msgs::Vector3>::value(m);
  36   }
  37 };
  38 
  39 template<>
  40 struct DataType<MyVector3>
  41 {
  42   static const char* value()
  43   {
  44     return DataType<geometry_msgs::Vector3>::value();
  45   }
  46 
  47   static const char* value(const MyVector3& m)
  48   {
  49     return DataType<geometry_msgs::Vector3>::value(m);
  50   }
  51 };
  52 
  53 template<>
  54 struct Definition<MyVector3>
  55 {
  56   static const char* value()
  57   {
  58     return Definition<geometry_msgs::Vector3>::value();
  59   }
  60 
  61   static const char* value(const MyVector3& m)
  62   {
  63     return Definition<geometry_msgs::Vector3>::value(m);
  64   }
  65 };
  66 } // namespace message_traits
  67 
  68 namespace serialization
  69 {
  70 template<>
  71 struct Serializer<MyVector3>
  72 {
  73   template<typename Stream, typename T>
  74   inline static void allInOne(Stream& stream, T t)
  75   {
  76     stream.next(t.x);
  77     stream.next(t.y);
  78     stream.next(t.z);
  79   }
  80 
  81   ROS_DECLARE_ALLINONE_SERIALIZER;
  82 };
  83 } // namespace serialization
  84 } // namespace ros
  85 

To instead use the 3-function serializer:

   1 namespace ros
   2 {
   3 namespace serialization
   4 {
   5 
   6 template<>
   7 struct Serializer<MyVector3>
   8 {
   9   template<typename Stream>
  10   inline static void write(Stream& stream, const MyVector3& t)
  11   {
  12     stream.next(t.x);
  13     stream.next(t.y);
  14     stream.next(t.z);
  15   }
  16 
  17   template<typename Stream>
  18   inline static void read(Stream& stream, MyVector3& t)
  19   {
  20     stream.next(t.x);
  21     stream.next(t.y);
  22     stream.next(t.z);
  23   }
  24 
  25   inline static uint32_t serializedLength(const MyVector3& t)
  26   {
  27     uint32_t size = 0;
  28     size += serializationLength(t.x);
  29     size += serializationLength(t.y);
  30     size += serializationLength(t.z);
  31     return size;
  32   }
  33 };
  34 
  35 } // namespace serialization
  36 } // namespace ros
  37 

Customizing generated message headers for C++

New in gencpp 0.6.0

In case you need further control on the generated message headers, or want to provide additional custom methods which can be used with your messages, it is possible to do so via adding specific macros, or providing a full header for your message type. This is complementary to Adapting C++ types outlined above, in the sense that you start from a message definition and allow for additional / more fine-grained control of the generated object type, instead of the other way around. A convenient effect of this approach is that extensions applied to a message type will immediately apply to that message nested instances as well.

IMPORTANT: be careful, as doing so might break the expected message API and/or compatibility with other languages. Custom-defined components will replace the auto-generated ones.

Consider you have a simple message definition

# my_pkg/msg/MyVector3.msg
float64 x
float64 y
float64 z

it is possible to customize the generated header by defining the appropriate macros in the file my_pkg/include/my_pkg/plugin/MyVector3.h. The name of these macros follow the structure <PKG_NAME>_MESSAGE_<MSG_NAME>_PLUGIN_<MACRO_TYPE>, where <MACRO_TYPE> is one of CONSTRUCTOR, CLASS_BODY, SERIALIZER, PRINTER.

New in gencpp 0.6.2 If you create file my_pkg/include/my_pkg/plugin/MyVector3.after.h, it will be included at the end of the generated message header. This can be used to define free functions (functions in the global namespace), e.g. operators on the message types.

You will also need to add an install target for these headers in your package CMakeLists.txt, e.g. (mind the trailing / in the directory name)

install(DIRECTORY include/${PROJECT_NAME}/
  DESTINATION ${CATKIN_PACKAGE_INCLUDE_DESTINATION}
  FILES_MATCHING PATTERN "*.h"
)

Example: defining a custom constructor

If you want MyVector3 instances to have a custom initial value, you could customize your constructor by defining the macro

   1 #define `MY_PKG_MESSAGE_MYVECTOR3_PLUGIN_CONSTRUCTOR` \
   2   MyVector3_(double x = 0, double y = 0, double z = 0) \
   3     : x(x), \
   4       y(y), \
   5       z(z) { }
   6 

Notice that you have to provide a default value (or an additional default constructor), as ROS messages are required to be default constructible because in the subscription pipeline a new instance is constructed and then passed to the deserializer (customization would be possible via traits). Alternatively, additional custom constructors can also be added without replacing the default one by defining them as custom methods.

Example: defining custom methods

Let's see how to define custom methods for MyVector3. If you want to add multiple methods, they all need to be defined in the same macro instance.

   1 #include <cmath>  // for std::sqrt()
   2 ...
   3 #define `MY_PKG_MESSAGE_MYVECTOR3_PLUGIN_CLASS_BODY` \
   4   double norm() const { \
   5     return std::sqrt(x * x + y * y + z * z); \
   6   } \
   7   \
   8   void reset() { \
   9     x = 0; \
  10     y = 0; \
  11     z = 0; \
  12   }
  13 

Example: define global namespace operators

New in gencpp 0.6.2 To add functions using the generated class to the global namespace, create file my_pkg/include/my_pkg/plugin/MyVector3.after.h. These are example contents of the file that add a comparison operator based on the ordering of x coordinates of the vector:

bool operator<(const MyVector3& vec1, const MyVectro3& vec2)
{
   return vec1.x < vec2.x;
}

Note that you don't have to include the generated message header in this file (but you can if e.g. your IDE behaves better with it).

Full control on the message

If you need even more control, e.g. to include custom field or use custom data types, you can as well provide the full header of your message: instead of placing it in my_pkg/include/my_pkg/plugin/MyVector3.h, place it in my_pkg/include/my_pkg/MyVector3.h. Remember that it is then up to you to specify the full expected API compatible to the provided message definition, including message_traits, serialization, and message_operations. See Adapting a custom Vector3 for an example redefinition of the other necessary message headers components.

Wiki: roscpp/Overview/MessagesSerializationAndAdaptingTypes (last edited 2019-09-06 20:32:38 by MarcinPanek)