Go to the documentation of this file.
6 #ifndef SENSOR_MSGS_MESSAGE_POINTCLOUD2_H
7 #define SENSOR_MSGS_MESSAGE_POINTCLOUD2_H
14 #include <ros/types.h>
15 #include <ros/serialization.h>
16 #include <ros/builtin_message_traits.h>
17 #include <ros/message_operations.h>
24 template <
class ContainerAllocator>
64 typedef std::vector< ::sensor_msgs::PointField_<ContainerAllocator> ,
typename ContainerAllocator::template rebind< ::sensor_msgs::PointField_<ContainerAllocator> >::other >
_fields_type;
76 typedef std::vector<uint8_t, typename ContainerAllocator::template rebind<uint8_t>::other >
_data_type;
85 typedef std::shared_ptr< ::sensor_msgs::PointCloud2_<ContainerAllocator> >
Ptr;
86 typedef std::shared_ptr< ::sensor_msgs::PointCloud2_<ContainerAllocator>
const>
ConstPtr;
90 typedef ::sensor_msgs::PointCloud2_<std::allocator<void> >
PointCloud2;
99 template<
typename ContainerAllocator>
100 std::ostream&
operator<<(std::ostream& s, const ::sensor_msgs::PointCloud2_<ContainerAllocator> & v)
110 namespace message_traits
123 template <
class ContainerAllocator>
128 template <
class ContainerAllocator>
133 template <
class ContainerAllocator>
138 template <
class ContainerAllocator>
143 template <
class ContainerAllocator>
148 template <
class ContainerAllocator>
154 template<
class ContainerAllocator>
159 return "1158d486dd51d683ce2f1be655c3c181";
162 static const char*
value(const ::sensor_msgs::PointCloud2_<ContainerAllocator>&) {
return value(); }
163 static const uint64_t static_value1 = 0x1158d486dd51d683ULL;
164 static const uint64_t static_value2 = 0xce2f1be655c3c181ULL;
167 template<
class ContainerAllocator>
172 return "sensor_msgs/PointCloud2";
175 static const char*
value(const ::sensor_msgs::PointCloud2_<ContainerAllocator>&) {
return value(); }
178 template<
class ContainerAllocator>
183 return "# This message holds a collection of N-dimensional points, which may\n\
184 # contain additional information such as normals, intensity, etc. The\n\
185 # point data is stored as a binary blob, its layout described by the\n\
186 # contents of the \"fields\" array.\n\
188 # The point cloud data may be organized 2d (image-like) or 1d\n\
189 # (unordered). Point clouds organized as 2d images may be produced by\n\
190 # camera depth sensors such as stereo or time-of-flight.\n\
192 # Time of sensor data acquisition, and the coordinate frame ID (for 3d\n\
196 # 2D structure of the point cloud. If the cloud is unordered, height is\n\
197 # 1 and width is the length of the point cloud.\n\
201 # Describes the channels and their layout in the binary data blob.\n\
202 PointField[] fields\n\
204 bool is_bigendian # Is this data bigendian?\n\
205 uint32 point_step # Length of a point in bytes\n\
206 uint32 row_step # Length of a row in bytes\n\
207 uint8[] data # Actual point data, size is (row_step*height)\n\
209 bool is_dense # True if there are no invalid points\n\
211 ================================================================================\n\
212 MSG: std_msgs/Header\n\
213 # Standard metadata for higher-level stamped data types.\n\
214 # This is generally used to communicate timestamped data \n\
215 # in a particular coordinate frame.\n\
217 # sequence ID: consecutively increasing ID \n\
219 #Two-integer timestamp that is expressed as:\n\
220 # * stamp.sec: seconds (stamp_secs) since epoch (in Python the variable is called 'secs')\n\
221 # * stamp.nsec: nanoseconds since stamp_secs (in Python the variable is called 'nsecs')\n\
222 # time-handling sugar is provided by the client library\n\
224 #Frame this data is associated with\n\
229 ================================================================================\n\
230 MSG: sensor_msgs/PointField\n\
231 # This message holds the description of one point entry in the\n\
232 # PointCloud2 message format.\n\
242 string name # Name of field\n\
243 uint32 offset # Offset from start of point struct\n\
244 uint8 datatype # Datatype enumeration, see above\n\
245 uint32 count # How many elements in the field\n\
249 static const char*
value(const ::sensor_msgs::PointCloud2_<ContainerAllocator>&) {
return value(); }
257 namespace serialization
262 template<
typename Stream,
typename T>
inline static void allInOne(
Stream& stream, T m)
264 stream.next(m.header);
265 stream.next(m.height);
266 stream.next(m.width);
267 stream.next(m.fields);
268 stream.next(m.is_bigendian);
269 stream.next(m.point_step);
270 stream.next(m.row_step);
272 stream.next(m.is_dense);
283 namespace message_operations
286 template<
class ContainerAllocator>
289 template<
typename Stream>
static void stream(Stream& s,
const std::string&
indent, const ::sensor_msgs::PointCloud2_<ContainerAllocator>& v)
298 s <<
indent <<
"fields[]" << std::endl;
299 for (
size_t i = 0; i < v.fields.size(); ++i)
301 s <<
indent <<
" fields[" << i <<
"]: ";
306 s <<
indent <<
"is_bigendian: ";
312 s <<
indent <<
"data[]" << std::endl;
313 for (
size_t i = 0; i < v.data.size(); ++i)
315 s <<
indent <<
" data[" << i <<
"]: ";
326 #endif // SENSOR_MSGS_MESSAGE_POINTCLOUD2_H
Base type for compile-type true/false tests. Compatible with Boost.MPL. classes inheriting from this ...
static const char * value()
Templated serialization class. Default implementation provides backwards compatibility with old messa...
_point_step_type point_step
static const char * value(const ::sensor_msgs::PointCloud2_< ContainerAllocator > &)
::sensor_msgs::PointCloud2_< std::allocator< void > > PointCloud2
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...
#define ROS_DECLARE_ALLINONE_SERIALIZER
Declare your serializer to use an allInOne member instead of requiring 3 different serialization func...
std::shared_ptr< ::sensor_msgs::PointCloud2_< ContainerAllocator > > Ptr
Specialize to provide the datatype for a message.
PointCloud2_(const ContainerAllocator &_alloc)
Specialize to provide the definition for a message.
::std_msgs::Header_< ContainerAllocator > _header_type
std::ostream & operator<<(std::ostream &s, const ::sensor_msgs::BatteryState_< ContainerAllocator > &v)
static const char * value()
uint8_t _is_bigendian_type
PointCloud2_< ContainerAllocator > Type
std::vector< uint8_t, typename ContainerAllocator::template rebind< uint8_t >::other > _data_type
std::shared_ptr< ::sensor_msgs::PointCloud2_< ContainerAllocator > const > ConstPtr
uint32_t _point_step_type
_is_bigendian_type is_bigendian
static const char * value(const ::sensor_msgs::PointCloud2_< ContainerAllocator > &)
std::vector< ::sensor_msgs::PointField_< ContainerAllocator >, typename ContainerAllocator::template rebind< ::sensor_msgs::PointField_< ContainerAllocator > >::other > _fields_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::PointCloud2 > PointCloud2Ptr
static void stream(Stream &s, const std::string &indent, const ::sensor_msgs::PointCloud2_< ContainerAllocator > &v)
static void allInOne(Stream &stream, T m)
Stream base-class, provides common functionality for IStream and OStream.
Tools for manipulating sensor_msgs.
static const char * value()
std::shared_ptr< ::sensor_msgs::PointCloud2 const > PointCloud2ConstPtr
static const char * value(const ::sensor_msgs::PointCloud2_< ContainerAllocator > &)
sick_scan_xd
Author(s): Michael Lehning
, Jochen Sprickerhof , Martin Günther
autogenerated on Fri Oct 25 2024 02:47:09