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

Iterator to iterate over all leafs of the tree. More...

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

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
 leaf_iterator (OcTreeBase< NodeType > const *tree, unsigned char depth=0)
 Constructor of the iterator.
 leaf_iterator (const leaf_iterator &other)
 leaf_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.
leaf_iterator operator++ (int)
 postfix increment operator of iterator (it++)
leaf_iteratoroperator++ ()
 prefix increment operator of iterator (++it)
NodeTypeoperator-> ()
 Ptr operator will 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.
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 >::leaf_iterator

Iterator to iterate over all leafs of the tree.

Inner nodes are skipped. See below for example usage. Note that the non-trivial call to tree->end_leafs() should be done only once for efficiency!

 for(OcTreeTYPE::leaf_iterator it = tree->begin_leafs(),
        end=tree->end_leafs(); it!= end; ++it)
 {
   //manipulate node, e.g.:
   std::cout << "Node center: " << it.getCoordinate() << std::endl;
   std::cout << "Node size: " << it.getSize() << std::endl;
   std::cout << "Node value: " << it->getValue() << std::endl;
 }

Constructor & Destructor Documentation

template<class NODE>
octomap::OcTreeBase< NODE >::leaf_iterator::leaf_iterator ( ) [inline]
template<class NODE>
octomap::OcTreeBase< NODE >::leaf_iterator::leaf_iterator ( OcTreeBase< NodeType > const *  tree,
unsigned char  depth = 0 
) [inline]

Constructor of the iterator.

Parameters:
treeOcTreeBase on which the iterator is used on
depthMaximum depth to traverse the tree. 0 (default): unlimited

References octomap::OcTreeBase< NODE >::leaf_iterator::operator++(), and octomap::OcTreeBase< NODE >::iterator_base::stack.

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

Member Function Documentation

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

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, inherited]
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, inherited]
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, inherited]
template<class NODE>
double octomap::OcTreeBase< NODE >::iterator_base::getX ( ) const [inline, inherited]
template<class NODE>
double octomap::OcTreeBase< NODE >::iterator_base::getY ( ) const [inline, inherited]
template<class NODE>
double octomap::OcTreeBase< NODE >::iterator_base::getZ ( ) const [inline, inherited]
template<class NODE>
bool octomap::OcTreeBase< NODE >::iterator_base::operator!= ( const iterator_base other) const [inline, inherited]

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>
NodeType& octomap::OcTreeBase< NODE >::iterator_base::operator* ( ) [inline, inherited]

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

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

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

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

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

template<class NODE>
leaf_iterator octomap::OcTreeBase< NODE >::leaf_iterator::operator++ ( int  ) [inline]

postfix increment operator of iterator (it++)

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

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, inherited]

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, inherited]

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, inherited]

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