octomap 1.5.0
|
Iterator to iterate over all leafs of the tree. 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 OcTreeKey & | getKey () const |
double | getSize () const |
double | getX () const |
double | getY () const |
double | getZ () const |
leaf_iterator (OcTreeBaseImpl< NodeType, INTERFACE > 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 iterators. First compares the tree, then stack size and top element of stack. | |
const NodeType & | operator* () const |
Return the current node in the octree which the iterator is referring to. | |
NodeType & | operator* () |
Return the current node in the octree which the iterator is referring to. | |
leaf_iterator | operator++ (int) |
postfix increment operator of iterator (it++) | |
leaf_iterator & | operator++ () |
prefix increment operator of iterator (++it) | |
NodeType * | operator-> () |
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 iterators. 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. | |
OcTreeBaseImpl< NodeType, INTERFACE > const * | tree |
Octree this iterator is working on. |
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; }
leaf_iterator::leaf_iterator | ( | ) | [inline] |
leaf_iterator::leaf_iterator | ( | OcTreeBaseImpl< NodeType, INTERFACE > const * | tree, |
unsigned char | depth = 0 |
||
) | [inline] |
Constructor of the iterator.
tree | OcTreeBaseImpl on which the iterator is used on |
depth | Maximum depth to traverse the tree. 0 (default): unlimited |
References operator++(), and iterator_base::stack.
leaf_iterator::leaf_iterator | ( | const leaf_iterator & | other | ) | [inline] |
point3d iterator_base::getCoordinate | ( | ) | const [inline, inherited] |
return the center coordinate of the current node
References iterator_base::stack, and iterator_base::tree.
unsigned iterator_base::getDepth | ( | ) | const [inline, inherited] |
return depth of the current node
References iterator_base::stack.
OcTreeKey iterator_base::getIndexKey | ( | ) | const [inline, inherited] |
References octomap::computeIndexKey(), iterator_base::stack, and iterator_base::tree.
const OcTreeKey& iterator_base::getKey | ( | ) | const [inline, inherited] |
References iterator_base::stack.
double iterator_base::getSize | ( | ) | const [inline, inherited] |
References iterator_base::stack, and iterator_base::tree.
double iterator_base::getX | ( | ) | const [inline, inherited] |
References iterator_base::stack, and iterator_base::tree.
double iterator_base::getY | ( | ) | const [inline, inherited] |
References iterator_base::stack, and iterator_base::tree.
double iterator_base::getZ | ( | ) | const [inline, inherited] |
References iterator_base::stack, and iterator_base::tree.
bool iterator_base::operator!= | ( | const iterator_base & | other | ) | const [inline, inherited] |
Comparison between iterators. First compares the tree, then stack size and top element of stack.
References iterator_base::stack, and iterator_base::tree.
NodeType& iterator_base::operator* | ( | ) | [inline, inherited] |
Return the current node in the octree which the iterator is referring to.
References iterator_base::stack.
const NodeType& iterator_base::operator* | ( | ) | const [inline, inherited] |
Return the current node in the octree which the iterator is referring to.
References iterator_base::stack.
leaf_iterator leaf_iterator::operator++ | ( | int | ) | [inline] |
postfix increment operator of iterator (it++)
leaf_iterator& leaf_iterator::operator++ | ( | ) | [inline] |
prefix increment operator of iterator (++it)
References iterator_base::maxDepth, iterator_base::singleIncrement(), iterator_base::stack, and iterator_base::tree.
Referenced by leaf_iterator().
NodeType const* iterator_base::operator-> | ( | ) | const [inline, inherited] |
Ptr operator will return the current node in the octree which the iterator is referring to.
References iterator_base::stack.
NodeType* iterator_base::operator-> | ( | ) | [inline, inherited] |
Ptr operator will return the current node in the octree which the iterator is referring to.
References iterator_base::stack.
bool iterator_base::operator== | ( | const iterator_base & | other | ) | const [inline, inherited] |
Comparison between iterators. First compares the tree, then stack size and top element of stack.
References iterator_base::stack, and iterator_base::tree.
void iterator_base::singleIncrement | ( | ) | [inline, protected, inherited] |
One step of depth-first tree traversal.
How this is used depends on the actual iterator.
Reimplemented in leaf_bbx_iterator.
References octomap::computeChildKey(), iterator_base::StackElement::depth, iterator_base::StackElement::key, iterator_base::maxDepth, iterator_base::StackElement::node, iterator_base::stack, and iterator_base::tree.
Referenced by operator++(), and tree_iterator::operator++().
unsigned char iterator_base::maxDepth [protected, inherited] |
Maximum depth for depth-limited queries.
Referenced by octomap::OcTreeBaseImpl< CountingOcTreeNode, AbstractOcTree >::begin(), octomap::OcTreeBaseImpl< CountingOcTreeNode, AbstractOcTree >::begin_leafs(), octomap::OcTreeBaseImpl< CountingOcTreeNode, AbstractOcTree >::begin_leafs_bbx(), octomap::OcTreeBaseImpl< CountingOcTreeNode, AbstractOcTree >::begin_tree(), tree_iterator::isLeaf(), iterator_base::iterator_base(), leaf_bbx_iterator::leaf_bbx_iterator(), leaf_bbx_iterator::operator++(), operator++(), iterator_base::operator=(), and iterator_base::singleIncrement().
std::stack<StackElement,std::vector<StackElement> > iterator_base::stack [protected, inherited] |
Internal recursion stack. Apparently a stack of vector works fastest here.
Referenced by iterator_base::getCoordinate(), iterator_base::getDepth(), iterator_base::getIndexKey(), iterator_base::getKey(), iterator_base::getSize(), iterator_base::getX(), iterator_base::getY(), iterator_base::getZ(), tree_iterator::isLeaf(), iterator_base::iterator_base(), leaf_bbx_iterator::leaf_bbx_iterator(), leaf_iterator(), iterator_base::operator!=(), iterator_base::operator*(), leaf_bbx_iterator::operator++(), operator++(), tree_iterator::operator++(), iterator_base::operator->(), iterator_base::operator=(), iterator_base::operator==(), leaf_bbx_iterator::singleIncrement(), and iterator_base::singleIncrement().
OcTreeBaseImpl<NodeType,INTERFACE> const* iterator_base::tree [protected, inherited] |
Octree this iterator is working on.
Referenced by iterator_base::getCoordinate(), iterator_base::getIndexKey(), iterator_base::getSize(), iterator_base::getX(), iterator_base::getY(), iterator_base::getZ(), iterator_base::operator!=(), leaf_bbx_iterator::operator++(), operator++(), tree_iterator::operator++(), iterator_base::operator=(), iterator_base::operator==(), leaf_bbx_iterator::singleIncrement(), and iterator_base::singleIncrement().