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 OCTREE_CONTAINER_H
00040 #define OCTREE_CONTAINER_H
00041 
00042 #include <string.h>
00043 #include <vector>
00044 #include <cstddef>
00045 
00046 #include <pcl/pcl_macros.h>
00047 
00048 using namespace std;
00049 
00050 namespace pcl
00051 {
00052   namespace octree
00053   {
00055 
00059     template<typename DataT>
00060       class OctreeContainerEmpty
00061       {
00062       public:
00064         OctreeContainerEmpty ()
00065         {
00066         }
00067 
00069         OctreeContainerEmpty (const OctreeContainerEmpty&)
00070         {
00071         }
00072 
00074         virtual
00075         ~OctreeContainerEmpty ()
00076         {
00077         }
00078 
00080         virtual OctreeContainerEmpty *
00081         deepCopy () const
00082         {
00083           return (new OctreeContainerEmpty (*this));
00084         }
00085 
00089         void
00090         setData (const DataT&)
00091         {
00092         }
00093 
00096         void
00097         getData (DataT&) const
00098         {
00099         }
00100 
00101 
00105         void
00106         getData (std::vector<DataT>&) const
00107         {
00108         }
00109 
00113         size_t
00114         getSize () const
00115         {
00116           return 0;
00117         }
00118 
00120         void
00121         reset ()
00122         {
00123         }
00124       };
00125 
00127 
00131     template<typename DataT>
00132       class OctreeContainerDataT
00133       {
00134       public:
00136         OctreeContainerDataT () :
00137             data_ (),
00138             isEmpty_(true)
00139         {
00140           reset ();
00141         }
00142 
00144         OctreeContainerDataT (const OctreeContainerDataT& source) :
00145             data_ (source.data_), isEmpty_ (source.isEmpty_)
00146         {
00147         }
00148 
00150         virtual
00151         ~OctreeContainerDataT ()
00152         {
00153         }
00154 
00156         virtual OctreeContainerDataT*
00157         deepCopy () const
00158         {
00159           return (new OctreeContainerDataT (*this));
00160         }
00161 
00165         void
00166         setData (const DataT& data_arg)
00167         {
00168           this->data_ = data_arg;
00169           isEmpty_ = false;
00170         }
00171 
00175         void
00176         getData (DataT& dataVector_arg) const
00177         {
00178           if (!isEmpty_)
00179             dataVector_arg = this->data_;
00180         }
00181 
00185         void
00186         getData (vector<DataT>& dataVector_arg) const
00187         {
00188           if (!isEmpty_)
00189             dataVector_arg.push_back (this->data_);
00190         }
00191 
00195         size_t
00196         getSize () const
00197         {
00198           return isEmpty_ ? 0 : 1;
00199         }
00200 
00202         void
00203         reset ()
00204         {
00205           isEmpty_ = true;
00206         }
00207       protected:
00209         DataT data_;
00210 
00212         bool isEmpty_;
00213       };
00214 
00216 
00220     template<typename DataT>
00221       class OctreeContainerDataTVector
00222       {
00223       public:
00225         OctreeContainerDataTVector () :
00226             leafDataTVector_ ()
00227         {
00228         }
00229 
00231         OctreeContainerDataTVector (const OctreeContainerDataTVector& source) :
00232             leafDataTVector_ (source.leafDataTVector_)
00233         {
00234         }
00235 
00237         virtual
00238         ~OctreeContainerDataTVector ()
00239         {
00240         }
00241 
00243         virtual OctreeContainerDataTVector *
00244         deepCopy () const
00245         {
00246           return (new OctreeContainerDataTVector (*this));
00247         }
00248 
00252         void
00253         setData (const DataT& data_arg)
00254         {
00255           leafDataTVector_.push_back (data_arg);
00256         }
00257 
00261         void
00262         getData (DataT& data_arg) const
00263         {
00264           if (leafDataTVector_.size () > 0)
00265             data_arg = leafDataTVector_.back ();
00266         }
00267 
00271         void
00272         getData (std::vector<DataT>& dataVector_arg) const
00273         {
00274           dataVector_arg.insert (dataVector_arg.end (),
00275               leafDataTVector_.begin (), leafDataTVector_.end ());
00276         }
00277 
00281         const std::vector<DataT>& getDataTVector () const
00282         {
00283           return leafDataTVector_;
00284         }
00285 
00289         size_t
00290         getSize () const
00291         {
00292           return leafDataTVector_.size ();
00293         }
00294 
00296         void
00297         reset ()
00298         {
00299           leafDataTVector_.clear ();
00300         }
00301 
00302       protected:
00304         vector<DataT> leafDataTVector_;
00305       };
00306 
00307   }
00308 }
00309 
00310 #endif


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