5 #ifndef SENSOR_MSGS_MESSAGE_POINTCLOUD2_H 6 #define SENSOR_MSGS_MESSAGE_POINTCLOUD2_H 23 template <
class ContainerAllocator>
63 typedef std::vector< ::sensor_msgs::PointField_<ContainerAllocator> ,
typename ContainerAllocator::template rebind< ::sensor_msgs::PointField_<ContainerAllocator> >::other >
_fields_type;
75 typedef std::vector<uint8_t, typename ContainerAllocator::template rebind<uint8_t>::other >
_data_type;
89 typedef ::sensor_msgs::PointCloud2_<std::allocator<void> >
PointCloud2;
98 template<
typename ContainerAllocator>
99 std::ostream& operator<<(std::ostream& s, const ::sensor_msgs::PointCloud2_<ContainerAllocator> &
v)
109 namespace message_traits
122 template <
class ContainerAllocator>
127 template <
class ContainerAllocator>
132 template <
class ContainerAllocator>
137 template <
class ContainerAllocator>
142 template <
class ContainerAllocator>
147 template <
class ContainerAllocator>
153 template<
class ContainerAllocator>
158 return "1158d486dd51d683ce2f1be655c3c181";
161 static const char*
value(const ::sensor_msgs::PointCloud2_<ContainerAllocator>&) {
return value(); }
162 static const uint64_t static_value1 = 0x1158d486dd51d683ULL;
163 static const uint64_t static_value2 = 0xce2f1be655c3c181ULL;
166 template<
class ContainerAllocator>
171 return "sensor_msgs/PointCloud2";
174 static const char*
value(const ::sensor_msgs::PointCloud2_<ContainerAllocator>&) {
return value(); }
177 template<
class ContainerAllocator>
182 return "# This message holds a collection of N-dimensional points, which may\n\ 183 # contain additional information such as normals, intensity, etc. The\n\ 184 # point data is stored as a binary blob, its layout described by the\n\ 185 # contents of the \"fields\" array.\n\ 187 # The point cloud data may be organized 2d (image-like) or 1d\n\ 188 # (unordered). Point clouds organized as 2d images may be produced by\n\ 189 # camera depth sensors such as stereo or time-of-flight.\n\ 191 # Time of sensor data acquisition, and the coordinate frame ID (for 3d\n\ 195 # 2D structure of the point cloud. If the cloud is unordered, height is\n\ 196 # 1 and width is the length of the point cloud.\n\ 200 # Describes the channels and their layout in the binary data blob.\n\ 201 PointField[] fields\n\ 203 bool is_bigendian # Is this data bigendian?\n\ 204 uint32 point_step # Length of a point in bytes\n\ 205 uint32 row_step # Length of a row in bytes\n\ 206 uint8[] data # Actual point data, size is (row_step*height)\n\ 208 bool is_dense # True if there are no invalid points\n\ 210 ================================================================================\n\ 211 MSG: std_msgs/Header\n\ 212 # Standard metadata for higher-level stamped data types.\n\ 213 # This is generally used to communicate timestamped data \n\ 214 # in a particular coordinate frame.\n\ 216 # sequence ID: consecutively increasing ID \n\ 218 #Two-integer timestamp that is expressed as:\n\ 219 # * stamp.sec: seconds (stamp_secs) since epoch (in Python the variable is called 'secs')\n\ 220 # * stamp.nsec: nanoseconds since stamp_secs (in Python the variable is called 'nsecs')\n\ 221 # time-handling sugar is provided by the client library\n\ 223 #Frame this data is associated with\n\ 228 ================================================================================\n\ 229 MSG: sensor_msgs/PointField\n\ 230 # This message holds the description of one point entry in the\n\ 231 # PointCloud2 message format.\n\ 241 string name # Name of field\n\ 242 uint32 offset # Offset from start of point struct\n\ 243 uint8 datatype # Datatype enumeration, see above\n\ 244 uint32 count # How many elements in the field\n\ 248 static const char*
value(const ::sensor_msgs::PointCloud2_<ContainerAllocator>&) {
return value(); }
256 namespace serialization
263 stream.next(m.header);
264 stream.next(m.height);
265 stream.next(m.width);
266 stream.next(m.fields);
267 stream.next(m.is_bigendian);
268 stream.next(m.point_step);
269 stream.next(m.row_step);
271 stream.next(m.is_dense);
282 namespace message_operations
285 template<
class ContainerAllocator>
288 template<
typename Stream>
static void stream(Stream&
s,
const std::string& indent, const ::sensor_msgs::PointCloud2_<ContainerAllocator>&
v)
290 s << indent <<
"header: ";
293 s << indent <<
"height: ";
295 s << indent <<
"width: ";
297 s << indent <<
"fields[]" << std::endl;
298 for (
size_t i = 0;
i < v.fields.size(); ++
i)
300 s << indent <<
" fields[" <<
i <<
"]: ";
305 s << indent <<
"is_bigendian: ";
307 s << indent <<
"point_step: ";
309 s << indent <<
"row_step: ";
311 s << indent <<
"data[]" << std::endl;
312 for (
size_t i = 0;
i < v.data.size(); ++
i)
314 s << indent <<
" data[" <<
i <<
"]: ";
317 s << indent <<
"is_dense: ";
325 #endif // SENSOR_MSGS_MESSAGE_POINTCLOUD2_H PointCloud2_(const ContainerAllocator &_alloc)
typedef void(APIENTRY *GLDEBUGPROC)(GLenum source
Base type for compile-type true/false tests. Compatible with Boost.MPL. classes inheriting from this ...
::sensor_msgs::PointCloud2_< std::allocator< void > > PointCloud2
std::vector< ::sensor_msgs::PointField_< ContainerAllocator >, typename ContainerAllocator::template rebind< ::sensor_msgs::PointField_< ContainerAllocator > >::other > _fields_type
static const char * value(const ::sensor_msgs::PointCloud2_< ContainerAllocator > &)
_is_bigendian_type is_bigendian
Specialize to provide the md5sum for a message.
boost::shared_ptr< ::sensor_msgs::PointCloud2_< ContainerAllocator > const > ConstPtr
static void stream(Stream &s, const std::string &indent, const ::sensor_msgs::PointCloud2_< ContainerAllocator > &v)
uint8_t _is_bigendian_type
Base type for compile-type true/false tests. Compatible with Boost.MPL. classes inheriting from this ...
GLsizei const GLchar *const * string
static const char * value(const ::sensor_msgs::PointCloud2_< ContainerAllocator > &)
Specialize to provide the datatype for a message.
static const char * value(const ::sensor_msgs::PointCloud2_< ContainerAllocator > &)
PointCloud2_< ContainerAllocator > Type
::std_msgs::Header_< ContainerAllocator > _header_type
A fixed-size datatype is one whose size is constant, i.e. it has no variable-length arrays or strings...
std::vector< uint8_t, typename ContainerAllocator::template rebind< uint8_t >::other > _data_type
Stream base-class, provides common functionality for IStream and OStream.
_point_step_type point_step
boost::shared_ptr< ::sensor_msgs::PointCloud2 > PointCloud2Ptr
Tools for manipulating sensor_msgs.
GLint GLsizei GLsizei height
boost::shared_ptr< ::sensor_msgs::PointCloud2 const > PointCloud2ConstPtr
#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()
boost::shared_ptr< ::sensor_msgs::PointCloud2_< ContainerAllocator > > Ptr
static void allInOne(Stream &stream, T m)
static const char * value()
static const char * value()
Templated serialization class. Default implementation provides backwards compatibility with old messa...
uint32_t _point_step_type