00001
00002
00003
00004
00005
00006
00007
00008
00009
00010
00011
00012
00013
00014
00015
00016
00017
00018
00019
00020
00021
00022
00023
00024
00025
00026
00027
00028 #ifndef ROSCPP_SERIALIZATION_H
00029 #define ROSCPP_SERIALIZATION_H
00030
00031 #include "roscpp_serialization_macros.h"
00032
00033 #include <ros/types.h>
00034 #include <ros/time.h>
00035
00036 #include "serialized_message.h"
00037 #include "ros/message_traits.h"
00038 #include "ros/builtin_message_traits.h"
00039 #include "ros/exception.h"
00040
00041 #include <vector>
00042
00043 #include <boost/array.hpp>
00044 #include <boost/call_traits.hpp>
00045 #include <boost/utility/enable_if.hpp>
00046 #include <boost/mpl/and.hpp>
00047 #include <boost/mpl/or.hpp>
00048 #include <boost/mpl/not.hpp>
00049
00050 #include <cstring>
00051
00052 #define ROS_NEW_SERIALIZATION_API 1
00053
00071 #define ROS_DECLARE_ALLINONE_SERIALIZER \
00072 template<typename Stream, typename T> \
00073 inline static void write(Stream& stream, const T& t) \
00074 { \
00075 allInOne<Stream, const T&>(stream, t); \
00076 } \
00077 \
00078 template<typename Stream, typename T> \
00079 inline static void read(Stream& stream, T& t) \
00080 { \
00081 allInOne<Stream, T&>(stream, t); \
00082 } \
00083 \
00084 template<typename T> \
00085 inline static uint32_t serializedLength(const T& t) \
00086 { \
00087 LStream stream; \
00088 allInOne<LStream, const T&>(stream, t); \
00089 return stream.getLength(); \
00090 }
00091
00092 namespace ros
00093 {
00094 namespace serialization
00095 {
00096 namespace mt = message_traits;
00097 namespace mpl = boost::mpl;
00098
00099 class ROSCPP_SERIALIZATION_DECL StreamOverrunException : public ros::Exception
00100 {
00101 public:
00102 StreamOverrunException(const std::string& what)
00103 : Exception(what)
00104 {}
00105 };
00106
00107 ROSCPP_SERIALIZATION_DECL void throwStreamOverrun();
00108
00116 template<typename T>
00117 struct Serializer
00118 {
00122 template<typename Stream>
00123 inline static void write(Stream& stream, typename boost::call_traits<T>::param_type t)
00124 {
00125 t.serialize(stream.getData(), 0);
00126 }
00127
00131 template<typename Stream>
00132 inline static void read(Stream& stream, typename boost::call_traits<T>::reference t)
00133 {
00134 t.deserialize(stream.getData());
00135 }
00136
00140 inline static uint32_t serializedLength(typename boost::call_traits<T>::param_type t)
00141 {
00142 return t.serializationLength();
00143 }
00144 };
00145
00149 template<typename T, typename Stream>
00150 inline void serialize(Stream& stream, const T& t)
00151 {
00152 Serializer<T>::write(stream, t);
00153 }
00154
00158 template<typename T, typename Stream>
00159 inline void deserialize(Stream& stream, T& t)
00160 {
00161 Serializer<T>::read(stream, t);
00162 }
00163
00167 template<typename T>
00168 inline uint32_t serializationLength(const T& t)
00169 {
00170 return Serializer<T>::serializedLength(t);
00171 }
00172
00173 #define ROS_CREATE_SIMPLE_SERIALIZER(Type) \
00174 template<> struct Serializer<Type> \
00175 { \
00176 template<typename Stream> inline static void write(Stream& stream, const Type v) \
00177 { \
00178 *reinterpret_cast<Type*>(stream.advance(sizeof(v))) = v; \
00179 } \
00180 \
00181 template<typename Stream> inline static void read(Stream& stream, Type& v) \
00182 { \
00183 v = *reinterpret_cast<Type*>(stream.advance(sizeof(v))); \
00184 } \
00185 \
00186 inline static uint32_t serializedLength(const Type&) \
00187 { \
00188 return sizeof(Type); \
00189 } \
00190 };
00191
00192 #define ROS_CREATE_SIMPLE_SERIALIZER_ARM(Type) \
00193 template<> struct Serializer<Type> \
00194 { \
00195 template<typename Stream> inline static void write(Stream& stream, const Type v) \
00196 { \
00197 memcpy(stream.advance(sizeof(v)), &v, sizeof(v) ); \
00198 } \
00199 \
00200 template<typename Stream> inline static void read(Stream& stream, Type& v) \
00201 { \
00202 memcpy(&v, stream.advance(sizeof(v)), sizeof(v) ); \
00203 } \
00204 \
00205 inline static uint32_t serializedLength(const Type t) \
00206 { \
00207 return sizeof(Type); \
00208 } \
00209 };
00210
00211 #if defined(__arm__) || defined(__arm)
00212 ROS_CREATE_SIMPLE_SERIALIZER_ARM(uint8_t);
00213 ROS_CREATE_SIMPLE_SERIALIZER_ARM(int8_t);
00214 ROS_CREATE_SIMPLE_SERIALIZER_ARM(uint16_t);
00215 ROS_CREATE_SIMPLE_SERIALIZER_ARM(int16_t);
00216 ROS_CREATE_SIMPLE_SERIALIZER_ARM(uint32_t);
00217 ROS_CREATE_SIMPLE_SERIALIZER_ARM(int32_t);
00218 ROS_CREATE_SIMPLE_SERIALIZER_ARM(uint64_t);
00219 ROS_CREATE_SIMPLE_SERIALIZER_ARM(int64_t);
00220 ROS_CREATE_SIMPLE_SERIALIZER_ARM(float);
00221 ROS_CREATE_SIMPLE_SERIALIZER_ARM(double);
00222 #else
00223 ROS_CREATE_SIMPLE_SERIALIZER(uint8_t);
00224 ROS_CREATE_SIMPLE_SERIALIZER(int8_t);
00225 ROS_CREATE_SIMPLE_SERIALIZER(uint16_t);
00226 ROS_CREATE_SIMPLE_SERIALIZER(int16_t);
00227 ROS_CREATE_SIMPLE_SERIALIZER(uint32_t);
00228 ROS_CREATE_SIMPLE_SERIALIZER(int32_t);
00229 ROS_CREATE_SIMPLE_SERIALIZER(uint64_t);
00230 ROS_CREATE_SIMPLE_SERIALIZER(int64_t);
00231 ROS_CREATE_SIMPLE_SERIALIZER(float);
00232 ROS_CREATE_SIMPLE_SERIALIZER(double);
00233 #endif
00234
00238 template<> struct Serializer<bool>
00239 {
00240 template<typename Stream> inline static void write(Stream& stream, const bool v)
00241 {
00242 uint8_t b = (uint8_t)v;
00243 #if defined(__arm__) || defined(__arm)
00244 memcpy(stream.advance(sizeof(1)), &b, 1 );
00245 #else
00246 *reinterpret_cast<uint8_t*>(stream.advance(1)) = b;
00247 #endif
00248 }
00249
00250 template<typename Stream> inline static void read(Stream& stream, bool& v)
00251 {
00252 uint8_t b;
00253 #if defined(__arm__) || defined(__arm)
00254 memcpy(&b, stream.advance(sizeof(1)), 1 );
00255 #else
00256 b = *reinterpret_cast<uint8_t*>(stream.advance(1));
00257 #endif
00258 v = (bool)b;
00259 }
00260
00261 inline static uint32_t serializedLength(bool)
00262 {
00263 return 1;
00264 }
00265 };
00266
00270 template<class ContainerAllocator>
00271 struct Serializer<std::basic_string<char, std::char_traits<char>, ContainerAllocator> >
00272 {
00273 typedef std::basic_string<char, std::char_traits<char>, ContainerAllocator> StringType;
00274
00275 template<typename Stream>
00276 inline static void write(Stream& stream, const StringType& str)
00277 {
00278 size_t len = str.size();
00279 stream.next((uint32_t)len);
00280
00281 if (len > 0)
00282 {
00283 memcpy(stream.advance((uint32_t)len), str.data(), len);
00284 }
00285 }
00286
00287 template<typename Stream>
00288 inline static void read(Stream& stream, StringType& str)
00289 {
00290 uint32_t len;
00291 stream.next(len);
00292 if (len > 0)
00293 {
00294 str = StringType((char*)stream.advance(len), len);
00295 }
00296 else
00297 {
00298 str.clear();
00299 }
00300 }
00301
00302 inline static uint32_t serializedLength(const StringType& str)
00303 {
00304 return 4 + (uint32_t)str.size();
00305 }
00306 };
00307
00311 template<>
00312 struct Serializer<ros::Time>
00313 {
00314 template<typename Stream>
00315 inline static void write(Stream& stream, const ros::Time& v)
00316 {
00317 stream.next(v.sec);
00318 stream.next(v.nsec);
00319 }
00320
00321 template<typename Stream>
00322 inline static void read(Stream& stream, ros::Time& v)
00323 {
00324 stream.next(v.sec);
00325 stream.next(v.nsec);
00326 }
00327
00328 inline static uint32_t serializedLength(const ros::Time&)
00329 {
00330 return 8;
00331 }
00332 };
00333
00337 template<>
00338 struct Serializer<ros::Duration>
00339 {
00340 template<typename Stream>
00341 inline static void write(Stream& stream, const ros::Duration& v)
00342 {
00343 stream.next(v.sec);
00344 stream.next(v.nsec);
00345 }
00346
00347 template<typename Stream>
00348 inline static void read(Stream& stream, ros::Duration& v)
00349 {
00350 stream.next(v.sec);
00351 stream.next(v.nsec);
00352 }
00353
00354 inline static uint32_t serializedLength(const ros::Duration&)
00355 {
00356 return 8;
00357 }
00358 };
00359
00363 template<typename T, class ContainerAllocator, class Enabled = void>
00364 struct VectorSerializer
00365 {};
00366
00370 template<typename T, class ContainerAllocator>
00371 struct VectorSerializer<T, ContainerAllocator, typename boost::disable_if<mt::IsFixedSize<T> >::type >
00372 {
00373 typedef std::vector<T, typename ContainerAllocator::template rebind<T>::other> VecType;
00374 typedef typename VecType::iterator IteratorType;
00375 typedef typename VecType::const_iterator ConstIteratorType;
00376
00377 template<typename Stream>
00378 inline static void write(Stream& stream, const VecType& v)
00379 {
00380 stream.next((uint32_t)v.size());
00381 ConstIteratorType it = v.begin();
00382 ConstIteratorType end = v.end();
00383 for (; it != end; ++it)
00384 {
00385 stream.next(*it);
00386 }
00387 }
00388
00389 template<typename Stream>
00390 inline static void read(Stream& stream, VecType& v)
00391 {
00392 uint32_t len;
00393 stream.next(len);
00394 v.resize(len);
00395 IteratorType it = v.begin();
00396 IteratorType end = v.end();
00397 for (; it != end; ++it)
00398 {
00399 stream.next(*it);
00400 }
00401 }
00402
00403 inline static uint32_t serializedLength(const VecType& v)
00404 {
00405 uint32_t size = 4;
00406 ConstIteratorType it = v.begin();
00407 ConstIteratorType end = v.end();
00408 for (; it != end; ++it)
00409 {
00410 size += serializationLength(*it);
00411 }
00412
00413 return size;
00414 }
00415 };
00416
00420 template<typename T, class ContainerAllocator>
00421 struct VectorSerializer<T, ContainerAllocator, typename boost::enable_if<mt::IsSimple<T> >::type >
00422 {
00423 typedef std::vector<T, typename ContainerAllocator::template rebind<T>::other> VecType;
00424 typedef typename VecType::iterator IteratorType;
00425 typedef typename VecType::const_iterator ConstIteratorType;
00426
00427 template<typename Stream>
00428 inline static void write(Stream& stream, const VecType& v)
00429 {
00430 uint32_t len = (uint32_t)v.size();
00431 stream.next(len);
00432 if (!v.empty())
00433 {
00434 const uint32_t data_len = len * (uint32_t)sizeof(T);
00435 memcpy(stream.advance(data_len), &v.front(), data_len);
00436 }
00437 }
00438
00439 template<typename Stream>
00440 inline static void read(Stream& stream, VecType& v)
00441 {
00442 uint32_t len;
00443 stream.next(len);
00444 v.resize(len);
00445
00446 if (len > 0)
00447 {
00448 const uint32_t data_len = (uint32_t)sizeof(T) * len;
00449 memcpy(&v.front(), stream.advance(data_len), data_len);
00450 }
00451 }
00452
00453 inline static uint32_t serializedLength(const VecType& v)
00454 {
00455 return 4 + v.size() * (uint32_t)sizeof(T);
00456 }
00457 };
00458
00462 template<typename T, class ContainerAllocator>
00463 struct VectorSerializer<T, ContainerAllocator, typename boost::enable_if<mpl::and_<mt::IsFixedSize<T>, mpl::not_<mt::IsSimple<T> > > >::type >
00464 {
00465 typedef std::vector<T, typename ContainerAllocator::template rebind<T>::other> VecType;
00466 typedef typename VecType::iterator IteratorType;
00467 typedef typename VecType::const_iterator ConstIteratorType;
00468
00469 template<typename Stream>
00470 inline static void write(Stream& stream, const VecType& v)
00471 {
00472 stream.next((uint32_t)v.size());
00473 ConstIteratorType it = v.begin();
00474 ConstIteratorType end = v.end();
00475 for (; it != end; ++it)
00476 {
00477 stream.next(*it);
00478 }
00479 }
00480
00481 template<typename Stream>
00482 inline static void read(Stream& stream, VecType& v)
00483 {
00484 uint32_t len;
00485 stream.next(len);
00486 v.resize(len);
00487 IteratorType it = v.begin();
00488 IteratorType end = v.end();
00489 for (; it != end; ++it)
00490 {
00491 stream.next(*it);
00492 }
00493 }
00494
00495 inline static uint32_t serializedLength(const VecType& v)
00496 {
00497 uint32_t size = 4;
00498 if (!v.empty())
00499 {
00500 uint32_t len_each = serializationLength(v.front());
00501 size += len_each * (uint32_t)v.size();
00502 }
00503
00504 return size;
00505 }
00506 };
00507
00511 template<typename T, class ContainerAllocator, typename Stream>
00512 inline void serialize(Stream& stream, const std::vector<T, ContainerAllocator>& t)
00513 {
00514 VectorSerializer<T, ContainerAllocator>::write(stream, t);
00515 }
00516
00520 template<typename T, class ContainerAllocator, typename Stream>
00521 inline void deserialize(Stream& stream, std::vector<T, ContainerAllocator>& t)
00522 {
00523 VectorSerializer<T, ContainerAllocator>::read(stream, t);
00524 }
00525
00529 template<typename T, class ContainerAllocator>
00530 inline uint32_t serializationLength(const std::vector<T, ContainerAllocator>& t)
00531 {
00532 return VectorSerializer<T, ContainerAllocator>::serializedLength(t);
00533 }
00534
00538 template<typename T, size_t N, class Enabled = void>
00539 struct ArraySerializer
00540 {};
00541
00545 template<typename T, size_t N>
00546 struct ArraySerializer<T, N, typename boost::disable_if<mt::IsFixedSize<T> >::type>
00547 {
00548 typedef boost::array<T, N > ArrayType;
00549 typedef typename ArrayType::iterator IteratorType;
00550 typedef typename ArrayType::const_iterator ConstIteratorType;
00551
00552 template<typename Stream>
00553 inline static void write(Stream& stream, const ArrayType& v)
00554 {
00555 ConstIteratorType it = v.begin();
00556 ConstIteratorType end = v.end();
00557 for (; it != end; ++it)
00558 {
00559 stream.next(*it);
00560 }
00561 }
00562
00563 template<typename Stream>
00564 inline static void read(Stream& stream, ArrayType& v)
00565 {
00566 IteratorType it = v.begin();
00567 IteratorType end = v.end();
00568 for (; it != end; ++it)
00569 {
00570 stream.next(*it);
00571 }
00572 }
00573
00574 inline static uint32_t serializedLength(const ArrayType& v)
00575 {
00576 uint32_t size = 0;
00577 ConstIteratorType it = v.begin();
00578 ConstIteratorType end = v.end();
00579 for (; it != end; ++it)
00580 {
00581 size += serializationLength(*it);
00582 }
00583
00584 return size;
00585 }
00586 };
00587
00591 template<typename T, size_t N>
00592 struct ArraySerializer<T, N, typename boost::enable_if<mt::IsSimple<T> >::type>
00593 {
00594 typedef boost::array<T, N > ArrayType;
00595 typedef typename ArrayType::iterator IteratorType;
00596 typedef typename ArrayType::const_iterator ConstIteratorType;
00597
00598 template<typename Stream>
00599 inline static void write(Stream& stream, const ArrayType& v)
00600 {
00601 const uint32_t data_len = N * sizeof(T);
00602 memcpy(stream.advance(data_len), &v.front(), data_len);
00603 }
00604
00605 template<typename Stream>
00606 inline static void read(Stream& stream, ArrayType& v)
00607 {
00608 const uint32_t data_len = N * sizeof(T);
00609 memcpy(&v.front(), stream.advance(data_len), data_len);
00610 }
00611
00612 inline static uint32_t serializedLength(const ArrayType&)
00613 {
00614 return N * sizeof(T);
00615 }
00616 };
00617
00621 template<typename T, size_t N>
00622 struct ArraySerializer<T, N, typename boost::enable_if<mpl::and_<mt::IsFixedSize<T>, mpl::not_<mt::IsSimple<T> > > >::type>
00623 {
00624 typedef boost::array<T, N > ArrayType;
00625 typedef typename ArrayType::iterator IteratorType;
00626 typedef typename ArrayType::const_iterator ConstIteratorType;
00627
00628 template<typename Stream>
00629 inline static void write(Stream& stream, const ArrayType& v)
00630 {
00631 ConstIteratorType it = v.begin();
00632 ConstIteratorType end = v.end();
00633 for (; it != end; ++it)
00634 {
00635 stream.next(*it);
00636 }
00637 }
00638
00639 template<typename Stream>
00640 inline static void read(Stream& stream, ArrayType& v)
00641 {
00642 IteratorType it = v.begin();
00643 IteratorType end = v.end();
00644 for (; it != end; ++it)
00645 {
00646 stream.next(*it);
00647 }
00648 }
00649
00650 inline static uint32_t serializedLength(const ArrayType& v)
00651 {
00652 return serializationLength(v.front()) * N;
00653 }
00654 };
00655
00659 template<typename T, size_t N, typename Stream>
00660 inline void serialize(Stream& stream, const boost::array<T, N>& t)
00661 {
00662 ArraySerializer<T, N>::write(stream, t);
00663 }
00664
00668 template<typename T, size_t N, typename Stream>
00669 inline void deserialize(Stream& stream, boost::array<T, N>& t)
00670 {
00671 ArraySerializer<T, N>::read(stream, t);
00672 }
00673
00677 template<typename T, size_t N>
00678 inline uint32_t serializationLength(const boost::array<T, N>& t)
00679 {
00680 return ArraySerializer<T, N>::serializedLength(t);
00681 }
00682
00686 namespace stream_types
00687 {
00688 enum StreamType
00689 {
00690 Input,
00691 Output,
00692 Length
00693 };
00694 }
00695 typedef stream_types::StreamType StreamType;
00696
00700 struct ROSCPP_SERIALIZATION_DECL Stream
00701 {
00702
00703
00704
00705 inline uint8_t* getData() { return data_; }
00711 ROS_FORCE_INLINE uint8_t* advance(uint32_t len)
00712 {
00713 uint8_t* old_data = data_;
00714 data_ += len;
00715 if (data_ > end_)
00716 {
00717
00718
00719 throwStreamOverrun();
00720 }
00721 return old_data;
00722 }
00723
00727 inline uint32_t getLength() { return (uint32_t)(end_ - data_); }
00728
00729 protected:
00730 Stream(uint8_t* _data, uint32_t _count)
00731 : data_(_data)
00732 , end_(_data + _count)
00733 {}
00734
00735 private:
00736 uint8_t* data_;
00737 uint8_t* end_;
00738 };
00739
00743 struct ROSCPP_SERIALIZATION_DECL IStream : public Stream
00744 {
00745 static const StreamType stream_type = stream_types::Input;
00746
00747 IStream(uint8_t* data, uint32_t count)
00748 : Stream(data, count)
00749 {}
00750
00754 template<typename T>
00755 ROS_FORCE_INLINE void next(T& t)
00756 {
00757 deserialize(*this, t);
00758 }
00759
00760 template<typename T>
00761 ROS_FORCE_INLINE IStream& operator>>(T& t)
00762 {
00763 deserialize(*this, t);
00764 return *this;
00765 }
00766 };
00767
00771 struct ROSCPP_SERIALIZATION_DECL OStream : public Stream
00772 {
00773 static const StreamType stream_type = stream_types::Output;
00774
00775 OStream(uint8_t* data, uint32_t count)
00776 : Stream(data, count)
00777 {}
00778
00782 template<typename T>
00783 ROS_FORCE_INLINE void next(const T& t)
00784 {
00785 serialize(*this, t);
00786 }
00787
00788 template<typename T>
00789 ROS_FORCE_INLINE OStream& operator<<(const T& t)
00790 {
00791 serialize(*this, t);
00792 return *this;
00793 }
00794 };
00795
00796
00803 struct ROSCPP_SERIALIZATION_DECL LStream
00804 {
00805 static const StreamType stream_type = stream_types::Length;
00806
00807 LStream()
00808 : count_(0)
00809 {}
00810
00814 template<typename T>
00815 ROS_FORCE_INLINE void next(const T& t)
00816 {
00817 count_ += serializationLength(t);
00818 }
00819
00823 ROS_FORCE_INLINE uint32_t advance(uint32_t len)
00824 {
00825 uint32_t old = count_;
00826 count_ += len;
00827 return old;
00828 }
00829
00833 inline uint32_t getLength() { return count_; }
00834
00835 private:
00836 uint32_t count_;
00837 };
00838
00842 template<typename M>
00843 inline SerializedMessage serializeMessage(const M& message)
00844 {
00845 SerializedMessage m;
00846 uint32_t len = serializationLength(message);
00847 m.num_bytes = len + 4;
00848 m.buf.reset(new uint8_t[m.num_bytes]);
00849
00850 OStream s(m.buf.get(), (uint32_t)m.num_bytes);
00851 serialize(s, (uint32_t)m.num_bytes - 4);
00852 m.message_start = s.getData();
00853 serialize(s, message);
00854
00855 return m;
00856 }
00857
00861 template<typename M>
00862 inline SerializedMessage serializeServiceResponse(bool ok, const M& message)
00863 {
00864 SerializedMessage m;
00865
00866 if (ok)
00867 {
00868 uint32_t len = serializationLength(message);
00869 m.num_bytes = len + 5;
00870 m.buf.reset(new uint8_t[m.num_bytes]);
00871
00872 OStream s(m.buf.get(), (uint32_t)m.num_bytes);
00873 serialize(s, (uint8_t)ok);
00874 serialize(s, (uint32_t)m.num_bytes - 5);
00875 serialize(s, message);
00876 }
00877 else
00878 {
00879 uint32_t len = serializationLength(message);
00880 m.num_bytes = len + 1;
00881 m.buf.reset(new uint8_t[m.num_bytes]);
00882
00883 OStream s(m.buf.get(), (uint32_t)m.num_bytes);
00884 serialize(s, (uint8_t)ok);
00885 serialize(s, message);
00886 }
00887
00888 return m;
00889 }
00890
00894 template<typename M>
00895 inline void deserializeMessage(const SerializedMessage& m, M& message)
00896 {
00897 IStream s(m.message_start, m.num_bytes - (m.message_start - m.buf.get()));
00898 deserialize(s, message);
00899 }
00900
00901 }
00902 }
00903
00904 #endif // ROSCPP_SERIALIZATION_H