outofcore_iterator_base.h
Go to the documentation of this file.
00001 /*
00002  * Software License Agreement (BSD License)
00003  *
00004  *  Point Cloud Library (PCL) - www.pointclouds.org
00005  *  Copyright (c) 2010-2012, Willow Garage, Inc.
00006  *
00007  *  All rights reserved.
00008  *
00009  *  Redistribution and use in source and binary forms, with or without
00010  *  modification, are permitted provided that the following conditions
00011  *  are met:
00012  *
00013  *   * Redistributions of source code must retain the above copyright
00014  *     notice, this list of conditions and the following disclaimer.
00015  *   * Redistributions in binary form must reproduce the above
00016  *     copyright notice, this list of conditions and the following
00017  *     disclaimer in the documentation and/or other materials provided
00018  *     with the distribution.
00019  *   * Neither the name of Willow Garage, Inc. nor the names of its
00020  *     contributors may be used to endorse or promote products derived
00021  *     from this software without specific prior written permission.
00022  *
00023  *  THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
00024  *  "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
00025  *  LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
00026  *  FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
00027  *  COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
00028  *  INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
00029  *  BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
00030  *  LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
00031  *  CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
00032  *  LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
00033  *  ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
00034  *  POSSIBILITY OF SUCH DAMAGE.
00035  *
00036  * $Id$
00037  */
00038 
00039 #ifndef PCL_OUTOFCORE_ITERATOR_BASE_H_
00040 #define PCL_OUTOFCORE_ITERATOR_BASE_H_
00041 
00042 #include <iterator>
00043 
00044 #include <pcl/point_types.h>
00045 
00046 #include <pcl/outofcore/octree_base.h>
00047 #include <pcl/outofcore/octree_base_node.h>
00048 #include <pcl/outofcore/octree_disk_container.h>
00049 
00050 namespace pcl
00051 {
00052   namespace outofcore
00053   {
00059     template<typename PointT, typename ContainerT>
00060     class OutofcoreIteratorBase : public std::iterator<std::forward_iterator_tag,     /*iterator type*/
00061                                                       const OutofcoreOctreeBaseNode<ContainerT, PointT>,
00062                                                        void,  /*no defined distance between iterator*/
00063                                                        const OutofcoreOctreeBaseNode<ContainerT, PointT>*,/*Pointer type*/
00064                                                        const OutofcoreOctreeBaseNode<ContainerT, PointT>&>/*Reference type*/
00065     {
00066       public:
00067         typedef typename pcl::outofcore::OutofcoreOctreeBase<ContainerT, PointT> OctreeDisk;
00068         typedef typename pcl::outofcore::OutofcoreOctreeBaseNode<ContainerT, PointT> OctreeDiskNode;
00069         
00070         typedef typename pcl::outofcore::OutofcoreOctreeBase<ContainerT, PointT>::BranchNode BranchNode;
00071         typedef typename pcl::outofcore::OutofcoreOctreeBase<ContainerT, PointT>::LeafNode LeafNode;
00072 
00073         typedef typename OctreeDisk::OutofcoreNodeType OutofcoreNodeType;
00074 
00075         explicit
00076         OutofcoreIteratorBase (OctreeDisk& octree_arg) 
00077           : octree_ (octree_arg), currentNode_ (NULL)
00078         {
00079           reset ();
00080         }
00081         
00082         virtual
00083         ~OutofcoreIteratorBase ()
00084         {
00085         }
00086 
00087         OutofcoreIteratorBase (const OutofcoreIteratorBase& src)
00088           : octree_ (src.octree_), currentNode_ (src.currentNode_)
00089         {
00090         }
00091 
00092         inline OutofcoreIteratorBase&
00093         operator = (const OutofcoreIteratorBase& src)
00094         {
00095           octree_ = src.octree_;
00096           currentNode_ = src.currentNode_;
00097           currentOctreeDepth_ = src.currentOctreeDepth_;
00098         }
00099         
00100         
00101         inline OutofcoreNodeType*
00102         operator* () const
00103         {
00104           return (this->getCurrentOctreeNode ());
00105         }
00106 
00107         virtual inline OutofcoreNodeType*
00108         getCurrentOctreeNode () const
00109         {
00110           return (currentNode_);
00111         }
00112         
00113         virtual inline void
00114         reset ()
00115         {
00116           currentNode_ = static_cast<OctreeDiskNode*> (octree_.getRootNode ());
00117           currentOctreeDepth_ = 0;
00118           max_depth_ = static_cast<unsigned int> (octree_.getDepth ());
00119         }
00120 
00121         inline void
00122         setMaxDepth (unsigned int max_depth)
00123         {
00124           if (max_depth > static_cast<unsigned int> (octree_.getDepth ()))
00125           {
00126             max_depth = static_cast<unsigned int> (octree_.getDepth ());
00127           }
00128 
00129           max_depth_ = max_depth;
00130         }
00131 
00132       protected:
00133         OctreeDisk& octree_;
00134         OctreeDiskNode* currentNode_;
00135         unsigned int currentOctreeDepth_;
00136         unsigned int max_depth_;
00137     };
00138 
00139 
00140 #if 0
00141     class PCL_EXPORTS OutofcoreBreadthFirstIterator : public OutofcoreIteratorBase
00142     {
00143       
00144 
00145 
00146 
00147     };
00148     
00149     class PCL_EXPORTS OutofcoreLeafIterator : public OutofcoreIteratorBase
00150     {
00151 
00152 
00153 
00154     };
00155 #endif
00156   }
00157 }
00158 
00159 #endif //PCL_OUTOFCORE_ITERATOR_BASE_H_


pcl
Author(s): Open Perception
autogenerated on Wed Aug 26 2015 15:27:30