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

Bounding-box leaf iterator. More...

Inheritance diagram for octomap::OcTreeBase< NODE >::leaf_bbx_iterator:
Collaboration diagram for octomap::OcTreeBase< NODE >::leaf_bbx_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_bbx_iterator (const leaf_bbx_iterator &other)
 leaf_bbx_iterator (OcTreeBase< NodeType > const *tree, const point3d &min, const point3d &max, unsigned char depth=0)
 Constructor of the iterator.
 leaf_bbx_iterator (OcTreeBase< NodeType > const *tree, const OcTreeKey &min, const OcTreeKey &max, unsigned char depth=0)
 Constructor of the iterator.
 leaf_bbx_iterator ()
bool operator!= (const iterator_base &other) const
 Comparison between interators. First compares the tree, then stack size and top element of stack.
NodeTypeoperator* ()
 Return the current node in the octree which the iterator is referring to.
const NodeTypeoperator* () const
 Return the current node in the octree which the iterator is referring to.
leaf_bbx_iteratoroperator++ ()
 prefix increment operator of iterator (++it)
leaf_bbx_iterator operator++ (int)
 postfix increment operator of iterator (it++)
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.
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.
OcTreeKey maxKey
OcTreeKey minKey
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_bbx_iterator

Bounding-box leaf iterator.

This iterator will traverse all leaf nodes within a given bounding box (axis-aligned). See below for example usage. Note that the non-trivial call to tree->end_leafs_bbx() should be done only once for efficiency!

 for(OcTreeTYPE::leaf_bbx_iterator it = tree->begin_leafs_bbx(min,max),
        end=tree->end_leafs_bbx(); 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_bbx_iterator::leaf_bbx_iterator ( ) [inline]
template<class NODE>
octomap::OcTreeBase< NODE >::leaf_bbx_iterator::leaf_bbx_iterator ( OcTreeBase< NodeType > const *  tree,
const point3d min,
const point3d max,
unsigned char  depth = 0 
) [inline]

Constructor of the iterator.

The bounding box corners min and max are converted into an OcTreeKey first.

Note:
Due to rounding and discretization effects, nodes may be traversed that have float coordinates appearing outside of the (float) bounding box. However, the node's complete volume will include the bounding box coordinate. For a more exact control, use the constructor with OcTreeKeys instead.
Parameters:
treeOcTreeBase on which the iterator is used on
minMinimum point3d of the axis-aligned boundingbox
maxMaximum point3d of the axis-aligned boundingbox
depthMaximum depth to traverse the tree. 0 (default): unlimited

References octomap::OcTreeBase< NODE >::genKey(), octomap::OcTreeBase< NODE >::iterator_base::maxDepth, octomap::OcTreeBase< NODE >::leaf_bbx_iterator::maxKey, octomap::OcTreeBase< NODE >::leaf_bbx_iterator::minKey, octomap::OcTreeBase< NODE >::leaf_bbx_iterator::operator++(), and octomap::OcTreeBase< NODE >::iterator_base::stack.

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

Constructor of the iterator.

This version uses the exact keys as axis-aligned bounding box (including min and max).

Parameters:
treeOcTreeBase on which the iterator is used on
minMinimum OcTreeKey to be included in the axis-aligned boundingbox
maxMaximum OcTreeKey to be included in the axis-aligned boundingbox
depthMaximum depth to traverse the tree. 0 (default): unlimited

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

template<class NODE>
octomap::OcTreeBase< NODE >::leaf_bbx_iterator::leaf_bbx_iterator ( const leaf_bbx_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_bbx_iterator octomap::OcTreeBase< NODE >::leaf_bbx_iterator::operator++ ( int  ) [inline]

postfix increment operator of iterator (it++)

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>
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>
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: