Template Class PointCloud2Iterator

Inheritance Relationships

Base Type

Class Documentation

template<typename T>
class PointCloud2Iterator : public sensor_msgs::impl::PointCloud2IteratorBase<T, T, unsigned char, sensor_msgs::msg::PointCloud2, PointCloud2Iterator>

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::msg::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::msg::PointCloud2Iterator<uint8_t> iter_rgb(cloud_msg, "rgb");
*
and then access R,G,B through iter_rgb[0], iter_rgb[1], iter_rgb[2]

Public Functions

inline PointCloud2Iterator(sensor_msgs::msg::PointCloud2 &cloud_msg, const std::string &field_name)

Construct a new PointCloud2Const iterator based on a cloud message.

Parameters:
  • cloud_msg – the cloud message to use

  • field_name – the field to iterate over