This is part 2 of the proposal, now that I have a working prototype. See roscpp/NewMessageAPIProposal for more information about goals/motivation.

Traits

Different from my original proposal, I've implemented traits as entirely struct-based so that implementing them is more uniform. function-style accessors are provided to make using them easier.

Message

namespace ros::message_traits

Required traits for advertise/subscribe

   1 template<typename M>
   2 struct MD5Sum
   3 {
   4   static const char* value();
   5   static const char* value(const M& m);
   6 };
   7 
   8 template<typename M>
   9 struct DataType
  10 {
  11   static const char* value();
  12   static const char* value(const M& m);
  13 };
  14 
  15 template<typename M>
  16 struct Definition
  17 {
  18   static const char* value();
  19   static const char* value(const M& m);
  20 };

For backwards compatibility, these default to returning the values of e.g. __s_getMD5Sum()/__getMD5Sum().

Optional Traits

template<typename M> struct IsSimple;

  • A "simple" message is one which, given a vector/array of them, can be memcpy'd directly. Note that due to the padding rules of various compilers you need to be very careful about marking a struct as simple. For simple struct A, A must be a POD type and sizeof(A) must equal the sum of the length of serialization for each of its members.

template<typename M> struct IsFixedSize;

  • A fixed-size message is one which is always the same size. Used to optimize determining the size of a vector/array of M.

template<typename M> struct HasHeader;

  • Tells whether or not M has a header.

To change this to true you simply specialize for your message and inherit from TrueType instead of FalseType.

   1 template<typename M>
   2 struct Header
   3 {
   4   static roslib::Header* pointer(M& m);
   5   static roslib::Header const* pointer(const M& m);
   6 };
  • Returns a pointer to the header in the message. By default this returns &m.header if HasHeader<M>::value is true, or NULL if false.

   1 template<typename M>
   2 struct FrameId
   3 {
   4   static std::string* pointer(M& m);
   5   static std::string const* pointer(const M& m);
   6   static std::string value(const M& m);
   7 };
  • Returns the frame id of the message, as pointer or value type as requested.

   1 template<typename M>
   2 struct TimeStamp
   3 {
   4   static std::string* pointer(M& m);
   5   static std::string const* pointer(const M& m);
   6   static std::string value(const M& m);
   7 };
  • Returns the timestamp of the message, as pointer or value type as requested.

IsSimple, IsFixedSize and HasHeader can be used at compile time. Their default implementation is:

   1 template<typename M> struct IsSimple : public FalseType {};

FalseType/TrueType provide a bool integral constant value and a type typedef to support use with boost mpl and enable_if

  • FalseType::value = false

  • FalseType::type = FalseType

  • TrueType::value = true

  • TrueType::type = TrueType

Function Accessors

Function

Return Value

md5sum<M>()

MD5Sum<M>::value()

md5sum<M>(const M& m)

MD5Sum<M>::value(m)

datatype<M>()

DataType<M>::value()

datatype<M>(const M& m)

DataType<M>::value(m)

definition<M>()

Definition<M>::value()

definition<M>(const M& m)

Definition<M>::value(m)

hasHeader<M>()

HasHeader<M>::value

isSimple<M>()

IsSimple<M>::value

isFixedSize<M>()

IsFixedSize<M>::value

header<M>(M& m)

Header<M>::pointer(m)

frameId<M>(M& m)

FrameId<M>::pointer(m)

timeStamp<M>(M& m)

TimeStamp<M>::pointer(m)

Service

namespace ros::service_traits

Service request/response classes are not really meant to be custom-defined, but it is possible. There are only two traits:

   1 template<typename M>
   2 struct MD5Sum
   3 {
   4   static const char* value();
   5   static const char* value(const M& m);
   6 };
   7 
   8 template<typename M>
   9 struct DataType
  10 {
  11   static const char* value();
  12   static const char* value(const M& m);
  13 };

Note that these are the service md5sum and datatype, not the request/response md5sum/datatypes. Their equivalents in the old API were __s_getServerMD5Sum()/__getServerMD5Sum() and __s_getServiceDataType/__getServiceDataType.

Accessors are also provided for these:

Function

Return Value

md5sum<M>()

MD5Sum<M>::value()

