octomap 1.4.2
octomap::OcTreeBase< NODE >::iterator_base Class Reference

Base class for OcTree iterators. More...

Inheritance diagram for octomap::OcTreeBase< NODE >::iterator_base:
Collaboration diagram for octomap::OcTreeBase< NODE >::iterator_base:

Data Structures

struct  StackElement
 Element on the internal recursion stack of the iterator. More...

Public Member Functions

point3d getCoordinate () const
 return the center coordinate of the current node
unsigned getDepth () const
 return depth of the current node
OcTreeKey getIndexKey () const
const OcTreeKeygetKey () const
double getSize () const
double getX () const
double getY () const
double getZ () const
 iterator_base ()
 Default ctor, only used for the end-iterator.
 iterator_base (OcTreeBase< NodeType > const *tree, unsigned char depth=0)
 Constructor of the iterator.
 iterator_base (const iterator_base &other)
 Copy constructor of the iterator.
bool operator!= (const iterator_base &other) const
 Comparison between interators. First compares the tree, then stack size and top element of stack.
const NodeTypeoperator* () const
 Return the current node in the octree which the iterator is referring to.
NodeTypeoperator* ()
 Return the current node in the octree which the iterator is referring to.
NodeType const * operator-> () const
 Ptr operator will return the current node in the octree which the iterator is referring to.
NodeTypeoperator-> ()
 Ptr operator will return the current node in the octree which the iterator is referring to.
iterator_baseoperator= (const iterator_base &other)
bool operator== (const iterator_base &other) const
 Comparison between interators. First compares the tree, then stack size and top element of stack.

Protected Member Functions

void singleIncrement ()
 One step of depth-first tree traversal.

Protected Attributes

unsigned char maxDepth
 Maximum depth for depth-limited queries.
std::stack< StackElement,
std::vector< StackElement > > 
stack
 Internal recursion stack. Apparently a stack of vector works fastest here.
OcTreeBase< NodeType > const * tree
 Octree this iterator is working on.

Detailed Description

template<class NODE>
class octomap::OcTreeBase< NODE >::iterator_base

Base class for OcTree iterators.

So far, all iterator's are const with respect to the tree


Constructor & Destructor Documentation

template<class NODE>
octomap::OcTreeBase< NODE >::iterator_base::iterator_base ( ) [inline]

Default ctor, only used for the end-iterator.

template<class NODE>
octomap::OcTreeBase< NODE >::iterator_base::iterator_base ( const iterator_base other) [inline]

Copy constructor of the iterator.


Member Function Documentation

template<class NODE>
point3d octomap::OcTreeBase< NODE >::iterator_base::getCoordinate ( ) const [inline]
template<class NODE>
unsigned octomap::OcTreeBase< NODE >::iterator_base::getDepth ( ) const [inline]

return depth of the current node

References octomap::OcTreeBase< NODE >::iterator_base::stack.

template<class NODE>
OcTreeKey octomap::OcTreeBase< NODE >::iterator_base::getIndexKey ( ) const [inline]
Returns:
the OcTreeKey of the current node, for nodes with depth != maxDepth

References octomap::OcTreeBase< NODE >::iterator_base::stack.

template<class NODE>
const OcTreeKey& octomap::OcTreeBase< NODE >::iterator_base::getKey ( ) const [inline]
Returns:
the OcTreeKey of the current node

References octomap::OcTreeBase< NODE >::iterator_base::stack.

template<class NODE>
double octomap::OcTreeBase< NODE >::iterator_base::getSize ( ) const [inline]
template<class NODE>
double octomap::OcTreeBase< NODE >::iterator_base::getX ( ) const [inline]
template<class NODE>
double octomap::OcTreeBase< NODE >::iterator_base::getY ( ) const [inline]
template<class NODE>
double octomap::OcTreeBase< NODE >::iterator_base::getZ ( ) const [inline]
template<class NODE>
bool octomap::OcTreeBase< NODE >::iterator_base::operator!= ( const iterator_base other) const [inline]

Comparison between interators. First compares the tree, then stack size and top element of stack.

References octomap::OcTreeBase< NODE >::iterator_base::stack, and octomap::OcTreeBase< NODE >::iterator_base::tree.

template<class NODE>
const NodeType& octomap::OcTreeBase< NODE >::iterator_base::operator* ( ) const [inline]

Return the current node in the octree which the iterator is referring to.

References octomap::OcTreeBase< NODE >::iterator_base::stack.

template<class NODE>
NodeType& octomap::OcTreeBase< NODE >::iterator_base::operator* ( ) [inline]

Return the current node in the octree which the iterator is referring to.

References octomap::OcTreeBase< NODE >::iterator_base::stack.

template<class NODE>
NodeType const* octomap::OcTreeBase< NODE >::iterator_base::operator-> ( ) const [inline]

Ptr operator will return the current node in the octree which the iterator is referring to.

References octomap::OcTreeBase< NODE >::iterator_base::stack.

template<class NODE>
NodeType* octomap::OcTreeBase< NODE >::iterator_base::operator-> ( ) [inline]

Ptr operator will return the current node in the octree which the iterator is referring to.

References octomap::OcTreeBase< NODE >::iterator_base::stack.

template<class NODE>
bool octomap::OcTreeBase< NODE >::iterator_base::operator== ( const iterator_base other) const [inline]

Comparison between interators. First compares the tree, then stack size and top element of stack.

References octomap::OcTreeBase< NODE >::iterator_base::stack, and octomap::OcTreeBase< NODE >::iterator_base::tree.


Field Documentation

template<class NODE>
std::stack<StackElement,std::vector<StackElement> > octomap::OcTreeBase< NODE >::iterator_base::stack [protected]

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