35 #ifndef STD_MSGS_VECTOR_MULTI_ARRAY_ADAPTER_H 36 #define STD_MSGS_VECTOR_MULTI_ARRAY_ADAPTER_H 38 #include <std_msgs/Float32MultiArray.h> 39 #include <std_msgs/Float64MultiArray.h> 40 #include <std_msgs/Int16MultiArray.h> 41 #include <std_msgs/Int32MultiArray.h> 42 #include <std_msgs/Int64MultiArray.h> 43 #include <std_msgs/Int8MultiArray.h> 44 #include <std_msgs/UInt16MultiArray.h> 45 #include <std_msgs/UInt32MultiArray.h> 46 #include <std_msgs/UInt64MultiArray.h> 47 #include <std_msgs/UInt8MultiArray.h> 56 template <
typename T,
class ContainerAllocator = std::allocator<T> >
67 :
vector_(const_cast<VectorType*>(&v)) {}
82 #define STD_MSGS_DEFINE_MULTIARRAY_TRAITS(value_type, msg, static_md5sum1, static_md5sum2) \ 85 namespace message_traits \ 88 template <class ContainerAllocator> struct MD5Sum<std_msgs::VectorMultiArrayAdapter<value_type, ContainerAllocator> > \ 90 static const char* value() \ 92 ROS_STATIC_ASSERT(MD5Sum<std_msgs::msg>::static_value1 == static_md5sum1); \ 93 ROS_STATIC_ASSERT(MD5Sum<std_msgs::msg>::static_value2 == static_md5sum2); \ 94 return MD5Sum<std_msgs::msg>::value(); \ 97 static const char* value(const std_msgs::VectorMultiArrayAdapter<value_type, ContainerAllocator> &) \ 103 template <class ContainerAllocator> struct DataType<std_msgs::VectorMultiArrayAdapter<value_type, ContainerAllocator> > \ 105 static const char* value() \ 107 return DataType<std_msgs::msg>::value(); \ 110 static const char* value(const std_msgs::VectorMultiArrayAdapter<value_type, ContainerAllocator> &) \ 116 template <class ContainerAllocator> struct Definition<std_msgs::VectorMultiArrayAdapter<value_type, ContainerAllocator> > \ 118 static const char* value() \ 120 return Definition<std_msgs::msg>::value(); \ 123 static const char* value(const std_msgs::VectorMultiArrayAdapter<value_type, ContainerAllocator> &) \ 144 namespace serialization {
146 template <
typename T,
class ContainerAllocator>
151 template<
typename Stream>
156 stream.next((uint32_t)1);
157 stream.next(std::string());
158 stream.next((uint32_t)v->size());
159 stream.next((uint32_t)1);
160 stream.next((uint32_t)0);
164 template<
typename Stream>
167 std_msgs::MultiArrayLayout_<ContainerAllocator> layout;
181 #endif // STD_MSGS_VECTOR_MULTI_ARRAY_ADAPTER_H const VectorType & operator*() const
static void write(Stream &stream, const AdaptedType &v)
std::vector< T, ContainerAllocator > VectorType
VectorMultiArrayAdapter()
static uint32_t serializedLength(const AdaptedType &v)
std_msgs::VectorMultiArrayAdapter< T, ContainerAllocator > AdaptedType
#define STD_MSGS_DEFINE_MULTIARRAY_TRAITS(value_type, msg, static_md5sum1, static_md5sum2)
VectorMultiArrayAdapter(VectorType &v)
const VectorType * operator->() const
uint32_t serializationLength(const T &t)
VectorType * operator->()
static void read(Stream &stream, AdaptedType &v)
VectorMultiArrayAdapter(const VectorType &v)