35 #ifndef SENSOR_MSGS_POINT_CLOUD2_ITERATOR_H 36 #define SENSOR_MSGS_POINT_CLOUD2_ITERATOR_H 38 #include <sensor_msgs/PointCloud2.h> 178 template<
typename T,
typename TT,
typename U,
typename C,
template <
typename>
class V>
196 V<T>& operator =(
const V<T>& iter);
203 TT& operator [](
size_t i)
const;
208 TT& operator *()
const;
219 V<T> operator +(
int i);
224 V<T>& operator +=(
int i);
229 bool operator !=(
const V<T>& iter)
const;
242 int set_field(
const sensor_msgs::PointCloud2 &cloud_msg,
const std::string &field_name);
302 #endif// SENSOR_MSGS_POINT_CLOUD2_ITERATOR_H
Same as a PointCloud2Iterator but for const data.
void reserve(size_t size)
PointCloud2Modifier(PointCloud2 &cloud_msg)
Default constructor.
void setPointCloud2Fields(int n_fields,...)
Function setting some fields in a PointCloud and adjusting the internals of the PointCloud2.
PointCloud2ConstIterator(const sensor_msgs::PointCloud2 &cloud_msg, const std::string &field_name)
PointCloud2Iterator(sensor_msgs::PointCloud2 &cloud_msg, const std::string &field_name)
Tools for manipulating sensor_msgs.
Class that can iterate over a PointCloud2.
Enables modifying a sensor_msgs::PointCloud2 like a container.
void clear()
remove all T's from the original sensor_msgs::PointCloud2
void setPointCloud2FieldsByString(int n_fields,...)
Function setting some fields in a PointCloud and adjusting the internals of the PointCloud2.