#include <cloud-impl.hpp>
Public Member Functions | |
void | copyData (const GenericCloudConstIterator< T > &otherIter) const |
void | copyData (const GenericCloudIterator< T > &otherIter) const |
GenericCloudIterator (sensor_msgs::PointCloud2 &cloud_msg, const std::string &field_name) | |
![]() | |
GenericCloudIteratorBase (sensor_msgs::PointCloud2 &cloudMsg, const std::string &fieldName) | |
unsigned char * | getData () const |
size_t | getFieldSize () |
![]() | |
GenericCloudIterator< T > | end () const |
bool | operator!= (const GenericCloudIterator< T > &iter) const |
TT & | operator* () const |
GenericCloudIterator< T > | operator+ (int i) |
GenericCloudIterator< T > & | operator++ () |
GenericCloudIterator< T > & | operator+= (int i) |
GenericCloudIterator< T > & | operator= (const GenericCloudIterator< T > &iter) |
TT & | operator[] (size_t i) const |
PointCloud2IteratorBase () | |
PointCloud2IteratorBase (C &cloud_msg, const std::string &field_name) | |
Additional Inherited Members | |
![]() | |
size_t | fieldSize |
Definition at line 33 of file cloud-impl.hpp.
|
inline |
Definition at line 36 of file cloud-impl.hpp.
void robot_body_filter::impl::GenericCloudIterator< T >::copyData | ( | const GenericCloudConstIterator< T > & | otherIter | ) | const |
void robot_body_filter::impl::GenericCloudIterator< T >::copyData | ( | const GenericCloudIterator< T > & | otherIter | ) | const |