serialization.h
Go to the documentation of this file.
1 /*
2  * Copyright (C) 2009, Willow Garage, Inc.
3  *
4  * Redistribution and use in source and binary forms, with or without
5  * modification, are permitted provided that the following conditions are met:
6  * * Redistributions of source code must retain the above copyright notice,
7  * this list of conditions and the following disclaimer.
8  * * Redistributions in binary form must reproduce the above copyright
9  * notice, this list of conditions and the following disclaimer in the
10  * documentation and/or other materials provided with the distribution.
11  * * Neither the names of Willow Garage, Inc. nor the names of its
12  * contributors may be used to endorse or promote products derived from
13  * this software without specific prior written permission.
14  *
15  * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
16  * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
17  * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE
18  * ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE
19  * LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR
20  * CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF
21  * SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS
22  * INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN
23  * CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE)
24  * ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
25  * POSSIBILITY OF SUCH DAMAGE.
26  */
27 
28 #ifndef ROSCPP_SERIALIZATION_H
29 #define ROSCPP_SERIALIZATION_H
30 
32 
33 #include <ros/types.h>
34 #include <ros/time.h>
35 
36 #include "serialized_message.h"
37 #include "ros/message_traits.h"
39 #include "ros/exception.h"
40 #include "ros/datatypes.h"
41 
42 #include <vector>
43 #include <map>
44 
45 #include <boost/array.hpp>
46 #include <boost/call_traits.hpp>
47 #include <boost/utility/enable_if.hpp>
48 #include <boost/mpl/and.hpp>
49 #include <boost/mpl/or.hpp>
50 #include <boost/mpl/not.hpp>
51 
52 #include <cstring>
53 
54 #define ROS_NEW_SERIALIZATION_API 1
55 
73 #define ROS_DECLARE_ALLINONE_SERIALIZER \
74  template<typename Stream, typename T> \
75  inline static void write(Stream& stream, const T& t) \
76  { \
77  allInOne<Stream, const T&>(stream, t); \
78  } \
79  \
80  template<typename Stream, typename T> \
81  inline static void read(Stream& stream, T& t) \
82  { \
83  allInOne<Stream, T&>(stream, t); \
84  } \
85  \
86  template<typename T> \
87  inline static uint32_t serializedLength(const T& t) \
88  { \
89  LStream stream; \
90  allInOne<LStream, const T&>(stream, t); \
91  return stream.getLength(); \
92  }
93 
94 namespace ros
95 {
96 namespace serialization
97 {
98 namespace mt = message_traits;
99 namespace mpl = boost::mpl;
100 
102 {
103 public:
104  StreamOverrunException(const std::string& what)
105  : Exception(what)
106  {}
107 };
108 
110 
118 template<typename T>
120 {
124  template<typename Stream>
125  inline static void write(Stream& stream, typename boost::call_traits<T>::param_type t)
126  {
127  t.serialize(stream.getData(), 0);
128  }
129 
133  template<typename Stream>
134  inline static void read(Stream& stream, typename boost::call_traits<T>::reference t)
135  {
136  t.deserialize(stream.getData());
137  }
138 
142  inline static uint32_t serializedLength(typename boost::call_traits<T>::param_type t)
143  {
144  return t.serializationLength();
145  }
146 };
147 
151 template<typename T, typename Stream>
152 inline void serialize(Stream& stream, const T& t)
153 {
154  Serializer<T>::write(stream, t);
155 }
156 
160 template<typename T, typename Stream>
161 inline void deserialize(Stream& stream, T& t)
162 {
163  Serializer<T>::read(stream, t);
164 }
165 
169 template<typename T>
170 inline uint32_t serializationLength(const T& t)
171 {
173 }
174 
175 #define ROS_CREATE_SIMPLE_SERIALIZER(Type) \
176  template<> struct Serializer<Type> \
177  { \
178  template<typename Stream> inline static void write(Stream& stream, const Type v) \
179  { \
180  memcpy(stream.advance(sizeof(v)), &v, sizeof(v) ); \
181  } \
182  \
183  template<typename Stream> inline static void read(Stream& stream, Type& v) \
184  { \
185  memcpy(&v, stream.advance(sizeof(v)), sizeof(v) ); \
186  } \
187  \
188  inline static uint32_t serializedLength(const Type&) \
189  { \
190  return sizeof(Type); \
191  } \
192 };
193 
204 
205 
208 template<> struct Serializer<bool>
209 {
210  template<typename Stream> inline static void write(Stream& stream, const bool v)
211  {
212  uint8_t b = static_cast<uint8_t>(v);
213  memcpy(stream.advance(1), &b, 1 );
214  }
215 
216  template<typename Stream> inline static void read(Stream& stream, bool& v)
217  {
218  uint8_t b;
219  memcpy(&b, stream.advance(1), 1 );
220  v = static_cast<bool>(b);
221  }
222 
223  inline static uint32_t serializedLength(bool)
224  {
225  return 1;
226  }
227 };
228 
232 template<class ContainerAllocator>
233 struct Serializer<std::basic_string<char, std::char_traits<char>, ContainerAllocator> >
234 {
235  typedef std::basic_string<char, std::char_traits<char>, ContainerAllocator> StringType;
236 
237  template<typename Stream>
238  inline static void write(Stream& stream, const StringType& str)
239  {
240  size_t len = str.size();
241  stream.next(static_cast<uint32_t>(len));
242 
243  if (len > 0)
244  {
245  memcpy(stream.advance(static_cast<uint32_t>(len)), str.data(), len);
246  }
247  }
248 
249  template<typename Stream>
250  inline static void read(Stream& stream, StringType& str)
251  {
252  uint32_t len;
253  stream.next(len);
254  if (len > 0)
255  {
256  str = StringType(reinterpret_cast<char*>(stream.advance(len)), len);
257  }
258  else
259  {
260  str.clear();
261  }
262  }
263 
264  inline static uint32_t serializedLength(const StringType& str)
265  {
266  return 4 + static_cast<uint32_t>(str.size());
267  }
268 };
269 
273 template<>
275 {
276  template<typename Stream>
277  inline static void write(Stream& stream, const ros::Time& v)
278  {
279  stream.next(v.sec);
280  stream.next(v.nsec);
281  }
282 
283  template<typename Stream>
284  inline static void read(Stream& stream, ros::Time& v)
285  {
286  stream.next(v.sec);
287  stream.next(v.nsec);
288  }
289 
290  inline static uint32_t serializedLength(const ros::Time&)
291  {
292  return 8;
293  }
294 };
295 
299 template<>
301 {
302  template<typename Stream>
303  inline static void write(Stream& stream, const ros::Duration& v)
304  {
305  stream.next(v.sec);
306  stream.next(v.nsec);
307  }
308 
309  template<typename Stream>
310  inline static void read(Stream& stream, ros::Duration& v)
311  {
312  stream.next(v.sec);
313  stream.next(v.nsec);
314  }
315 
316  inline static uint32_t serializedLength(const ros::Duration&)
317  {
318  return 8;
319  }
320 };
321 
325 template<typename T, class ContainerAllocator, class Enabled = void>
327 {};
328 
332 template<typename T, class ContainerAllocator>
333 struct VectorSerializer<T, ContainerAllocator, typename boost::disable_if<mt::IsFixedSize<T> >::type >
334 {
335  typedef std::vector<T, typename ContainerAllocator::template rebind<T>::other> VecType;
336  typedef typename VecType::iterator IteratorType;
337  typedef typename VecType::const_iterator ConstIteratorType;
338 
339  template<typename Stream>
340  inline static void write(Stream& stream, const VecType& v)
341  {
342  stream.next(static_cast<uint32_t>(v.size()));
343  ConstIteratorType it = v.begin();
344  ConstIteratorType end = v.end();
345  for (; it != end; ++it)
346  {
347  stream.next(*it);
348  }
349  }
350 
351  template<typename Stream>
352  inline static void read(Stream& stream, VecType& v)
353  {
354  uint32_t len;
355  stream.next(len);
356  v.resize(len);
357  IteratorType it = v.begin();
358  IteratorType end = v.end();
359  for (; it != end; ++it)
360  {
361  stream.next(*it);
362  }
363  }
364 
365  inline static uint32_t serializedLength(const VecType& v)
366  {
367  uint32_t size = 4;
368  ConstIteratorType it = v.begin();
369  ConstIteratorType end = v.end();
370  for (; it != end; ++it)
371  {
372  size += serializationLength(*it);
373  }
374 
375  return size;
376  }
377 };
378 
382 template<typename T, class ContainerAllocator>
383 struct VectorSerializer<T, ContainerAllocator, typename boost::enable_if<mt::IsSimple<T> >::type >
384 {
385  typedef std::vector<T, typename ContainerAllocator::template rebind<T>::other> VecType;
386  typedef typename VecType::iterator IteratorType;
387  typedef typename VecType::const_iterator ConstIteratorType;
388 
389  template<typename Stream>
390  inline static void write(Stream& stream, const VecType& v)
391  {
392  uint32_t len = static_cast<uint32_t>(v.size());
393  stream.next(len);
394  if (!v.empty())
395  {
396  const uint32_t data_len = len * static_cast<uint32_t>(sizeof(T));
397  memcpy(stream.advance(data_len), &v.front(), data_len);
398  }
399  }
400 
401  template<typename Stream>
402  inline static void read(Stream& stream, VecType& v)
403  {
404  uint32_t len;
405  stream.next(len);
406  v.resize(len);
407 
408  if (len > 0)
409  {
410  const uint32_t data_len = static_cast<uint32_t>(sizeof(T)) * len;
411  memcpy(static_cast<void*>(&v.front()), stream.advance(data_len), data_len);
412  }
413  }
414 
415  inline static uint32_t serializedLength(const VecType& v)
416  {
417  return 4 + v.size() * static_cast<uint32_t>(sizeof(T));
418  }
419 };
420 
424 template<typename T, class ContainerAllocator>
425 struct VectorSerializer<T, ContainerAllocator, typename boost::enable_if<mpl::and_<mt::IsFixedSize<T>, mpl::not_<mt::IsSimple<T> > > >::type >
426 {
427  typedef std::vector<T, typename ContainerAllocator::template rebind<T>::other> VecType;
428  typedef typename VecType::iterator IteratorType;
429  typedef typename VecType::const_iterator ConstIteratorType;
430 
431  template<typename Stream>
432  inline static void write(Stream& stream, const VecType& v)
433  {
434  stream.next(static_cast<uint32_t>(v.size()));
435  ConstIteratorType it = v.begin();
436  ConstIteratorType end = v.end();
437  for (; it != end; ++it)
438  {
439  stream.next(*it);
440  }
441  }
442 
443  template<typename Stream>
444  inline static void read(Stream& stream, VecType& v)
445  {
446  uint32_t len;
447  stream.next(len);
448  v.resize(len);
449  IteratorType it = v.begin();
450  IteratorType end = v.end();
451  for (; it != end; ++it)
452  {
453  stream.next(*it);
454  }
455  }
456 
457  inline static uint32_t serializedLength(const VecType& v)
458  {
459  uint32_t size = 4;
460  if (!v.empty())
461  {
462  uint32_t len_each = serializationLength(v.front());
463  size += len_each * static_cast<uint32_t>(v.size());
464  }
465 
466  return size;
467  }
468 };
469 
473 template<typename T, class ContainerAllocator, typename Stream>
474 inline void serialize(Stream& stream, const std::vector<T, ContainerAllocator>& t)
475 {
477 }
478 
482 template<typename T, class ContainerAllocator, typename Stream>
483 inline void deserialize(Stream& stream, std::vector<T, ContainerAllocator>& t)
484 {
486 }
487 
491 template<typename T, class ContainerAllocator>
492 inline uint32_t serializationLength(const std::vector<T, ContainerAllocator>& t)
493 {
495 }
496 
500 template<typename T, size_t N, class Enabled = void>
502 {};
503 
507 template<typename T, size_t N>
508 struct ArraySerializer<T, N, typename boost::disable_if<mt::IsFixedSize<T> >::type>
509 {
510  typedef boost::array<T, N > ArrayType;
511  typedef typename ArrayType::iterator IteratorType;
512  typedef typename ArrayType::const_iterator ConstIteratorType;
513 
514  template<typename Stream>
515  inline static void write(Stream& stream, const ArrayType& v)
516  {
517  ConstIteratorType it = v.begin();
518  ConstIteratorType end = v.end();
519  for (; it != end; ++it)
520  {
521  stream.next(*it);
522  }
523  }
524 
525  template<typename Stream>
526  inline static void read(Stream& stream, ArrayType& v)
527  {
528  IteratorType it = v.begin();
529  IteratorType end = v.end();
530  for (; it != end; ++it)
531  {
532  stream.next(*it);
533  }
534  }
535 
536  inline static uint32_t serializedLength(const ArrayType& v)
537  {
538  uint32_t size = 0;
539  ConstIteratorType it = v.begin();
540  ConstIteratorType end = v.end();
541  for (; it != end; ++it)
542  {
543  size += serializationLength(*it);
544  }
545 
546  return size;
547  }
548 };
549 
553 template<typename T, size_t N>
554 struct ArraySerializer<T, N, typename boost::enable_if<mt::IsSimple<T> >::type>
555 {
556  typedef boost::array<T, N > ArrayType;
557  typedef typename ArrayType::iterator IteratorType;
558  typedef typename ArrayType::const_iterator ConstIteratorType;
559 
560  template<typename Stream>
561  inline static void write(Stream& stream, const ArrayType& v)
562  {
563  const uint32_t data_len = N * sizeof(T);
564  memcpy(stream.advance(data_len), &v.front(), data_len);
565  }
566 
567  template<typename Stream>
568  inline static void read(Stream& stream, ArrayType& v)
569  {
570  const uint32_t data_len = N * sizeof(T);
571  memcpy(&v.front(), stream.advance(data_len), data_len);
572  }
573 
574  inline static uint32_t serializedLength(const ArrayType&)
575  {
576  return N * sizeof(T);
577  }
578 };
579 
583 template<typename T, size_t N>
584 struct ArraySerializer<T, N, typename boost::enable_if<mpl::and_<mt::IsFixedSize<T>, mpl::not_<mt::IsSimple<T> > > >::type>
585 {
586  typedef boost::array<T, N > ArrayType;
587  typedef typename ArrayType::iterator IteratorType;
588  typedef typename ArrayType::const_iterator ConstIteratorType;
589 
590  template<typename Stream>
591  inline static void write(Stream& stream, const ArrayType& v)
592  {
593  ConstIteratorType it = v.begin();
594  ConstIteratorType end = v.end();
595  for (; it != end; ++it)
596  {
597  stream.next(*it);
598  }
599  }
600 
601  template<typename Stream>
602  inline static void read(Stream& stream, ArrayType& v)
603  {
604  IteratorType it = v.begin();
605  IteratorType end = v.end();
606  for (; it != end; ++it)
607  {
608  stream.next(*it);
609  }
610  }
611 
612  inline static uint32_t serializedLength(const ArrayType& v)
613  {
614  return serializationLength(v.front()) * N;
615  }
616 };
617 
621 template<typename T, size_t N, typename Stream>
622 inline void serialize(Stream& stream, const boost::array<T, N>& t)
623 {
624  ArraySerializer<T, N>::write(stream, t);
625 }
626 
630 template<typename T, size_t N, typename Stream>
631 inline void deserialize(Stream& stream, boost::array<T, N>& t)
632 {
633  ArraySerializer<T, N>::read(stream, t);
634 }
635 
639 template<typename T, size_t N>
640 inline uint32_t serializationLength(const boost::array<T, N>& t)
641 {
643 }
644 
648 namespace stream_types
649 {
651 {
655 };
656 }
658 
663 {
664  /*
665  * \brief Returns a pointer to the current position of the stream
666  */
667  inline uint8_t* getData() { return data_; }
673  ROS_FORCE_INLINE uint8_t* advance(uint32_t len)
674  {
675  uint8_t* old_data = data_;
676  data_ += len;
677  if (data_ > end_)
678  {
679  // Throwing directly here causes a significant speed hit due to the extra code generated
680  // for the throw statement
682  }
683  return old_data;
684  }
685 
689  inline uint32_t getLength() { return static_cast<uint32_t>(end_ - data_); }
690 
691 protected:
692  Stream(uint8_t* _data, uint32_t _count)
693  : data_(_data)
694  , end_(_data + _count)
695  {}
696 
697 private:
698  uint8_t* data_;
699  uint8_t* end_;
700 };
701 
706 {
707  static const StreamType stream_type = stream_types::Input;
708 
709  IStream(uint8_t* data, uint32_t count)
710  : Stream(data, count)
711  {}
712 
716  template<typename T>
718  {
719  deserialize(*this, t);
720  }
721 
722  template<typename T>
724  {
725  deserialize(*this, t);
726  return *this;
727  }
728 };
729 
734 {
735  static const StreamType stream_type = stream_types::Output;
736 
737  OStream(uint8_t* data, uint32_t count)
738  : Stream(data, count)
739  {}
740 
744  template<typename T>
745  ROS_FORCE_INLINE void next(const T& t)
746  {
747  serialize(*this, t);
748  }
749 
750  template<typename T>
752  {
753  serialize(*this, t);
754  return *this;
755  }
756 };
757 
765 {
766  static const StreamType stream_type = stream_types::Length;
767 
769  : count_(0)
770  {}
771 
775  template<typename T>
776  ROS_FORCE_INLINE void next(const T& t)
777  {
778  count_ += serializationLength(t);
779  }
780 
784  ROS_FORCE_INLINE uint32_t advance(uint32_t len)
785  {
786  uint32_t old = count_;
787  count_ += len;
788  return old;
789  }
790 
794  inline uint32_t getLength() { return count_; }
795 
796 private:
797  uint32_t count_;
798 };
799 
803 template<typename M>
804 inline SerializedMessage serializeMessage(const M& message)
805 {
807  uint32_t len = serializationLength(message);
808  m.num_bytes = len + 4;
809  m.buf.reset(new uint8_t[m.num_bytes]);
810 
811  OStream s(m.buf.get(), static_cast<uint32_t>(m.num_bytes));
812  serialize(s, static_cast<uint32_t>(m.num_bytes) - 4);
813  m.message_start = s.getData();
814  serialize(s, message);
815 
816  return m;
817 }
818 
822 template<typename M>
823 inline SerializedMessage serializeServiceResponse(bool ok, const M& message)
824 {
826 
827  if (ok)
828  {
829  uint32_t len = serializationLength(message);
830  m.num_bytes = len + 5;
831  m.buf.reset(new uint8_t[m.num_bytes]);
832 
833  OStream s(m.buf.get(), static_cast<uint32_t>(m.num_bytes));
834  serialize(s, static_cast<uint8_t>(ok));
835  serialize(s, static_cast<uint32_t>(m.num_bytes) - 5);
836  serialize(s, message);
837  }
838  else
839  {
840  uint32_t len = serializationLength(message);
841  m.num_bytes = len + 1;
842  m.buf.reset(new uint8_t[m.num_bytes]);
843 
844  OStream s(m.buf.get(), static_cast<uint32_t>(m.num_bytes));
845  serialize(s, static_cast<uint8_t>(ok));
846  serialize(s, message);
847  }
848 
849  return m;
850 }
851 
855 template<typename M>
856 inline void deserializeMessage(const SerializedMessage& m, M& message)
857 {
858  IStream s(m.message_start, static_cast<uint32_t>(m.num_bytes - (m.message_start - m.buf.get())));
859  deserialize(s, message);
860 }
861 
862 // Additional serialization traits
863 
864 template<typename M>
866 {
869 };
870 
875 template<typename M>
877 {
878  static void notify(const PreDeserializeParams<M>&) { }
879 };
880 
881 } // namespace serialization
882 
883 } // namespace ros
884 
885 #endif // ROSCPP_SERIALIZATION_H
static void write(Stream &stream, typename boost::call_traits< T >::param_type t)
Write an object to the stream. Normally the stream passed in here will be a ros::serialization::OStre...
static void notify(const PreDeserializeParams< M > &)
static void read(Stream &stream, ros::Time &v)
stream_types::StreamType StreamType
OStream(uint8_t *data, uint32_t count)
SerializedMessage serializeServiceResponse(bool ok, const M &message)
Serialize a service response.
static uint32_t serializedLength(typename boost::call_traits< T >::param_type t)
Determine the serialized length of an object.
Vector serializer. Default implementation does nothing.
static void write(Stream &stream, const ros::Duration &v)
static void read(Stream &stream, ros::Duration &v)
static void read(Stream &stream, bool &v)
void deserializeMessage(const SerializedMessage &m, M &message)
Deserialize a message. If includes_length is true, skips the first 4 bytes.
ROS_FORCE_INLINE void next(T &t)
Deserialize an item from this input stream.
ROS_FORCE_INLINE uint8_t * advance(uint32_t len)
Advances the stream, checking bounds, and returns a pointer to the position before it was advanced...
StreamOverrunException(const std::string &what)
uint32_t getLength()
Returns the amount of space left in the stream.
ROSCPP_SERIALIZATION_DECL void throwStreamOverrun()
std::basic_string< char, std::char_traits< char >, ContainerAllocator > StringType
void serialize(Stream &stream, const T &t)
Serialize an object. Stream here should normally be a ros::serialization::OStream.
#define ROSCPP_SERIALIZATION_DECL
called by the SubscriptionCallbackHelper after a message is instantiated but before that message is d...
ROS_FORCE_INLINE OStream & operator<<(const T &t)
uint32_t getLength()
Get the total length of this tream.
Templated serialization class. Default implementation provides backwards compatibility with old messa...
static void read(Stream &stream, typename boost::call_traits< T >::reference t)
Read an object from the stream. Normally the stream passed in here will be a ros::serialization::IStr...
SerializedMessage serializeMessage(const M &message)
Serialize a message.
#define ROS_CREATE_SIMPLE_SERIALIZER(Type)
static uint32_t serializedLength(bool)
ROS_FORCE_INLINE void next(const T &t)
Add the length of an item to this length stream.
ROS_FORCE_INLINE IStream & operator>>(T &t)
Stream base-class, provides common functionality for IStream and OStream.
uint32_t serializationLength(const T &t)
Determine the serialized length of an object.
boost::shared_array< uint8_t > buf
#define ROS_FORCE_INLINE
static void write(Stream &stream, const ros::Time &v)
ROS_FORCE_INLINE void next(const T &t)
Serialize an item to this output stream.
IStream(uint8_t *data, uint32_t count)
Stream(uint8_t *_data, uint32_t _count)
boost::shared_ptr< std::map< std::string, std::string > > connection_header
Array serializer, default implementation does nothing.
void deserialize(Stream &stream, T &t)
Deserialize an object. Stream here should normally be a ros::serialization::IStream.
static void write(Stream &stream, const bool v)
ROS_FORCE_INLINE uint32_t advance(uint32_t len)
increment the length by len
static uint32_t serializedLength(const ros::Duration &)
static uint32_t serializedLength(const ros::Time &)


roscpp_serialization
Author(s): Josh Faust
autogenerated on Mon Feb 28 2022 23:31:39