octree_nodes.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-2011, 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: octree_nodes.h 6119 2012-07-03 18:50:04Z aichim $
00037  */
00038 
00039 #ifndef OCTREE_NODE_H
00040 #define OCTREE_NODE_H
00041 
00042 #include <string>
00043 #include <vector>
00044 #include <cstddef>
00045 
00046 #include <assert.h>
00047 
00048 #include <pcl/pcl_macros.h>
00049 
00050 using namespace std;
00051 
00052 namespace pcl
00053 {
00054   namespace octree
00055   {
00056 
00057     // enum of node types within the octree
00058     enum node_type_t
00059     {
00060       BRANCH_NODE, LEAF_NODE
00061     };
00062 
00064 
00068     class PCL_EXPORTS OctreeNode
00069     {
00070     public:
00071 
00072       OctreeNode ()
00073       {
00074       }
00075 
00076       virtual
00077       ~OctreeNode ()
00078       {
00079       }
00081       virtual node_type_t
00082       getNodeType () const = 0;
00083 
00085       virtual OctreeNode*
00086       deepCopy () const = 0;
00087 
00088     };
00089 
00091 
00096     template<typename ContainerT>
00097       class OctreeLeafNode : public OctreeNode, public ContainerT
00098       {
00099       public:
00100 
00101         using ContainerT::getSize;
00102         using ContainerT::getData;
00103         using ContainerT::setData;
00104 
00106         OctreeLeafNode () :
00107             OctreeNode (), ContainerT ()
00108         {
00109         }
00110 
00112         OctreeLeafNode (const OctreeLeafNode& source) :
00113             OctreeNode (), ContainerT (source)
00114         {
00115         }
00116 
00118         virtual
00119         ~OctreeLeafNode ()
00120         {
00121         }
00122 
00124         virtual OctreeLeafNode<ContainerT>*
00125         deepCopy () const
00126         {
00127           return new OctreeLeafNode<ContainerT> (*this);
00128         }
00129 
00131         virtual node_type_t
00132         getNodeType () const
00133         {
00134           return LEAF_NODE;
00135         }
00136 
00138         inline
00139         void
00140         reset ()
00141         {
00142           ContainerT::reset ();
00143         }
00144 
00145       };
00146 
00148 
00152     template<typename ContainerT>
00153       class OctreeBranchNode : public OctreeNode, ContainerT
00154       {
00155       public:
00156 
00157         using ContainerT::getSize;
00158         using ContainerT::getData;
00159         using ContainerT::setData;
00160 
00162         OctreeBranchNode () :
00163             ContainerT ()
00164         {
00165           // reset pointer to child node vectors
00166           memset (childNodeArray_, 0, sizeof(childNodeArray_));
00167         }
00168 
00170         OctreeBranchNode (const OctreeBranchNode& source) :
00171             ContainerT (source)
00172         {
00173           unsigned char i;
00174 
00175           memset (childNodeArray_, 0, sizeof(childNodeArray_));
00176 
00177           for (i = 0; i < 8; ++i)
00178             if (source.childNodeArray_[i])
00179               childNodeArray_[i] = source.childNodeArray_[i]->deepCopy ();
00180         }
00181 
00183         inline OctreeBranchNode&
00184         operator = (const OctreeBranchNode &source)
00185         {
00186           unsigned char i;
00187 
00188           memset (childNodeArray_, 0, sizeof(childNodeArray_));
00189 
00190           for (i = 0; i < 8; ++i)
00191             if (source.childNodeArray_[i])
00192               childNodeArray_[i] = source.childNodeArray_[i]->deepCopy ();
00193           return (*this);
00194         }
00195 
00197         virtual OctreeBranchNode*
00198         deepCopy () const
00199         {
00200           return (new OctreeBranchNode<ContainerT> (*this));
00201         }
00202 
00204         virtual
00205         ~OctreeBranchNode ()
00206         {
00207         }
00208 
00209         inline
00210         void
00211         reset ()
00212         {
00213           memset (childNodeArray_, 0, sizeof(childNodeArray_));
00214           ContainerT::reset ();
00215         }
00216 
00221         inline OctreeNode*&
00222         operator[] (unsigned char childIdx_arg)
00223         {
00224           assert(childIdx_arg < 8);
00225           return childNodeArray_[childIdx_arg];
00226         }
00227 
00232         inline OctreeNode*
00233         getChildPtr (unsigned char childIdx_arg) const
00234         {
00235           assert(childIdx_arg < 8);
00236           return childNodeArray_[childIdx_arg];
00237         }
00238 
00242         inline void setChildPtr (OctreeNode* child, unsigned char index)
00243         {
00244           assert(index < 8);
00245           childNodeArray_[index] = child;
00246         }
00247 
00248 
00253         inline bool hasChild (unsigned char childIdx_arg) const
00254         {
00255           return (childNodeArray_[childIdx_arg] != 0);
00256         }
00257 
00259         virtual node_type_t
00260         getNodeType () const
00261         {
00262           return BRANCH_NODE;
00263         }
00264 
00265       protected:
00266         OctreeNode* childNodeArray_[8];
00267       };
00268   }
00269 }
00270 
00271 #endif


pcl
Author(s): Open Perception
autogenerated on Mon Oct 6 2014 03:15:57