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 | 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 

Wiki: roscpp/Overview/MessagesSerializationAndAdaptingTypes (last edited 2011-07-25 17:43:11 by BhaskaraMarthi)