Go to the documentation of this file.
6 #ifndef SENSOR_MSGS_MESSAGE_IMAGE_H
7 #define SENSOR_MSGS_MESSAGE_IMAGE_H
14 #include <ros/types.h>
15 #include <ros/serialization.h>
16 #include <ros/builtin_message_traits.h>
17 #include <ros/message_operations.h>
23 template <
class ContainerAllocator>
37 Image_(
const ContainerAllocator& _alloc)
59 typedef std::basic_string<char, std::char_traits<char>,
typename ContainerAllocator::template rebind<char>::other >
_encoding_type;
68 typedef std::vector<uint8_t, typename ContainerAllocator::template rebind<uint8_t>::other >
_data_type;
74 typedef std::shared_ptr< ::sensor_msgs::Image_<ContainerAllocator> >
Ptr;
75 typedef std::shared_ptr< ::sensor_msgs::Image_<ContainerAllocator>
const>
ConstPtr;
79 typedef ::sensor_msgs::Image_<std::allocator<void> >
Image;
81 typedef std::shared_ptr< ::sensor_msgs::Image >
ImagePtr;
88 template<
typename ContainerAllocator>
89 std::ostream&
operator<<(std::ostream& s, const ::sensor_msgs::Image_<ContainerAllocator> & v)
99 namespace message_traits
112 template <
class ContainerAllocator>
117 template <
class ContainerAllocator>
122 template <
class ContainerAllocator>
127 template <
class ContainerAllocator>
132 template <
class ContainerAllocator>
137 template <
class ContainerAllocator>
143 template<
class ContainerAllocator>
148 return "060021388200f6f0f447d0fcd9c64743";
151 static const char*
value(const ::sensor_msgs::Image_<ContainerAllocator>&) {
return value(); }
152 static const uint64_t static_value1 = 0x060021388200f6f0ULL;
153 static const uint64_t static_value2 = 0xf447d0fcd9c64743ULL;
156 template<
class ContainerAllocator>
161 return "sensor_msgs/Image";
164 static const char*
value(const ::sensor_msgs::Image_<ContainerAllocator>&) {
return value(); }
167 template<
class ContainerAllocator>
172 return "# This message contains an uncompressed image\n\
173 # (0, 0) is at top-left corner of image\n\
176 Header header # Header timestamp should be acquisition time of image\n\
177 # Header frame_id should be optical frame of camera\n\
178 # origin of frame should be optical center of cameara\n\
179 # +x should point to the right in the image\n\
180 # +y should point down in the image\n\
181 # +z should point into to plane of the image\n\
182 # If the frame_id here and the frame_id of the CameraInfo\n\
183 # message associated with the image conflict\n\
184 # the behavior is undefined\n\
186 uint32 height # image height, that is, number of rows\n\
187 uint32 width # image width, that is, number of columns\n\
189 # The legal values for encoding are in file src/image_encodings.cpp\n\
190 # If you want to standardize a new string format, join\n\
191 # ros-users@lists.sourceforge.net and send an email proposing a new encoding.\n\
193 string encoding # Encoding of pixels -- channel meaning, ordering, size\n\
194 # taken from the list of strings in include/sensor_msgs/image_encodings.h\n\
196 uint8 is_bigendian # is this data bigendian?\n\
197 uint32 step # Full row length in bytes\n\
198 uint8[] data # actual matrix data, size is (step * rows)\n\
200 ================================================================================\n\
201 MSG: std_msgs/Header\n\
202 # Standard metadata for higher-level stamped data types.\n\
203 # This is generally used to communicate timestamped data \n\
204 # in a particular coordinate frame.\n\
206 # sequence ID: consecutively increasing ID \n\
208 #Two-integer timestamp that is expressed as:\n\
209 # * stamp.sec: seconds (stamp_secs) since epoch (in Python the variable is called 'secs')\n\
210 # * stamp.nsec: nanoseconds since stamp_secs (in Python the variable is called 'nsecs')\n\
211 # time-handling sugar is provided by the client library\n\
213 #Frame this data is associated with\n\
220 static const char*
value(const ::sensor_msgs::Image_<ContainerAllocator>&) {
return value(); }
228 namespace serialization
233 template<
typename Stream,
typename T>
inline static void allInOne(
Stream& stream, T m)
235 stream.next(m.header);
236 stream.next(m.height);
237 stream.next(m.width);
238 stream.next(m.encoding);
239 stream.next(m.is_bigendian);
252 namespace message_operations
255 template<
class ContainerAllocator>
258 template<
typename Stream>
static void stream(Stream& s,
const std::string&
indent, const ::sensor_msgs::Image_<ContainerAllocator>& v)
269 s <<
indent <<
"is_bigendian: ";
273 s <<
indent <<
"data[]" << std::endl;
274 for (
size_t i = 0; i < v.data.size(); ++i)
276 s <<
indent <<
" data[" << i <<
"]: ";
285 #endif // SENSOR_MSGS_MESSAGE_IMAGE_H
Base type for compile-type true/false tests. Compatible with Boost.MPL. classes inheriting from this ...
::sensor_msgs::Image_< std::allocator< void > > Image
Templated serialization class. Default implementation provides backwards compatibility with old messa...
static const char * value()
static void stream(Stream &s, const std::string &indent, const ::sensor_msgs::Image_< ContainerAllocator > &v)
std::shared_ptr< ::sensor_msgs::Image_< ContainerAllocator > const > ConstPtr
static const char * value(const ::sensor_msgs::Image_< ContainerAllocator > &)
static void stream(Stream &s, const std::string &indent, const M &value)
A fixed-size datatype is one whose size is constant, i.e. it has no variable-length arrays or strings...
::std_msgs::Header_< ContainerAllocator > _header_type
static const char * value(const ::sensor_msgs::Image_< ContainerAllocator > &)
uint8_t _is_bigendian_type
static const char * value()
#define ROS_DECLARE_ALLINONE_SERIALIZER
Declare your serializer to use an allInOne member instead of requiring 3 different serialization func...
Specialize to provide the datatype for a message.
Specialize to provide the definition for a message.
static const char * value(const ::sensor_msgs::Image_< ContainerAllocator > &)
std::ostream & operator<<(std::ostream &s, const ::sensor_msgs::BatteryState_< ContainerAllocator > &v)
static const char * value()
std::vector< uint8_t, typename ContainerAllocator::template rebind< uint8_t >::other > _data_type
Base type for compile-type true/false tests. Compatible with Boost.MPL. classes inheriting from this ...
Specialize to provide the md5sum for a message.
std::shared_ptr< ::sensor_msgs::Image_< ContainerAllocator > > Ptr
_is_bigendian_type is_bigendian
std::basic_string< char, std::char_traits< char >, typename ContainerAllocator::template rebind< char >::other > _encoding_type
Stream base-class, provides common functionality for IStream and OStream.
std::shared_ptr< ::sensor_msgs::Image > ImagePtr
std::shared_ptr< ::sensor_msgs::Image const > ImageConstPtr
Tools for manipulating sensor_msgs.
Image_(const ContainerAllocator &_alloc)
static void allInOne(Stream &stream, T m)
Image_< ContainerAllocator > Type
sick_scan_xd
Author(s): Michael Lehning
, Jochen Sprickerhof , Martin Günther
autogenerated on Fri Oct 25 2024 02:47:08