37 #include <sensor_msgs/Image.h>
68 namespace message_traits {
75 static const uint64_t static_value1 = MD5Sum<sensor_msgs::Image>::static_value1;
76 static const uint64_t static_value2 = MD5Sum<sensor_msgs::Image>::static_value2;
79 ROS_STATIC_ASSERT(MD5Sum<sensor_msgs::Image>::static_value1 == 0x060021388200f6f0ULL);
99 namespace serialization {
105 template<
typename Stream>
108 stream.next(m.
image_.header);
109 stream.next((uint32_t)m.
image_.height);
110 stream.next((uint32_t)m.
image_.width);
111 stream.next(m.
image_.encoding);
112 uint8_t is_bigendian = 0;
113 stream.next(is_bigendian);
114 stream.next((uint32_t)m.
image_.step);
116 stream.next((uint32_t)data_size);
118 memcpy(stream.advance(data_size), m.
data_, data_size);