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$
00037  */
00038 
00039 #ifndef PCL_OCTREE_NODE_H
00040 #define PCL_OCTREE_NODE_H
00041 
00042 #include <cstddef>
00043 
00044 #include <assert.h>
00045 #include <cstring>
00046 
00047 #include <string.h>
00048 
00049 #include <pcl/pcl_macros.h>
00050 
00051 #include "octree_container.h"
00052 
00053 namespace pcl
00054 {
00055   namespace octree
00056   {
00057 
00058     // enum of node types within the octree
00059     enum node_type_t
00060     {
00061       BRANCH_NODE, LEAF_NODE
00062     };
00063 
00065 
00069     class PCL_EXPORTS OctreeNode
00070     {
00071     public:
00072 
00073       OctreeNode ()
00074       {
00075       }
00076 
00077       virtual
00078       ~OctreeNode ()
00079       {
00080       }
00082       virtual node_type_t
00083       getNodeType () const = 0;
00084 
00086       virtual OctreeNode*
00087       deepCopy () const = 0;
00088 
00089     };
00090 
00092 
00097     template<typename ContainerT>
00098       class OctreeLeafNode : public OctreeNode
00099       {
00100       public:
00101 
00103         OctreeLeafNode () :
00104             OctreeNode ()
00105         {
00106         }
00107 
00109         OctreeLeafNode (const OctreeLeafNode& source) :
00110             OctreeNode ()
00111         {
00112           container_ = source.container_;
00113         }
00114 
00116         virtual
00117         ~OctreeLeafNode ()
00118         {
00119         }
00120 
00122         virtual OctreeLeafNode<ContainerT>*
00123         deepCopy () const
00124         {
00125           return new OctreeLeafNode<ContainerT> (*this);
00126         }
00127 
00129         virtual node_type_t
00130         getNodeType () const
00131         {
00132           return LEAF_NODE;
00133         }
00134 
00136         const ContainerT*
00137         operator->() const
00138         {
00139           return &container_;
00140         }
00141 
00143         ContainerT*
00144         operator-> ()
00145         {
00146           return &container_;
00147         }
00148 
00150         const ContainerT&
00151         operator* () const
00152         {
00153           return container_;
00154         }
00155 
00157         ContainerT&
00158         operator* ()
00159         {
00160           return container_;
00161         }
00162 
00164         const ContainerT&
00165         getContainer () const
00166         {
00167           return container_;
00168         }
00169 
00171         ContainerT&
00172         getContainer ()
00173         {
00174           return container_;
00175         }
00176 
00178         const ContainerT*
00179         getContainerPtr() const
00180         {
00181           return &container_;
00182         }
00183 
00185         ContainerT*
00186         getContainerPtr ()
00187         {
00188           return &container_;
00189         }
00190 
00191       protected:
00192         ContainerT container_;
00193       };
00194 
00196 
00200     template<typename ContainerT>
00201       class OctreeBranchNode : public OctreeNode
00202       {
00203       public:
00204 
00206         OctreeBranchNode () :
00207             OctreeNode()
00208         {
00209           // reset pointer to child node vectors
00210           memset (child_node_array_, 0, sizeof(child_node_array_));
00211         }
00212 
00214         OctreeBranchNode (const OctreeBranchNode& source) :
00215             OctreeNode()
00216         {
00217           unsigned char i;
00218 
00219           memset (child_node_array_, 0, sizeof(child_node_array_));
00220 
00221           for (i = 0; i < 8; ++i)
00222             if (source.child_node_array_[i])
00223               child_node_array_[i] = source.child_node_array_[i]->deepCopy ();
00224         }
00225 
00227         inline OctreeBranchNode&
00228         operator = (const OctreeBranchNode &source)
00229         {
00230           unsigned char i;
00231 
00232           memset (child_node_array_, 0, sizeof(child_node_array_));
00233 
00234           for (i = 0; i < 8; ++i)
00235             if (source.child_node_array_[i])
00236               child_node_array_[i] = source.child_node_array_[i]->deepCopy ();
00237           return (*this);
00238         }
00239 
00241         virtual OctreeBranchNode*
00242         deepCopy () const
00243         {
00244           return (new OctreeBranchNode<ContainerT> (*this));
00245         }
00246 
00248         virtual
00249         ~OctreeBranchNode ()
00250         {
00251         }
00252 
00257         inline OctreeNode*&
00258         operator[] (unsigned char child_idx_arg)
00259         {
00260           assert(child_idx_arg < 8);
00261           return child_node_array_[child_idx_arg];
00262         }
00263 
00268         inline OctreeNode*
00269         getChildPtr (unsigned char child_idx_arg) const
00270         {
00271           assert(child_idx_arg < 8);
00272           return child_node_array_[child_idx_arg];
00273         }
00274 
00278         inline void setChildPtr (OctreeNode* child, unsigned char index)
00279         {
00280           assert(index < 8);
00281           child_node_array_[index] = child;
00282         }
00283 
00284 
00289         inline bool hasChild (unsigned char child_idx_arg) const
00290         {
00291           return (child_node_array_[child_idx_arg] != 0);
00292         }
00293 
00294 
00299     /*    inline bool isPrunable () const
00300         {
00301           const OctreeNode* firstChild = child_node_array_[0];
00302           if (!firstChild || firstChild->getNodeType()==BRANCH_NODE)
00303             return false;
00304 
00305           bool prunable = true;
00306           for (unsigned char i = 1; i < 8 && prunable; ++i)
00307           {
00308             const OctreeNode* child = child_node_array_[i];
00309             if ( (!child) ||
00310                  (child->getNodeType()==BRANCH_NODE) ||
00311                  ((*static_cast<const OctreeContainerBase*>(child)) == (*static_cast<const OctreeContainerBase*>(child)) ) )
00312               prunable = false;
00313           }
00314 
00315           return prunable;
00316         }*/
00317 
00319         virtual node_type_t
00320         getNodeType () const
00321         {
00322           return BRANCH_NODE;
00323         }
00324 
00325         // reset node
00326         void reset()
00327         {
00328           memset(child_node_array_, 0, sizeof(child_node_array_));
00329           container_.reset();
00330         }
00331 
00332 
00334         const ContainerT*
00335         operator->() const
00336         {
00337           return &container_;
00338         }
00339 
00341         ContainerT*
00342         operator-> ()
00343         {
00344           return &container_;
00345         }
00346 
00348         const ContainerT&
00349         operator* () const
00350         {
00351           return container_;
00352         }
00353 
00355         ContainerT&
00356         operator* ()
00357         {
00358           return container_;
00359         }
00360 
00362         const ContainerT&
00363         getContainer () const
00364         {
00365           return container_;
00366         }
00367 
00369         ContainerT&
00370         getContainer ()
00371         {
00372           return container_;
00373         }
00374 
00376         const ContainerT*
00377         getContainerPtr() const
00378         {
00379           return &container_;
00380         }
00381 
00383         ContainerT*
00384         getContainerPtr ()
00385         {
00386           return &container_;
00387         }
00388 
00389       protected:
00390         OctreeNode* child_node_array_[8];
00391 
00392         ContainerT container_;
00393       };
00394   }
00395 }
00396 
00397 #endif


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