5 #ifndef SENSOR_MSGS_MESSAGE_IMAGE_H 6 #define SENSOR_MSGS_MESSAGE_IMAGE_H 22 template <
class ContainerAllocator>
36 Image_(
const ContainerAllocator& _alloc)
58 typedef std::basic_string<char, std::char_traits<char>,
typename ContainerAllocator::template rebind<char>::other >
_encoding_type;
67 typedef std::vector<uint8_t, typename ContainerAllocator::template rebind<uint8_t>::other >
_data_type;
73 typedef std::shared_ptr< ::sensor_msgs::Image_<ContainerAllocator> >
Ptr;
74 typedef std::shared_ptr< ::sensor_msgs::Image_<ContainerAllocator>
const>
ConstPtr;
78 typedef ::sensor_msgs::Image_<std::allocator<void> >
Image;
80 typedef std::shared_ptr< ::sensor_msgs::Image >
ImagePtr;
87 template<
typename ContainerAllocator>
88 std::ostream& operator<<(std::ostream& s, const ::sensor_msgs::Image_<ContainerAllocator> &
v)
98 namespace message_traits
111 template <
class ContainerAllocator>
116 template <
class ContainerAllocator>
121 template <
class ContainerAllocator>
126 template <
class ContainerAllocator>
131 template <
class ContainerAllocator>
136 template <
class ContainerAllocator>
142 template<
class ContainerAllocator>
147 return "060021388200f6f0f447d0fcd9c64743";
150 static const char*
value(const ::sensor_msgs::Image_<ContainerAllocator>&) {
return value(); }
151 static const uint64_t static_value1 = 0x060021388200f6f0ULL;
152 static const uint64_t static_value2 = 0xf447d0fcd9c64743ULL;
155 template<
class ContainerAllocator>
160 return "sensor_msgs/Image";
163 static const char*
value(const ::sensor_msgs::Image_<ContainerAllocator>&) {
return value(); }
166 template<
class ContainerAllocator>
171 return "# This message contains an uncompressed image\n\ 172 # (0, 0) is at top-left corner of image\n\ 175 Header header # Header timestamp should be acquisition time of image\n\ 176 # Header frame_id should be optical frame of camera\n\ 177 # origin of frame should be optical center of cameara\n\ 178 # +x should point to the right in the image\n\ 179 # +y should point down in the image\n\ 180 # +z should point into to plane of the image\n\ 181 # If the frame_id here and the frame_id of the CameraInfo\n\ 182 # message associated with the image conflict\n\ 183 # the behavior is undefined\n\ 185 uint32 height # image height, that is, number of rows\n\ 186 uint32 width # image width, that is, number of columns\n\ 188 # The legal values for encoding are in file src/image_encodings.cpp\n\ 189 # If you want to standardize a new string format, join\n\ 190 # ros-users@lists.sourceforge.net and send an email proposing a new encoding.\n\ 192 string encoding # Encoding of pixels -- channel meaning, ordering, size\n\ 193 # taken from the list of strings in include/sensor_msgs/image_encodings.h\n\ 195 uint8 is_bigendian # is this data bigendian?\n\ 196 uint32 step # Full row length in bytes\n\ 197 uint8[] data # actual matrix data, size is (step * rows)\n\ 199 ================================================================================\n\ 200 MSG: std_msgs/Header\n\ 201 # Standard metadata for higher-level stamped data types.\n\ 202 # This is generally used to communicate timestamped data \n\ 203 # in a particular coordinate frame.\n\ 205 # sequence ID: consecutively increasing ID \n\ 207 #Two-integer timestamp that is expressed as:\n\ 208 # * stamp.sec: seconds (stamp_secs) since epoch (in Python the variable is called 'secs')\n\ 209 # * stamp.nsec: nanoseconds since stamp_secs (in Python the variable is called 'nsecs')\n\ 210 # time-handling sugar is provided by the client library\n\ 212 #Frame this data is associated with\n\ 219 static const char*
value(const ::sensor_msgs::Image_<ContainerAllocator>&) {
return value(); }
227 namespace serialization
234 stream.next(m.header);
235 stream.next(m.height);
236 stream.next(m.width);
237 stream.next(m.encoding);
238 stream.next(m.is_bigendian);
251 namespace message_operations
254 template<
class ContainerAllocator>
257 template<
typename Stream>
static void stream(Stream&
s,
const std::string& indent, const ::sensor_msgs::Image_<ContainerAllocator>&
v)
259 s << indent <<
"header: ";
262 s << indent <<
"height: ";
264 s << indent <<
"width: ";
266 s << indent <<
"encoding: ";
268 s << indent <<
"is_bigendian: ";
270 s << indent <<
"step: ";
272 s << indent <<
"data[]" << std::endl;
273 for (
size_t i = 0;
i < v.data.size(); ++
i)
275 s << indent <<
" data[" <<
i <<
"]: ";
284 #endif // SENSOR_MSGS_MESSAGE_IMAGE_H static const char * value()
typedef void(APIENTRY *GLDEBUGPROC)(GLenum source
Base type for compile-type true/false tests. Compatible with Boost.MPL. classes inheriting from this ...
std::shared_ptr< ::sensor_msgs::Image_< ContainerAllocator > const > ConstPtr
Specialize to provide the md5sum for a message.
::sensor_msgs::Image_< std::allocator< void > > Image
static const char * value(const ::sensor_msgs::Image_< ContainerAllocator > &)
Base type for compile-type true/false tests. Compatible with Boost.MPL. classes inheriting from this ...
std::shared_ptr< ::sensor_msgs::Image const > ImageConstPtr
GLsizei const GLchar *const * string
Specialize to provide the datatype for a message.
static void allInOne(Stream &stream, T m)
A fixed-size datatype is one whose size is constant, i.e. it has no variable-length arrays or strings...
Stream base-class, provides common functionality for IStream and OStream.
Image_(const ContainerAllocator &_alloc)
Image_< ContainerAllocator > Type
Tools for manipulating sensor_msgs.
GLint GLsizei GLsizei height
#define ROS_DECLARE_ALLINONE_SERIALIZER
Declare your serializer to use an allInOne member instead of requiring 3 different serialization func...
unsigned __int64 uint64_t
Specialize to provide the definition for a message.
static const char * value()
std::vector< uint8_t, typename ContainerAllocator::template rebind< uint8_t >::other > _data_type
std::shared_ptr< ::sensor_msgs::Image_< ContainerAllocator > > Ptr
static const char * value()
static void stream(Stream &s, const std::string &indent, const ::sensor_msgs::Image_< ContainerAllocator > &v)
static const char * value(const ::sensor_msgs::Image_< ContainerAllocator > &)
std::basic_string< char, std::char_traits< char >, typename ContainerAllocator::template rebind< char >::other > _encoding_type
_is_bigendian_type is_bigendian
::std_msgs::Header_< ContainerAllocator > _header_type
Templated serialization class. Default implementation provides backwards compatibility with old messa...
static const char * value(const ::sensor_msgs::Image_< ContainerAllocator > &)
std::shared_ptr< ::sensor_msgs::Image > ImagePtr
uint8_t _is_bigendian_type