Go to the documentation of this file.00001
00002
00003
00004
00005
00006
00007
00008
00009
00010
00011
00012
00013
00014
00015
00016
00017
00018
00019
00020
00021
00022
00023
00024
00025
00026
00027
00028
00029
00030
00031
00032
00033
00034
00035
00036
00037
00038
00039 #ifndef PCL_OCTREE_ITERATOR_H
00040 #define PCL_OCTREE_ITERATOR_H
00041
00042 #include <cstddef>
00043 #include <vector>
00044 #include <deque>
00045
00046 #include "octree_nodes.h"
00047 #include "octree_key.h"
00048
00049 #include <pcl/point_cloud.h>
00050 #include <pcl/point_types.h>
00051
00052 #include <iterator>
00053
00054
00055 #ifdef __GNUC__
00056 #pragma GCC system_header
00057 #endif
00058
00059 namespace pcl
00060 {
00061 namespace octree
00062 {
00063
00064
00065 struct IteratorState{
00066 OctreeNode* node_;
00067 OctreeKey key_;
00068 unsigned char depth_;
00069 };
00070
00071
00077 template<typename OctreeT>
00078 class OctreeIteratorBase : public std::iterator<std::forward_iterator_tag, const OctreeNode, void,
00079 const OctreeNode*, const OctreeNode&>
00080 {
00081 public:
00082
00083 typedef typename OctreeT::LeafNode LeafNode;
00084 typedef typename OctreeT::BranchNode BranchNode;
00085
00086 typedef typename OctreeT::LeafContainer LeafContainer;
00087 typedef typename OctreeT::BranchContainer BranchContainer;
00088
00091 explicit
00092 OctreeIteratorBase (unsigned int max_depth_arg = 0) :
00093 octree_ (0), current_state_(0), max_octree_depth_(max_depth_arg)
00094 {
00095 this->reset ();
00096 }
00097
00102 explicit
00103 OctreeIteratorBase (OctreeT* octree_arg, unsigned int max_depth_arg = 0) :
00104 octree_ (octree_arg), current_state_(0), max_octree_depth_(max_depth_arg)
00105 {
00106 this->reset ();
00107 }
00108
00113 OctreeIteratorBase (const OctreeIteratorBase& src, unsigned int max_depth_arg = 0) :
00114 octree_ (src.octree_), current_state_(0), max_octree_depth_(max_depth_arg)
00115 {
00116 this->reset ();
00117 }
00118
00122 inline OctreeIteratorBase&
00123 operator = (const OctreeIteratorBase& src)
00124 {
00125 octree_ = src.octree_;
00126 current_state_ = src.current_state_;
00127 max_octree_depth_ = src.max_octree_depth_;
00128 return (*this);
00129 }
00130
00132 virtual
00133 ~OctreeIteratorBase ()
00134 {
00135 }
00136
00140 bool operator==(const OctreeIteratorBase& other) const
00141 {
00142 return (( octree_ ==other.octree_) &&
00143 ( current_state_ == other.current_state_) &&
00144 ( max_octree_depth_ == other.max_octree_depth_) );
00145 }
00146
00150 bool operator!=(const OctreeIteratorBase& other) const
00151 {
00152 return (( octree_ !=other.octree_) &&
00153 ( current_state_ != other.current_state_) &&
00154 ( max_octree_depth_ != other.max_octree_depth_) );
00155 }
00156
00158 inline void reset ()
00159 {
00160 current_state_ = 0;
00161 if (octree_ && (!max_octree_depth_))
00162 {
00163 max_octree_depth_ = octree_->getTreeDepth();
00164 }
00165 }
00166
00170 inline const OctreeKey&
00171 getCurrentOctreeKey () const
00172 {
00173 assert(octree_!=0);
00174 assert(current_state_!=0);
00175
00176 return (current_state_->key_);
00177 }
00178
00182 inline unsigned int
00183 getCurrentOctreeDepth () const
00184 {
00185 assert(octree_!=0);
00186 assert(current_state_!=0);
00187
00188 return (current_state_->depth_);
00189 }
00190
00194 inline OctreeNode*
00195 getCurrentOctreeNode () const
00196 {
00197 assert(octree_!=0);
00198 assert(current_state_!=0);
00199
00200 return (current_state_->node_);
00201 }
00202
00203
00207 inline bool
00208 isBranchNode () const
00209 {
00210 assert(octree_!=0);
00211 assert(current_state_!=0);
00212
00213 return (current_state_->node_->getNodeType () == BRANCH_NODE);
00214 }
00215
00219 inline bool
00220 isLeafNode () const
00221 {
00222 assert(octree_!=0);
00223 assert(current_state_!=0);
00224
00225 return (current_state_->node_->getNodeType () == LEAF_NODE);
00226 }
00227
00231 inline OctreeNode*
00232 operator* () const
00233 {
00234 if (octree_ && current_state_)
00235 {
00236 return (current_state_->node_);
00237 } else
00238 {
00239 return 0;
00240 }
00241 }
00242
00246 inline char
00247 getNodeConfiguration () const
00248 {
00249 char ret = 0;
00250
00251 assert(octree_!=0);
00252 assert(current_state_!=0);
00253
00254 if (isBranchNode ())
00255 {
00256
00257
00258 const BranchNode* current_branch = static_cast<const BranchNode*> (current_state_->node_);
00259
00260
00261 ret = octree_->getBranchBitPattern (*current_branch);
00262
00263 }
00264
00265 return (ret);
00266 }
00267
00271 const LeafContainer&
00272 getLeafContainer () const
00273 {
00274 assert(octree_!=0);
00275 assert(current_state_!=0);
00276 assert(this->isLeafNode());
00277
00278 LeafNode* leaf_node = static_cast<LeafNode*>(current_state_->node_);
00279
00280 return leaf_node->getContainer();
00281 }
00282
00286 LeafContainer&
00287 getLeafContainer ()
00288 {
00289 assert(octree_!=0);
00290 assert(current_state_!=0);
00291 assert(this->isLeafNode());
00292
00293 LeafNode* leaf_node = static_cast<LeafNode*>(current_state_->node_);
00294
00295 return leaf_node->getContainer();
00296 }
00297
00301 const BranchContainer&
00302 getBranchContainer () const
00303 {
00304 assert(octree_!=0);
00305 assert(current_state_!=0);
00306 assert(this->isBranchNode());
00307
00308 BranchNode* branch_node = static_cast<BranchNode*>(current_state_->node_);
00309
00310 return branch_node->getContainer();
00311 }
00312
00316 BranchContainer&
00317 getBranchContainer ()
00318 {
00319 assert(octree_!=0);
00320 assert(current_state_!=0);
00321 assert(this->isBranchNode());
00322
00323 BranchNode* branch_node = static_cast<BranchNode*>(current_state_->node_);
00324
00325 return branch_node->getContainer();
00326 }
00327
00331 virtual unsigned long
00332 getNodeID () const
00333 {
00334 unsigned long id = 0;
00335
00336 assert(octree_!=0);
00337 assert(current_state_!=0);
00338
00339 if (current_state_)
00340 {
00341 const OctreeKey& key = getCurrentOctreeKey();
00342
00343 unsigned int depth = octree_->getTreeDepth ();
00344 id = key.x << (depth * 2) | key.y << (depth * 1) | key.z << (depth * 0);
00345 }
00346
00347 return id;
00348 }
00349
00350 protected:
00352 OctreeT* octree_;
00353
00355 IteratorState* current_state_;
00356
00358 unsigned int max_octree_depth_;
00359 };
00360
00362
00367 template<typename OctreeT>
00368 class OctreeDepthFirstIterator : public OctreeIteratorBase<OctreeT>
00369 {
00370
00371 public:
00372
00373 typedef typename OctreeIteratorBase<OctreeT>::LeafNode LeafNode;
00374 typedef typename OctreeIteratorBase<OctreeT>::BranchNode BranchNode;
00375
00379 explicit
00380 OctreeDepthFirstIterator (unsigned int max_depth_arg = 0);
00381
00386 explicit
00387 OctreeDepthFirstIterator (OctreeT* octree_arg, unsigned int max_depth_arg = 0);
00388
00390 virtual
00391 ~OctreeDepthFirstIterator ();
00392
00396 inline OctreeDepthFirstIterator&
00397 operator = (const OctreeDepthFirstIterator& src)
00398 {
00399
00400 OctreeIteratorBase<OctreeT>::operator=(src);
00401
00402 stack_ = src.stack_;
00403
00404 if (stack_.size())
00405 {
00406 this->current_state_ = &stack_.back();
00407 } else
00408 {
00409 this->current_state_ = 0;
00410 }
00411
00412 return (*this);
00413 }
00414
00417 virtual void
00418 reset ();
00419
00423 OctreeDepthFirstIterator&
00424 operator++ ();
00425
00429 inline OctreeDepthFirstIterator
00430 operator++ (int)
00431 {
00432 OctreeDepthFirstIterator _Tmp = *this;
00433 ++*this;
00434 return (_Tmp);
00435 }
00436
00439 void
00440 skipChildVoxels ();
00441
00442 protected:
00444 std::vector<IteratorState> stack_;
00445 };
00446
00448
00453 template<typename OctreeT>
00454 class OctreeBreadthFirstIterator : public OctreeIteratorBase<OctreeT>
00455 {
00456
00457 typedef typename OctreeIteratorBase<OctreeT>::BranchNode BranchNode;
00458 typedef typename OctreeIteratorBase<OctreeT>::LeafNode LeafNode;
00459
00460
00461 public:
00465 explicit
00466 OctreeBreadthFirstIterator (unsigned int max_depth_arg = 0);
00467
00472 explicit
00473 OctreeBreadthFirstIterator (OctreeT* octree_arg, unsigned int max_depth_arg = 0);
00474
00476 virtual
00477 ~OctreeBreadthFirstIterator ();
00478
00482 inline OctreeBreadthFirstIterator&
00483 operator = (const OctreeBreadthFirstIterator& src)
00484 {
00485
00486 OctreeIteratorBase<OctreeT>::operator=(src);
00487
00488 FIFO_ = src.FIFO_;
00489
00490 if (FIFO_.size())
00491 {
00492 this->current_state_ = &FIFO_.front();
00493 } else
00494 {
00495 this->current_state_ = 0;
00496 }
00497
00498 return (*this);
00499 }
00500
00503 void
00504 reset ();
00505
00509 OctreeBreadthFirstIterator&
00510 operator++ ();
00511
00515 inline OctreeBreadthFirstIterator
00516 operator++ (int)
00517 {
00518 OctreeBreadthFirstIterator _Tmp = *this;
00519 ++*this;
00520 return (_Tmp);
00521 }
00522
00523 protected:
00525 std::deque<IteratorState> FIFO_;
00526 };
00527
00529
00534
00535 template<typename OctreeT>
00536 class OctreeLeafNodeIterator : public OctreeDepthFirstIterator<OctreeT>
00537 {
00538 typedef typename OctreeDepthFirstIterator<OctreeT>::BranchNode BranchNode;
00539 typedef typename OctreeDepthFirstIterator<OctreeT>::LeafNode LeafNode;
00540
00541 public:
00545 explicit
00546 OctreeLeafNodeIterator (unsigned int max_depth_arg = 0) :
00547 OctreeDepthFirstIterator<OctreeT> (max_depth_arg)
00548 {
00549 reset ();
00550 }
00551
00556 explicit
00557 OctreeLeafNodeIterator (OctreeT* octree_arg, unsigned int max_depth_arg = 0) :
00558 OctreeDepthFirstIterator<OctreeT> (octree_arg, max_depth_arg)
00559 {
00560 reset ();
00561 }
00562
00564 virtual
00565 ~OctreeLeafNodeIterator ()
00566 {
00567 }
00568
00571 inline void
00572 reset ()
00573 {
00574 OctreeDepthFirstIterator<OctreeT>::reset ();
00575 this->operator++ ();
00576 }
00577
00581 inline OctreeLeafNodeIterator&
00582 operator++ ()
00583 {
00584 do
00585 {
00586 OctreeDepthFirstIterator<OctreeT>::operator++ ();
00587 } while ((this->current_state_) && (this->current_state_->node_->getNodeType () != LEAF_NODE));
00588
00589 return (*this);
00590 }
00591
00595 inline OctreeLeafNodeIterator
00596 operator++ (int)
00597 {
00598 OctreeLeafNodeIterator _Tmp = *this;
00599 ++*this;
00600 return (_Tmp);
00601 }
00602
00606 OctreeNode*
00607 operator* () const
00608 {
00609
00610 OctreeNode* ret = 0;
00611
00612 if (this->current_state_ && (this->current_state_->node_->getNodeType () == LEAF_NODE))
00613 ret = this->current_state_->node_;
00614 return (ret);
00615 }
00616 };
00617
00618 }
00619 }
00620
00621 #endif
00622