5 #ifndef SENSOR_MSGS_MESSAGE_POINTCLOUD_H 6 #define SENSOR_MSGS_MESSAGE_POINTCLOUD_H 24 template <
class ContainerAllocator>
46 typedef std::vector< ::geometry_msgs::Point32_<ContainerAllocator> ,
typename ContainerAllocator::template rebind< ::geometry_msgs::Point32_<ContainerAllocator> >::other >
_points_type;
49 typedef std::vector< ::sensor_msgs::ChannelFloat32_<ContainerAllocator> ,
typename ContainerAllocator::template rebind< ::sensor_msgs::ChannelFloat32_<ContainerAllocator> >::other >
_channels_type;
60 typedef ::sensor_msgs::PointCloud_<std::allocator<void> >
PointCloud;
69 template<
typename ContainerAllocator>
70 std::ostream& operator<<(std::ostream& s, const ::sensor_msgs::PointCloud_<ContainerAllocator> &
v)
80 namespace message_traits
93 template <
class ContainerAllocator>
98 template <
class ContainerAllocator>
103 template <
class ContainerAllocator>
108 template <
class ContainerAllocator>
113 template <
class ContainerAllocator>
118 template <
class ContainerAllocator>
124 template<
class ContainerAllocator>
129 return "d8e9c3f5afbdd8a130fd1d2763945fca";
132 static const char*
value(const ::sensor_msgs::PointCloud_<ContainerAllocator>&) {
return value(); }
133 static const uint64_t static_value1 = 0xd8e9c3f5afbdd8a1ULL;
134 static const uint64_t static_value2 = 0x30fd1d2763945fcaULL;
137 template<
class ContainerAllocator>
142 return "sensor_msgs/PointCloud";
145 static const char*
value(const ::sensor_msgs::PointCloud_<ContainerAllocator>&) {
return value(); }
148 template<
class ContainerAllocator>
153 return "# This message holds a collection of 3d points, plus optional additional\n\ 154 # information about each point.\n\ 156 # Time of sensor data acquisition, coordinate frame ID.\n\ 159 # Array of 3d points. Each Point32 should be interpreted as a 3d point\n\ 160 # in the frame given in the header.\n\ 161 geometry_msgs/Point32[] points\n\ 163 # Each channel should have the same number of elements as points array,\n\ 164 # and the data in each channel should correspond 1:1 with each point.\n\ 165 # Channel names in common practice are listed in ChannelFloat32.msg.\n\ 166 ChannelFloat32[] channels\n\ 168 ================================================================================\n\ 169 MSG: std_msgs/Header\n\ 170 # Standard metadata for higher-level stamped data types.\n\ 171 # This is generally used to communicate timestamped data \n\ 172 # in a particular coordinate frame.\n\ 174 # sequence ID: consecutively increasing ID \n\ 176 #Two-integer timestamp that is expressed as:\n\ 177 # * stamp.sec: seconds (stamp_secs) since epoch (in Python the variable is called 'secs')\n\ 178 # * stamp.nsec: nanoseconds since stamp_secs (in Python the variable is called 'nsecs')\n\ 179 # time-handling sugar is provided by the client library\n\ 181 #Frame this data is associated with\n\ 186 ================================================================================\n\ 187 MSG: geometry_msgs/Point32\n\ 188 # This contains the position of a point in free space(with 32 bits of precision).\n\ 189 # It is recommeded to use Point wherever possible instead of Point32. \n\ 191 # This recommendation is to promote interoperability. \n\ 193 # This message is designed to take up less space when sending\n\ 194 # lots of points at once, as in the case of a PointCloud. \n\ 199 ================================================================================\n\ 200 MSG: sensor_msgs/ChannelFloat32\n\ 201 # This message is used by the PointCloud message to hold optional data\n\ 202 # associated with each point in the cloud. The length of the values\n\ 203 # array should be the same as the length of the points array in the\n\ 204 # PointCloud, and each value should be associated with the corresponding\n\ 207 # Channel names in existing practice include:\n\ 208 # \"u\", \"v\" - row and column (respectively) in the left stereo image.\n\ 209 # This is opposite to usual conventions but remains for\n\ 210 # historical reasons. The newer PointCloud2 message has no\n\ 212 # \"rgb\" - For point clouds produced by color stereo cameras. uint8\n\ 213 # (R,G,B) values packed into the least significant 24 bits,\n\ 215 # \"intensity\" - laser or pixel intensity.\n\ 218 # The channel name should give semantics of the channel (e.g.\n\ 219 # \"intensity\" instead of \"value\").\n\ 222 # The values array should be 1-1 with the elements of the associated\n\ 228 static const char*
value(const ::sensor_msgs::PointCloud_<ContainerAllocator>&) {
return value(); }
236 namespace serialization
243 stream.next(m.header);
244 stream.next(m.points);
245 stream.next(m.channels);
256 namespace message_operations
259 template<
class ContainerAllocator>
262 template<
typename Stream>
static void stream(Stream&
s,
const std::string& indent, const ::sensor_msgs::PointCloud_<ContainerAllocator>&
v)
264 s << indent <<
"header: ";
267 s << indent <<
"points[]" << std::endl;
268 for (
size_t i = 0;
i < v.points.size(); ++
i)
270 s << indent <<
" points[" <<
i <<
"]: ";
275 s << indent <<
"channels[]" << std::endl;
276 for (
size_t i = 0;
i < v.channels.size(); ++
i)
278 s << indent <<
" channels[" <<
i <<
"]: ";
289 #endif // SENSOR_MSGS_MESSAGE_POINTCLOUD_H
typedef void(APIENTRY *GLDEBUGPROC)(GLenum source
Base type for compile-type true/false tests. Compatible with Boost.MPL. classes inheriting from this ...
Specialize to provide the md5sum for a message.
Base type for compile-type true/false tests. Compatible with Boost.MPL. classes inheriting from this ...
static void allInOne(Stream &stream, T m)
GLsizei const GLchar *const * string
Specialize to provide the datatype for a message.
::sensor_msgs::PointCloud_< std::allocator< void > > PointCloud
static const char * value()
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.
PointCloud_(const ContainerAllocator &_alloc)
Tools for manipulating sensor_msgs.
#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.
boost::shared_ptr< ::sensor_msgs::PointCloud_< ContainerAllocator > > Ptr
boost::shared_ptr< ::sensor_msgs::PointCloud_< ContainerAllocator > const > ConstPtr
std::vector< ::sensor_msgs::ChannelFloat32_< ContainerAllocator >, typename ContainerAllocator::template rebind< ::sensor_msgs::ChannelFloat32_< ContainerAllocator > >::other > _channels_type
static void stream(Stream &s, const std::string &indent, const ::sensor_msgs::PointCloud_< ContainerAllocator > &v)
static const char * value()
static const char * value(const ::sensor_msgs::PointCloud_< ContainerAllocator > &)
static const char * value()
boost::shared_ptr< ::sensor_msgs::PointCloud > PointCloudPtr
std::vector< ::geometry_msgs::Point32_< ContainerAllocator >, typename ContainerAllocator::template rebind< ::geometry_msgs::Point32_< ContainerAllocator > >::other > _points_type
Templated serialization class. Default implementation provides backwards compatibility with old messa...
static const char * value(const ::sensor_msgs::PointCloud_< ContainerAllocator > &)
static const char * value(const ::sensor_msgs::PointCloud_< ContainerAllocator > &)
PointCloud_< ContainerAllocator > Type
boost::shared_ptr< ::sensor_msgs::PointCloud const > PointCloudConstPtr
GLdouble GLdouble GLint GLint const GLdouble * points
::std_msgs::Header_< ContainerAllocator > _header_type