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
00029
00030
00031
00032
00033
00034
00035 #ifndef STD_MSGS_VECTOR_MULTI_ARRAY_ADAPTER_H
00036 #define STD_MSGS_VECTOR_MULTI_ARRAY_ADAPTER_H
00037
00038 #include <std_msgs/Float32MultiArray.h>
00039 #include <std_msgs/Float64MultiArray.h>
00040 #include <std_msgs/Int16MultiArray.h>
00041 #include <std_msgs/Int32MultiArray.h>
00042 #include <std_msgs/Int64MultiArray.h>
00043 #include <std_msgs/Int8MultiArray.h>
00044 #include <std_msgs/UInt16MultiArray.h>
00045 #include <std_msgs/UInt32MultiArray.h>
00046 #include <std_msgs/UInt64MultiArray.h>
00047 #include <std_msgs/UInt8MultiArray.h>
00048
00049 #include <ros/assert.h>
00050 #include <ros/message_traits.h>
00051 #include <ros/serialization.h>
00052
00053 namespace std_msgs {
00054
00055
00056 template <typename T, class ContainerAllocator = std::allocator<T> >
00057 class VectorMultiArrayAdapter
00058 {
00059 public:
00060 typedef std::vector<T, ContainerAllocator> VectorType;
00061
00062 VectorMultiArrayAdapter()
00063 : vector_(&owned_vector_) {}
00064 VectorMultiArrayAdapter(VectorType &v)
00065 : vector_(&v) {}
00066 VectorMultiArrayAdapter(const VectorType &v)
00067 : vector_(const_cast<VectorType*>(&v)) {}
00068
00069 VectorType *operator->() { return vector_; }
00070 const VectorType *operator->() const { return vector_; }
00071 VectorType &operator*() { return *vector_; }
00072 const VectorType &operator*() const { return *vector_; }
00073
00074 private:
00075 VectorType owned_vector_;
00076 VectorType* vector_;
00077 };
00078
00079 }
00080
00081
00082 #define STD_MSGS_DEFINE_MULTIARRAY_TRAITS(value_type, msg, static_md5sum1, static_md5sum2) \
00083 namespace ros \
00084 { \
00085 namespace message_traits \
00086 { \
00087 \
00088 template <class ContainerAllocator> struct MD5Sum<std_msgs::VectorMultiArrayAdapter<value_type, ContainerAllocator> > \
00089 { \
00090 static const char* value() \
00091 { \
00092 ROS_STATIC_ASSERT(MD5Sum<std_msgs::msg>::static_value1 == static_md5sum1); \
00093 ROS_STATIC_ASSERT(MD5Sum<std_msgs::msg>::static_value2 == static_md5sum2); \
00094 return MD5Sum<std_msgs::msg>::value(); \
00095 } \
00096 \
00097 static const char* value(const std_msgs::VectorMultiArrayAdapter<value_type, ContainerAllocator> &) \
00098 { \
00099 return value(); \
00100 } \
00101 }; \
00102 \
00103 template <class ContainerAllocator> struct DataType<std_msgs::VectorMultiArrayAdapter<value_type, ContainerAllocator> > \
00104 { \
00105 static const char* value() \
00106 { \
00107 return DataType<std_msgs::msg>::value(); \
00108 } \
00109 \
00110 static const char* value(const std_msgs::VectorMultiArrayAdapter<value_type, ContainerAllocator> &) \
00111 { \
00112 return value(); \
00113 } \
00114 }; \
00115 \
00116 template <class ContainerAllocator> struct Definition<std_msgs::VectorMultiArrayAdapter<value_type, ContainerAllocator> > \
00117 { \
00118 static const char* value() \
00119 { \
00120 return Definition<std_msgs::msg>::value(); \
00121 } \
00122 \
00123 static const char* value(const std_msgs::VectorMultiArrayAdapter<value_type, ContainerAllocator> &) \
00124 { \
00125 return value(); \
00126 } \
00127 }; \
00128 \
00129 } \
00130 }
00131
00132 STD_MSGS_DEFINE_MULTIARRAY_TRAITS(float, Float32MultiArray, 0x6a40e0ffa6a17a50ULL, 0x3ac3f8616991b1f6ULL)
00133 STD_MSGS_DEFINE_MULTIARRAY_TRAITS(double, Float64MultiArray, 0x4b7d974086d4060eULL, 0x7db4613a7e6c3ba4ULL)
00134 STD_MSGS_DEFINE_MULTIARRAY_TRAITS(int16_t, Int16MultiArray, 0xd9338d7f523fcb69ULL, 0x2fae9d0a0e9f067cULL)
00135 STD_MSGS_DEFINE_MULTIARRAY_TRAITS(int32_t, Int32MultiArray, 0x1d99f79f8b325b44ULL, 0xfee908053e9c945bULL)
00136 STD_MSGS_DEFINE_MULTIARRAY_TRAITS(int64_t, Int64MultiArray, 0x54865aa6c65be044ULL, 0x8113a2afc6a49270ULL)
00137 STD_MSGS_DEFINE_MULTIARRAY_TRAITS(int8_t, Int8MultiArray, 0xd7c1af35a1b4781bULL, 0xbe79e03dd94b7c13ULL)
00138 STD_MSGS_DEFINE_MULTIARRAY_TRAITS(uint16_t, UInt16MultiArray, 0x52f264f1c973c4b7ULL, 0x3790d384c6cb4484ULL)
00139 STD_MSGS_DEFINE_MULTIARRAY_TRAITS(uint32_t, UInt32MultiArray, 0x4d6a180abc9be191ULL, 0xb96a7eda6c8a233dULL)
00140 STD_MSGS_DEFINE_MULTIARRAY_TRAITS(uint64_t, UInt64MultiArray, 0x6088f127afb1d6c7ULL, 0x2927aa1247e945afULL)
00141 STD_MSGS_DEFINE_MULTIARRAY_TRAITS(uint8_t, UInt8MultiArray, 0x82373f1612381bb6ULL, 0xee473b5cd6f5d89cULL)
00142
00143 namespace ros {
00144 namespace serialization {
00145
00146 template <typename T, class ContainerAllocator>
00147 struct Serializer<std_msgs::VectorMultiArrayAdapter<T, ContainerAllocator> >
00148 {
00149 typedef std_msgs::VectorMultiArrayAdapter<T, ContainerAllocator> AdaptedType;
00150
00151 template<typename Stream>
00152 inline static void write(Stream& stream, const AdaptedType& v)
00153 {
00154
00155
00156 stream.next((uint32_t)1);
00157 stream.next(std::string());
00158 stream.next((uint32_t)v->size());
00159 stream.next((uint32_t)1);
00160 stream.next((uint32_t)0);
00161 stream.next(*v);
00162 }
00163
00164 template<typename Stream>
00165 inline static void read(Stream& stream, AdaptedType& v)
00166 {
00167 std_msgs::MultiArrayLayout_<ContainerAllocator> layout;
00168 stream.next(layout);
00169 stream.next(*v);
00170 }
00171
00172 inline static uint32_t serializedLength(const AdaptedType& v)
00173 {
00174 return 20 + serializationLength(*v);
00175 }
00176 };
00177
00178 }
00179 }
00180
00181 #endif // STD_MSGS_VECTOR_MULTI_ARRAY_ADAPTER_H