Public Member Functions | Private Member Functions | Private Attributes
sensor_msgs::impl::PointCloud2IteratorBase< T, TT, U, C, V > Class Template Reference

#include <point_cloud2_iterator.h>

List of all members.

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_

Detailed Description

template<typename T, typename TT, typename U, typename C, template< typename > class V>
class sensor_msgs::impl::PointCloud2IteratorBase< T, TT, U, C, V >

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.


Constructor & Destructor Documentation

template<typename T , typename TT , typename U , typename C , template< typename > class V>
sensor_msgs::impl::PointCloud2IteratorBase< T, TT, U, C, V >::PointCloud2IteratorBase ( )

Definition at line 238 of file impl/point_cloud2_iterator.h.

template<typename T , typename TT , typename U , typename C, template< typename > class V>
sensor_msgs::impl::PointCloud2IteratorBase< T, TT, U, C, V >::PointCloud2IteratorBase ( C &  cloud_msg,
const std::string &  field_name 
)
Parameters:
cloud_msgThe PointCloud2 to iterate upon
field_nameThe field to iterate upon
cloud_msg_The PointCloud2 to iterate upon
field_nameThe field to iterate upon

Definition at line 247 of file impl/point_cloud2_iterator.h.


Member Function Documentation

template<typename T , typename TT , typename U , typename C , template< typename > class V>
V< T > sensor_msgs::impl::PointCloud2IteratorBase< T, TT, U, C, V >::end ( ) const

Return the end iterator

Returns:
the end iterator (useful when performing normal iterator processing with ++)

Definition at line 345 of file impl/point_cloud2_iterator.h.

template<typename T, typename TT , typename U , typename C , template< typename > class V>
bool sensor_msgs::impl::PointCloud2IteratorBase< T, TT, U, C, V >::operator!= ( const V< T > &  iter) const

Compare to another iterator

Returns:
whether the current iterator points to a different address than the other one

Definition at line 336 of file impl/point_cloud2_iterator.h.

template<typename T , typename TT , typename U , typename C , template< typename > class V>
TT & sensor_msgs::impl::PointCloud2IteratorBase< T, TT, U, C, V >::operator* ( ) const

Dereference the iterator. Equivalent to accessing it through [0]

Returns:
the value to which the iterator is pointing

Definition at line 290 of file impl/point_cloud2_iterator.h.

template<typename T , typename TT , typename U , typename C , template< typename > class V>
V< T > sensor_msgs::impl::PointCloud2IteratorBase< T, TT, U, C, V >::operator+ ( int  i)

Basic pointer addition

Parameters:
ithe amount to increase the iterator by
Returns:
an iterator with an increased position

Definition at line 311 of file impl/point_cloud2_iterator.h.

template<typename T , typename TT , typename U , typename C , template< typename > class V>
V< T > & sensor_msgs::impl::PointCloud2IteratorBase< T, TT, U, C, V >::operator++ ( )

Increase the iterator to the next element

Returns:
a reference to the updated iterator

Definition at line 299 of file impl/point_cloud2_iterator.h.

template<typename T , typename TT , typename U , typename C , template< typename > class V>
V< T > & sensor_msgs::impl::PointCloud2IteratorBase< T, TT, U, C, V >::operator+= ( int  i)

Increase the iterator by a certain amount

Returns:
a reference to the updated iterator

Definition at line 325 of file impl/point_cloud2_iterator.h.

template<typename T, typename TT , typename U , typename C , template< typename > class V>
V< T > & sensor_msgs::impl::PointCloud2IteratorBase< T, TT, U, C, V >::operator= ( const V< T > &  iter)

Assignment operator

Parameters:
iterthe iterator to copy data from
Returns:
a reference to *this

Definition at line 261 of file impl/point_cloud2_iterator.h.

template<typename T , typename TT , typename U , typename C , template< typename > class V>
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)

Parameters:
i
Returns:
a reference to the i^th value from the current position

Definition at line 281 of file impl/point_cloud2_iterator.h.

template<typename T , typename TT , typename U , typename C , template< typename > class V>
int sensor_msgs::impl::PointCloud2IteratorBase< T, TT, U, C, V >::set_field ( const sensor_msgs::PointCloud2 &  cloud_msg,
const std::string &  field_name 
) [private]

Common code to set the field of the PointCloud2

Parameters:
cloud_msgthe PointCloud2 to modify
field_namethe name of the field to iterate upon
Returns:
the offset at which the field is found

Definition at line 358 of file impl/point_cloud2_iterator.h.


Member Data Documentation

template<typename T, typename TT, typename U, typename C, template< typename > class V>
TT* sensor_msgs::impl::PointCloud2IteratorBase< T, TT, U, C, V >::data_ [private]

The cast data where the iterator is

Definition at line 249 of file point_cloud2_iterator.h.

template<typename T, typename TT, typename U, typename C, template< typename > class V>
U* sensor_msgs::impl::PointCloud2IteratorBase< T, TT, U, C, V >::data_char_ [private]

The raw data in uchar* where the iterator is

Definition at line 247 of file point_cloud2_iterator.h.

template<typename T, typename TT, typename U, typename C, template< typename > class V>
TT* sensor_msgs::impl::PointCloud2IteratorBase< T, TT, U, C, V >::data_end_ [private]

The end() pointer of the iterator

Definition at line 251 of file point_cloud2_iterator.h.

template<typename T, typename TT, typename U, typename C, template< typename > class V>
bool sensor_msgs::impl::PointCloud2IteratorBase< T, TT, U, C, V >::is_bigendian_ [private]

Whether the fields are stored as bigendian

Definition at line 253 of file point_cloud2_iterator.h.

template<typename T, typename TT, typename U, typename C, template< typename > class V>
int sensor_msgs::impl::PointCloud2IteratorBase< T, TT, U, C, V >::point_step_ [private]

The "point_step" of the original cloud

Definition at line 245 of file point_cloud2_iterator.h.


The documentation for this class was generated from the following files:


sensor_msgs
Author(s):
autogenerated on Thu Jun 6 2019 18:15:45