Go to the documentation of this file.
34 #ifndef OCTOMAP_OCTREEITERATOR_HXX_
35 #define OCTOMAP_OCTREEITERATOR_HXX_
42 class iterator_base :
public std::iterator<std::forward_iterator_tag, NodeType>{
55 iterator_base(OcTreeBaseImpl<NodeType,INTERFACE>
const* ptree, uint8_t depth=0)
56 :
tree((ptree && ptree->root) ? ptree : NULL),
maxDepth(depth)
81 &&
stack.top().depth == other.
stack.top().depth
82 &&
stack.top().key == other.
stack.top().key ))));
89 ||
stack.top().depth != other.
stack.top().depth
90 ||
stack.top().key != other.
stack.top().key ))));
158 OcTreeBaseImpl<NodeType,INTERFACE>
const*
tree;
162 std::stack<StackElement,std::vector<StackElement> >
stack;
177 for (
int i=7; i>=0; --i) {
178 if (
tree->nodeChildExists(top.
node,i)) {
228 if (!this->
stack.empty()){
232 if (this->
stack.empty()){
241 return (!this->
tree->nodeHasChildren(this->stack.top().node) || this->stack.top().depth == this->maxDepth);
275 if (this->
stack.size() > 0){
294 if (this->
stack.empty()){
301 while(!this->
stack.empty()
302 && this->stack.top().depth < this->maxDepth
303 && this->tree->nodeHasChildren(this->stack.top().node))
308 if (this->
stack.empty())
356 if (this->
stack.size() > 0){
358 if (!this->
tree->coordToKeyChecked(min,
minKey) || !this->tree->coordToKeyChecked(max,
maxKey)){
381 leaf_bbx_iterator(OcTreeBaseImpl<NodeType,INTERFACE>
const* ptree,
const OcTreeKey& min,
const OcTreeKey& max, uint8_t depth=0)
385 if (this->
stack.size() > 0){
408 if (this->
stack.empty()){
415 while(!this->
stack.empty()
416 && this->stack.top().depth < this->maxDepth
417 && this->tree->nodeHasChildren(this->stack.top().node))
422 if (this->
stack.empty())
440 for (
int i=7; i>=0; --i) {
441 if (this->
tree->nodeChildExists(top.
node, i)) {
445 if ((
minKey[0] <= (s.
key[0] + center_offset_key)) && (
maxKey[0] >= (s.
key[0] - center_offset_key))
446 && (
minKey[1] <= (s.
key[1] + center_offset_key)) && (
maxKey[1] >= (s.
key[1] - center_offset_key))
447 && (
minKey[2] <= (s.
key[2] + center_offset_key)) && (
maxKey[2] >= (s.
key[2] - center_offset_key)))
451 assert(s.
depth <= this->maxDepth);
OcTreeKey minKey
Definition: OcTreeIterator.hxx:458
Iterator over the complete tree (inner nodes and leafs).
Definition: OcTreeIterator.hxx:207
std::stack< StackElement, std::vector< StackElement > > stack
Internal recursion stack. Apparently a stack of vector works fastest here.
Definition: OcTreeIterator.hxx:162
leaf_iterator()
Definition: OcTreeIterator.hxx:265
uint16_t key_type
Definition: OcTreeKey.h:63
leaf_bbx_iterator()
Definition: OcTreeIterator.hxx:337
uint8_t maxDepth
Maximum depth for depth-limited queries.
Definition: OcTreeIterator.hxx:159
leaf_bbx_iterator(OcTreeBaseImpl< NodeType, INTERFACE > const *ptree, const OcTreeKey &min, const OcTreeKey &max, uint8_t depth=0)
Constructor of the iterator.
Definition: OcTreeIterator.hxx:381
void singleIncrement()
One step of depth-first tree traversal. How this is used depends on the actual iterator.
Definition: OcTreeIterator.hxx:166
NodeType * operator->()
Ptr operator will return the current node in the octree which the iterator is referring to.
Definition: OcTreeIterator.hxx:106
Element on the internal recursion stack of the iterator.
Definition: OcTreeIterator.hxx:150
tree_iterator operator++(int)
postfix increment operator of iterator (it++)
Definition: OcTreeIterator.hxx:219
leaf_iterator & operator++()
prefix increment operator of iterator (++it)
Definition: OcTreeIterator.hxx:293
Iterator to iterate over all leafs of the tree.
Definition: OcTreeIterator.hxx:263
void singleIncrement()
Definition: OcTreeIterator.hxx:432
bool isLeaf() const
Definition: OcTreeIterator.hxx:240
leaf_bbx_iterator operator++(int)
postfix increment operator of iterator (it++)
Definition: OcTreeIterator.hxx:400
OcTreeKey maxKey
Definition: OcTreeIterator.hxx:459
double getSize() const
Definition: OcTreeIterator.hxx:135
OcTreeKey getIndexKey() const
Definition: OcTreeIterator.hxx:144
leaf_iterator(const leaf_iterator &other)
Definition: OcTreeIterator.hxx:283
leaf_bbx_iterator & operator++()
prefix increment operator of iterator (++it)
Definition: OcTreeIterator.hxx:407
uint8_t depth
Definition: OcTreeIterator.hxx:153
unsigned getDepth() const
return depth of the current node
Definition: OcTreeIterator.hxx:138
leaf_bbx_iterator(const leaf_bbx_iterator &other)
Definition: OcTreeIterator.hxx:392
const NodeType & operator*() const
Return the current node in the octree which the iterator is referring to.
Definition: OcTreeIterator.hxx:110
iterator_base()
Default ctor, only used for the end-iterator.
Definition: OcTreeIterator.hxx:46
tree_iterator()
Definition: OcTreeIterator.hxx:209
double getZ() const
Definition: OcTreeIterator.hxx:130
const OcTreeKey & getKey() const
Definition: OcTreeIterator.hxx:141
Base class for OcTree iterators.
Definition: OcTreeIterator.hxx:42
iterator_base & operator=(const iterator_base &other)
Definition: OcTreeIterator.hxx:93
double getX() const
Definition: OcTreeIterator.hxx:122
leaf_iterator operator++(int)
postfix increment operator of iterator (it++)
Definition: OcTreeIterator.hxx:286
tree_iterator & operator++()
Prefix increment operator to advance the iterator.
Definition: OcTreeIterator.hxx:226
bool operator!=(const iterator_base &other) const
Comparison between iterators. First compares the tree, then stack size and top element of stack.
Definition: OcTreeIterator.hxx:86
OcTreeKey key
Definition: OcTreeIterator.hxx:152
Bounding-box leaf iterator.
Definition: OcTreeIterator.hxx:335
iterator_base(const iterator_base &other)
Copy constructor of the iterator.
Definition: OcTreeIterator.hxx:74
double getY() const
Definition: OcTreeIterator.hxx:126
OcTreeBaseImpl< NodeType, INTERFACE > const * tree
Octree this iterator is working on.
Definition: OcTreeIterator.hxx:158
NodeType & operator*()
Return the current node in the octree which the iterator is referring to.
Definition: OcTreeIterator.hxx:114
leaf_iterator(OcTreeBaseImpl< NodeType, INTERFACE > const *ptree, uint8_t depth=0)
Constructor of the iterator.
Definition: OcTreeIterator.hxx:273
void computeChildKey(unsigned int pos, key_type center_offset_key, const OcTreeKey &parent_key, OcTreeKey &child_key)
Computes the key of a child node while traversing the octree, given child index and current key.
Definition: OcTreeKey.h:193
NodeType const * operator->() const
Ptr operator will return the current node in the octree which the iterator is referring to.
Definition: OcTreeIterator.hxx:102
OcTreeKey computeIndexKey(key_type level, const OcTreeKey &key)
Generates a unique key for all keys on a certain level of the tree.
Definition: OcTreeKey.h:228
point3d getCoordinate() const
return the center coordinate of the current node
Definition: OcTreeIterator.hxx:117
octomath::Vector3 point3d
Use Vector3 (float precision) as a point3d in octomap.
Definition: octomap_types.h:49
bool operator==(const iterator_base &other) const
Comparison between iterators. First compares the tree, then stack size and top element of stack.
Definition: OcTreeIterator.hxx:78
leaf_bbx_iterator(OcTreeBaseImpl< NodeType, INTERFACE > const *ptree, const point3d &min, const point3d &max, uint8_t depth=0)
Constructor of the iterator.
Definition: OcTreeIterator.hxx:353
iterator_base(OcTreeBaseImpl< NodeType, INTERFACE > const *ptree, uint8_t depth=0)
Constructor of the iterator.
Definition: OcTreeIterator.hxx:55
tree_iterator(OcTreeBaseImpl< NodeType, INTERFACE > const *ptree, uint8_t depth=0)
Constructor of the iterator.
Definition: OcTreeIterator.hxx:216
NodeType * node
Definition: OcTreeIterator.hxx:151