md5sum<M>(M& m)

MD5Sum<M>::value(m)

datatype<M>()

DataType<M>::value()

datatype<M>(M& m)

DataType<M>::value(m)

Serialization

namespace ros::serialization

Serialization API

To use the serialization API there are 3 functions and 3 corresponding stream classes to know about:

  • template<typename T, typename Stream> inline void serialize(Stream& stream, const T& t)

  • template<typename T, typename Stream> inline void deserialize(Stream& stream, T& t)

  • template<typename T, typename Stream> inline void serializationLength(Stream& stream, const T& t)

  • struct OStream -- for use with serialize()

    • OStream(uint8_t* data, uint32_t count)

    • uint8_t* getData()

      • Returns a pointer to the current position in the stream
    • uint8_t* advance(uint32_t len)

      • Returns a pointer to the current position in the stream and advances the stream by len. If len would've put the stream past its end, throws a BufferOverrunException

    • template<typename T> void next(const T& t)

      • calls serialize(*this, t)

  • struct IStream -- for use with deserialize()

    • IStream(uint8_t* data, uint32_t count)

    • uint8_t* getData()

      • Returns a pointer to the current position in the stream
    • uint8_t* advance(uint32_t len)

      • Returns a pointer to the current position in the stream and advances the stream by len. If len would've put the stream past its end, throws a BufferOverrunException

    • template<typename T> void next(T& t)

      • calls deserialize(*this, t)

Extra Helper Functions

  • template<typename M> inline SerializedMessage serializeMessage(const M& message)

    • Serializes a message, returning a SerializedMessage struct (a shared_ptr<uint8_t> buf + uint32_t num_bytes)

  • template<typename M> inline void deserializeMessage(const SerializedMessage& m, M& message, bool includes_length = false)

    • Deserializes a message. If includes_length is true, it starts 4-bytes into the buffer

  • template<typename M> inline uint32_t serializationLength(const M& m)

    • Returns the serialization length of m. Makes code that would normally have to declare an LStream and pass it in shorter.

Serializer Specialization

To define serialization for a type you must define a specialization of the 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   template<typename Stream>
   9   inline static void_t serializedLength(Stream& stream, typename boost::call_traits<T>::param_type t);
  10 };

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.

Generated Messages

The message generators generate a message that looks something like this (taken directly from roslib/Header.h):

   1 template <template <typename T> class Allocator>
   2 struct Header_ 
   3 {
   4   Header_()
   5   :   seq(0)
   6   ,   stamp()
   7   ,   frame_id()
   8   {
   9   }
  10 
  11   typedef uint32_t _seq_type;
  12   uint32_t seq;
  13 
  14   typedef ros::Time _stamp_type;
  15   ros::Time stamp;
  16 
  17   typedef std::basic_string<char, std::char_traits<char>, Allocator<char> >  _frame_id_type;
  18   std::basic_string<char, std::char_traits<char>, Allocator<char> >  frame_id;
  19 
  20 
  21   typedef boost::shared_ptr<roslib::Header_<Allocator> > Ptr;
  22   typedef boost::shared_ptr<roslib::Header_<Allocator>  const> ConstPtr;
  23 }; // struct Header
  24 typedef roslib::Header_<std::allocator> Header;
  25 
  26 typedef boost::shared_ptr<roslib::Header> HeaderPtr;
  27 typedef boost::shared_ptr<roslib::Header const> HeaderConstPtr;

Things to note:

  • It defines a struct Header_ which is templated on the allocator type

  • It typedefs Header_<std::allocator> to Header, providing the default message type

The message generators also provide some extra compile-time-available md5sum values in their MD5Sum<> specialization:

  static const uint64_t static_value1 = 0x2176decaecbce78aULL;
  static const uint64_t static_value2 = 0xbc3b96ef049fabedULL;

This is so you can cause compile-time errors when the md5sum of a message changes.

Retrieving the Connection Header

Since there's no longer necessarily a ros::Message base class, retrieving the connection header requires some other way of doing things than msg->__connection_header.

Instead, you can now subscribe using the ros::MessageEvent<M> class, e.g.:

   1 void callback(const ros::MessageEvent<MyMsg>& event)
   2 {
   3   const MyMsgConstPtr& msg = event.getMessage();
   4   ros::M_string& conn_header = event.getConnectionHeader();
   5 }

