#include <point_cloud2_iterator.h>
Public Member Functions | |
V< T > | end () const |
bool | operator!= (const V< T > &iter) const |
TT & | operator* () const |
V< T > | operator+ (int i) |
V< T > & | operator++ () |
V< T > & | operator+= (int i) |
V< T > & | operator= (const V< T > &iter) |
TT & | operator[] (size_t i) const |
PointCloud2IteratorBase () | |
PointCloud2IteratorBase (C &cloud_msg, const std::string &field_name) | |
Private Member Functions | |
int | set_field (const sensor_msgs::PointCloud2 &cloud_msg, const std::string &field_name) |
Private Attributes | |
TT * | data_ |
U * | data_char_ |
TT * | data_end_ |
bool | is_bigendian_ |
int | point_step_ |
Private base class for PointCloud2Iterator and PointCloud2ConstIterator T is the type of the value on which the child class will be templated TT is the type of the value to be retrieved (same as T except for constness) U is the type of the raw data in PointCloud2 (only uchar and const uchar are supported) C is the type of the pointcloud to intialize from (const or not) V is the derived class (yop, curiously recurring template pattern)
Definition at line 179 of file point_cloud2_iterator.h.
sensor_msgs::impl::PointCloud2IteratorBase< T, TT, U, C, V >::PointCloud2IteratorBase |
Definition at line 239 of file impl/point_cloud2_iterator.h.
sensor_msgs::impl::PointCloud2IteratorBase< T, TT, U, C, V >::PointCloud2IteratorBase | ( | C & | cloud_msg, |
const std::string & | field_name | ||
) |
cloud_msg | The PointCloud2 to iterate upon |
field_name | The field to iterate upon |
cloud_msg_ | The PointCloud2 to iterate upon |
field_name | The field to iterate upon |
Definition at line 248 of file impl/point_cloud2_iterator.h.
V< T > sensor_msgs::impl::PointCloud2IteratorBase< T, TT, U, C, V >::end |
Return the end iterator
Definition at line 346 of file impl/point_cloud2_iterator.h.
bool sensor_msgs::impl::PointCloud2IteratorBase< T, TT, U, C, V >::operator!= | ( | const V< T > & | iter | ) | const |
Compare to another iterator
Definition at line 337 of file impl/point_cloud2_iterator.h.
TT & sensor_msgs::impl::PointCloud2IteratorBase< T, TT, U, C, V >::operator* |
Dereference the iterator. Equivalent to accessing it through [0]
Definition at line 291 of file impl/point_cloud2_iterator.h.
V< T > sensor_msgs::impl::PointCloud2IteratorBase< T, TT, U, C, V >::operator+ | ( | int | i | ) |
Basic pointer addition
i | the amount to increase the iterator by |
Definition at line 312 of file impl/point_cloud2_iterator.h.
V< T > & sensor_msgs::impl::PointCloud2IteratorBase< T, TT, U, C, V >::operator++ |
Increase the iterator to the next element
Definition at line 300 of file impl/point_cloud2_iterator.h.
V< T > & sensor_msgs::impl::PointCloud2IteratorBase< T, TT, U, C, V >::operator+= | ( | int | i | ) |
Increase the iterator by a certain amount
Definition at line 326 of file impl/point_cloud2_iterator.h.
V< T > & sensor_msgs::impl::PointCloud2IteratorBase< T, TT, U, C, V >::operator= | ( | const V< T > & | iter | ) |
Assignment operator
iter | the iterator to copy data from |
Definition at line 262 of file impl/point_cloud2_iterator.h.
TT & sensor_msgs::impl::PointCloud2IteratorBase< T, TT, U, C, V >::operator[] | ( | size_t | i | ) | const |
Access the i th element starting at the current pointer (useful when a field has several elements of the same type)
i |
Definition at line 282 of file impl/point_cloud2_iterator.h.
|
private |
Common code to set the field of the PointCloud2
cloud_msg | the PointCloud2 to modify |
field_name | the name of the field to iterate upon |
Definition at line 359 of file impl/point_cloud2_iterator.h.
|
private |
The cast data where the iterator is
Definition at line 249 of file point_cloud2_iterator.h.
|
private |
The raw data in uchar* where the iterator is
Definition at line 247 of file point_cloud2_iterator.h.
|
private |
The end() pointer of the iterator
Definition at line 251 of file point_cloud2_iterator.h.
|
private |
Whether the fields are stored as bigendian
Definition at line 253 of file point_cloud2_iterator.h.
|
private |
The "point_step" of the original cloud
Definition at line 245 of file point_cloud2_iterator.h.