octree_container.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 5596 2012-04-17 15:09:31Z jkammerl $
00037  */
00038 
00039 #ifndef PCL_OCTREE_CONTAINER_H
00040 #define PCL_OCTREE_CONTAINER_H
00041 
00042 #include <string.h>
00043 #include <vector>
00044 #include <cstddef>
00045 
00046 #include <pcl/pcl_macros.h>
00047 
00048 namespace pcl
00049 {
00050   namespace octree
00051   {
00053 
00056     class OctreeContainerBase
00057     {
00058     public:
00060       OctreeContainerBase ()
00061       {
00062       }
00063 
00065       OctreeContainerBase (const OctreeContainerBase&)
00066       {
00067       }
00068 
00070       virtual
00071       ~OctreeContainerBase ()
00072       {
00073       }
00074 
00077       virtual bool
00078       operator== (const OctreeContainerBase&) const
00079       {
00080         return false;
00081       }
00082 
00086       bool
00087       operator!= (const OctreeContainerBase& other) const
00088       {
00089         return (!operator== (other));
00090       }
00091 
00095       virtual size_t
00096       getSize ()
00097       {
00098         return 0u;
00099       }
00100 
00102       virtual void
00103       reset () = 0;
00104 
00107       void
00108       addPointIndex (const int&)
00109       {
00110       }
00111 
00114       void
00115       getPointIndex (int&) const
00116       {
00117       }
00118 
00121       void
00122       getPointIndices (std::vector<int>&) const
00123       {
00124       }
00125 
00126     };
00127 
00129 
00134     class OctreeContainerEmpty : public OctreeContainerBase
00135     {
00136     public:
00138       OctreeContainerEmpty () :
00139           OctreeContainerBase ()
00140       {
00141       }
00142 
00144       OctreeContainerEmpty (const OctreeContainerEmpty&) :
00145           OctreeContainerBase ()
00146       {
00147       }
00148 
00150       virtual
00151       ~OctreeContainerEmpty ()
00152       {
00153       }
00154 
00156       virtual OctreeContainerEmpty *
00157       deepCopy () const
00158       {
00159         return (new OctreeContainerEmpty (*this));
00160       }
00161 
00165       virtual size_t
00166       getSize () const
00167       {
00168         return 0;
00169       }
00170 
00172       virtual void
00173       reset ()
00174       {
00175 
00176       }
00177 
00180       void
00181       addPointIndex (int)
00182       {
00183       }
00184 
00187       int
00188       getPointIndex () const
00189       {
00190         assert("getPointIndex: undefined point index");
00191         return -1;
00192       }
00193 
00196       void
00197       getPointIndices (std::vector<int>&) const
00198       {
00199       }
00200 
00201     };
00202 
00204 
00208       class OctreeContainerPointIndex : public OctreeContainerBase
00209       {
00210       public:
00212         OctreeContainerPointIndex () :
00213             OctreeContainerBase (), data_ ()
00214         {
00215           reset ();
00216         }
00217 
00219         OctreeContainerPointIndex (const OctreeContainerPointIndex& source) :
00220             OctreeContainerBase (), data_ (source.data_)
00221         {
00222         }
00223 
00225         virtual
00226         ~OctreeContainerPointIndex ()
00227         {
00228         }
00229 
00231         virtual OctreeContainerPointIndex*
00232         deepCopy () const
00233         {
00234           return (new OctreeContainerPointIndex (*this));
00235         }
00236 
00240         virtual bool
00241         operator== (const OctreeContainerBase& other) const
00242         {
00243           const OctreeContainerPointIndex* otherConDataT = dynamic_cast<const OctreeContainerPointIndex*> (&other);
00244 
00245           return (this->data_ == otherConDataT->data_);
00246         }
00247 
00251         void
00252         addPointIndex (int data_arg)
00253         {
00254           data_ = data_arg;
00255         }
00256 
00260         int
00261         getPointIndex () const
00262         {
00263           return data_;
00264         }
00265 
00269         void
00270         getPointIndices (std::vector<int>& data_vector_arg) const
00271         {
00272           if (data_>=0)
00273           data_vector_arg.push_back (data_);
00274         }
00275 
00279         size_t
00280         getSize () const
00281         {
00282           return data_<0 ? 0 : 1;
00283         }
00284 
00286         virtual void
00287         reset ()
00288         {
00289           data_ = -1;
00290         }
00291       protected:
00293         int data_;
00294       };
00295 
00297 
00301       class OctreeContainerPointIndices : public OctreeContainerBase
00302       {
00303       public:
00305         OctreeContainerPointIndices () :
00306           OctreeContainerBase (), leafDataTVector_ ()
00307         {
00308         }
00309 
00311         OctreeContainerPointIndices (const OctreeContainerPointIndices& source) :
00312             OctreeContainerBase (), leafDataTVector_ (source.leafDataTVector_)
00313         {
00314         }
00315 
00317         virtual
00318         ~OctreeContainerPointIndices ()
00319         {
00320         }
00321 
00323         virtual OctreeContainerPointIndices *
00324         deepCopy () const
00325         {
00326           return (new OctreeContainerPointIndices (*this));
00327         }
00328 
00332         virtual bool
00333         operator== (const OctreeContainerBase& other) const
00334         {
00335           const OctreeContainerPointIndices* otherConDataTVec = dynamic_cast<const OctreeContainerPointIndices*> (&other);
00336 
00337           return (this->leafDataTVector_ == otherConDataTVec->leafDataTVector_);
00338         }
00339 
00343         void
00344         addPointIndex (int data_arg)
00345         {
00346           leafDataTVector_.push_back (data_arg);
00347         }
00348 
00352         int
00353         getPointIndex ( ) const
00354         {
00355           return leafDataTVector_.back ();
00356         }
00357 
00361         void
00362         getPointIndices (std::vector<int>& data_vector_arg) const
00363         {
00364           data_vector_arg.insert (data_vector_arg.end (), leafDataTVector_.begin (), leafDataTVector_.end ());
00365         }
00366 
00370         std::vector<int>&
00371         getPointIndicesVector ()
00372         {
00373           return leafDataTVector_;
00374         }
00375 
00379         size_t
00380         getSize () const
00381         {
00382           return leafDataTVector_.size ();
00383         }
00384 
00386         virtual void
00387         reset ()
00388         {
00389           leafDataTVector_.clear ();
00390         }
00391 
00392       protected:
00394         std::vector<int> leafDataTVector_;
00395       };
00396 
00397   }
00398 }
00399 
00400 #endif


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