00001 /* 00002 * Software License Agreement (BSD License) 00003 * 00004 * Point Cloud Library (PCL) - www.pointclouds.org 00005 * Copyright (c) 2012, Jeremie Papon 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 * Author : jpapon@gmail.com 00037 * Email : jpapon@gmail.com 00038 */ 00039 00040 #ifndef PCL_OCTREE_POINTCLOUD_ADJACENCY_CONTAINER_H_ 00041 #define PCL_OCTREE_POINTCLOUD_ADJACENCY_CONTAINER_H_ 00042 00043 namespace pcl 00044 { 00045 00046 namespace octree 00047 { 00053 template<typename PointInT, typename DataT = PointInT> 00054 class OctreePointCloudAdjacencyContainer : public OctreeContainerBase 00055 { 00056 public: 00057 typedef std::set<OctreePointCloudAdjacencyContainer*> NeighborSetT; 00058 //iterators to neighbors 00059 typedef typename NeighborSetT::iterator iterator; 00060 typedef typename NeighborSetT::const_iterator const_iterator; 00061 inline iterator begin () { return (neighbors_.begin ()); } 00062 inline iterator end () { return (neighbors_.end ()); } 00063 inline const_iterator begin () const { return (neighbors_.begin ()); } 00064 inline const_iterator end () const { return (neighbors_.end ()); } 00065 //size of neighbors 00066 inline size_t size () const { return neighbors_.size (); } 00067 //insert for neighbors 00068 inline std::pair<iterator, bool> insert (OctreePointCloudAdjacencyContainer* neighbor) { return neighbors_.insert (neighbor); } 00069 00071 OctreePointCloudAdjacencyContainer () : 00072 OctreeContainerBase () 00073 { 00074 this->reset(); 00075 } 00076 00078 virtual ~OctreePointCloudAdjacencyContainer () 00079 { 00080 } 00081 00083 virtual OctreePointCloudAdjacencyContainer * 00084 deepCopy () const 00085 { 00086 OctreePointCloudAdjacencyContainer *new_container = new OctreePointCloudAdjacencyContainer; 00087 new_container->setNeighbors (this->neighbors_); 00088 new_container->setPointCounter (this->num_points_); 00089 return new_container; 00090 } 00091 00097 void 00098 addPoint (const PointInT& new_point) 00099 { 00100 using namespace pcl::common; 00101 ++num_points_; 00102 } 00103 00106 void 00107 computeData () 00108 { 00109 } 00110 00112 int 00113 getPointCounter () const { return num_points_; } 00114 00116 void 00117 setPointCounter (int points_arg) { num_points_ = points_arg; } 00118 00120 virtual void 00121 reset () 00122 { 00123 neighbors_.clear (); 00124 num_points_ = 0; 00125 data_ = DataT (); 00126 } 00127 00131 void 00132 addNeighbor (OctreePointCloudAdjacencyContainer *neighbor) 00133 { 00134 neighbors_.insert (neighbor); 00135 } 00136 00140 void 00141 removeNeighbor (OctreePointCloudAdjacencyContainer *neighbor) 00142 { 00143 neighbors_.erase (neighbor); 00144 00145 } 00146 00150 size_t 00151 getNumNeighbors () const 00152 { 00153 return neighbors_.size (); 00154 } 00155 00159 void 00160 setNeighbors (const NeighborSetT &neighbor_arg) 00161 { 00162 neighbors_ = neighbor_arg; 00163 } 00164 00166 DataT& 00167 getData () { return data_; } 00168 00172 void 00173 setData (const DataT& data_arg) { data_ = data_arg;} 00174 00178 virtual size_t 00179 getSize () 00180 { 00181 return num_points_; 00182 } 00183 00184 00185 private: 00186 int num_points_; 00187 NeighborSetT neighbors_; 00188 DataT data_; 00189 }; 00190 } 00191 } 00192 00193 #endif