ros::MessageEvent currently only has two methods:

  • const boost::shared_ptr<M const>& getMessage()

  • ros::M_string& getConnectionHeader()

There is also a corresponding ros::ServiceEvent<Req, Res> class.

Examples

Adapting a custom type

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

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

Serializing a message to a buffer

NOTE: this function already exists as a helper, but it's a good example.

   1 template<typename M>
   2 inline SerializedMessage serializeMessage(const M& message)
   3 {
   4   SerializedMessage m;
   5   m.num_bytes = serializationLength(message);
   6   m.buf.reset(new uint8_t[m.num_bytes]);
   7 
   8   OStream s(m.buf.get(), (uint32_t)m.num_bytes);
   9   serialize(s, (uint32_t)m.num_bytes);
  10   serialize(s, message);
  11 
  12   return m;
  13 }

Deserializing a message from a buffer

NOTE: this function already exists as a helper, but it's good as an example.

   1 template<typename M>
   2 inline void deserializeMessage(const SerializedMessage& m, M& message)
   3 {
   4   IStream s(m.buf.get(), m.num_bytes);
   5   deserialize(s, message);
   6 }

Performance (Speed and Compiled Code Size)

One of my biggest concerns with templated serialization was ensuring serialization/deserialization speed ended up at least as good (or at least very close to) the old message generators. One thing the new API does that the old did not, is bounds-check the buffers (preventing overruns), which can cause a very slight performance hit depending on the compiler.

Code size was also a large concern, since code bloat can both make code slower and use more RAM (not much of an issue with 24 gigs per robot, but certainly an issue for those running on more-embedded platforms)

I've used the test_roscpp_serialization_perf package to test the difference in serialization/deserialization. While this is not a comprehensive test, it does provide a pretty good worst-case test, since it uses a structure exactly like sensor_msgs/PointCloud, serializing and deserializing 1,000,000 point messages.

Each test is done with the old generators, the new ones, and the new ones with the backwards-compatibility removed (no ros::Message base class, no Message::serialize()/etc. virtual methods generated for the struct).

Macbook Pro, OSX 10.5, gcc version 4.0.1 (Apple Inc. build 5493)

Baseline (old generators)

With Backcompat

No Backcompat

Serialization (seconds)

0.019130

0.018485

0.014914

Deserialization (seconds)

0.109823

0.112022

0.053462

Executable Size (bytes)

52324

61964

42180

4-core Intel Core i7 950, gcc version 4.4.1 (Ubuntu 4.4.1-4ubuntu8)

Baseline (old generators)

With Backcompat

No Backcompat

Serialization (seconds)

0.007251

0.006738

0.006731

Deserialization (seconds)

0.036333

0.035975

0.009559

Executable Size (bytes)

49675

59225

35351

Performance Conclusions

I think the numbers mostly speak for themselves. Currently the new API is somewhere from almost exactly the same speed to slightly faster with slightly larger executable size, and once we can remove the legacy aspects will be faster in all cases (in some cases almost 400% faster), with smaller executable size.

Questions

  1. In order to actually support types that do not derive from ros::Message I had to change the API of ros::SubscriptionMessageHelper and ros::ServiceMessageHelper. This will likely break rosoct and rosjava, but I should be able to easily fix that with conditional compilation (say, a ROS_NEW_SERIALIZATION_API define?) before the release goes out. These two classes are explicitly marked as not having a stable API, so is this OK for ROS 1.1/1.2? Or should we hold off on actually supporting non-Message-derived classes until 2.0?

  2. Should we support templating of string/vector/array types as well? I'm inclined to say no, at least for now.
  3. allinone is a silly-sounding name. Suggestions?
  4. Should we provide overloaded new/delete for generated messages, which use their allocator type? Or possible a boost::shared_ptr<M> ros::allocateMessage<M>() method that does the same?

  5. How do we want to pass the connection header along in the callback? I'm thinking something like const MessageEvent<M>& as the callback type, where you can do event.getMessage(), event.getConnectionHeader(), etc.

Wiki: roscpp/NewMessageAPIProposal2 (last edited 2010-03-10 02:44:58 by JoshFaust)