Template Class PointCloud2ConstIterator
Defined in File point_cloud2_iterator.hpp
Inheritance Relationships
Base Type
public sensor_msgs::impl::PointCloud2IteratorBase< T, const T, const unsigned char, const sensor_msgs::msg::PointCloud2, PointCloud2ConstIterator >
(Template Class PointCloud2IteratorBase)
Class Documentation
-
template<typename T>
class PointCloud2ConstIterator : public sensor_msgs::impl::PointCloud2IteratorBase<T, const T, const unsigned char, const sensor_msgs::msg::PointCloud2, PointCloud2ConstIterator> Same as a PointCloud2Iterator but for const data.
Public Functions
-
inline PointCloud2ConstIterator(const 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
-
inline PointCloud2ConstIterator(const sensor_msgs::msg::PointCloud2 &cloud_msg, const std::string &field_name)