Class that can iterate over a PointCloud2. More...
#include <point_cloud2_iterator.h>
Public Member Functions | |
PointCloud2Iterator (sensor_msgs::PointCloud2 &cloud_msg, const std::string &field_name) |
Class that can iterate over a PointCloud2.
T type of the element being iterated upon E.g, you create your PointClou2 message as follows:
setPointCloud2FieldsByString(cloud_msg, 2, "xyz", "rgb");
For iterating over XYZ, you do :
sensor_msgs::PointCloud2Iterator<float> iter_x(cloud_msg, "x");
and then access X through iter_x[0] or *iter_x You could create an iterator for Y and Z too but as they are consecutive, you can just use iter_x[1] and iter_x[2]
For iterating over RGB, you do:
sensor_msgs::PointCloud2Iterator<uint8_t> iter_rgb(cloud_msg, "rgb");
and then access R,G,B through iter_rgb[0], iter_rgb[1], iter_rgb[2]
Definition at line 281 of file point_cloud2_iterator.h.
sensor_msgs::PointCloud2Iterator< T >::PointCloud2Iterator | ( | sensor_msgs::PointCloud2 & | cloud_msg, |
const std::string & | field_name | ||
) | [inline] |
Definition at line 284 of file point_cloud2_iterator.h.