outofcore_breadth_first_iterator.hpp
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: outofcore_depth_first_iterator.hpp 7938 2012-11-14 06:27:39Z jrosen $
00037  */
00038 
00039 #ifndef PCL_OUTOFCORE_BREADTH_FIRST_ITERATOR_IMPL_H_
00040 #define PCL_OUTOFCORE_BREADTH_FIRST_ITERATOR_IMPL_H_
00041 
00042 namespace pcl
00043 {
00044   namespace outofcore
00045   {
00046 
00047     template<typename PointT, typename ContainerT> 
00048     OutofcoreBreadthFirstIterator<PointT, ContainerT>::OutofcoreBreadthFirstIterator (OutofcoreOctreeBase<ContainerT, PointT>& octree_arg)
00049     : OutofcoreIteratorBase<PointT, ContainerT> (octree_arg)
00050     {
00051       reset();
00052     }
00053 
00055 
00056     template<typename PointT, typename ContainerT> 
00057     OutofcoreBreadthFirstIterator<PointT, ContainerT>::~OutofcoreBreadthFirstIterator ()
00058     {
00059     }
00060 
00062 
00063     template<typename PointT, typename ContainerT>
00064     OutofcoreBreadthFirstIterator<PointT, ContainerT>&
00065     OutofcoreBreadthFirstIterator<PointT, ContainerT>::operator++ ()
00066     {
00067       if (FIFO_.size ())
00068       {
00069         // Get the first entry from the FIFO queue
00070         OctreeDiskNode *node = FIFO_.front ();
00071         FIFO_.pop_front ();
00072 
00073         // If not skipping children, not at the max specified depth and we're a branch then iterate over children
00074         if (!skip_child_voxels_ && node->getDepth () < this->max_depth_ && node->getNodeType () == pcl::octree::BRANCH_NODE)
00075         {
00076           // Get the branch node
00077           BranchNode* branch = static_cast<BranchNode*> (node);
00078           OctreeDiskNode* child = 0;
00079 
00080           // Iterate over the branches children
00081           for (unsigned char child_idx = 0; child_idx < 8 ; child_idx++)
00082           {
00083             // If child/index exists add it to FIFO queue
00084             child = this->octree_.getBranchChildPtr (*branch, child_idx);
00085             if (child)
00086             {
00087               FIFO_.push_back (child);
00088             }
00089           }
00090         }
00091       }
00092 
00093       // Reset skipped children
00094       skip_child_voxels_ = false;
00095 
00096       // If there's a queue, set the current node to the first entry
00097       if (FIFO_.size ())
00098       {
00099         this->currentNode_ = FIFO_.front ();
00100       }
00101       else
00102       {
00103         this->currentNode_ = NULL;
00104       }
00105 
00106       return (*this);
00107     }
00108 
00110 
00111   }//namesapce pcl
00112 }//namespace outofcore
00113 
00114 #endif //PCL_OUTOFCORE_BREADTH_FIRST_ITERATOR_IMPL_H_
00115 


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