kdtree.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) 2009-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: kdtree.h 6121 2012-07-03 18:53:38Z aichim $
00037  *
00038  */
00039 
00040 #ifndef PCL_KDTREE_KDTREE_H_
00041 #define PCL_KDTREE_KDTREE_H_
00042 
00043 #include <limits.h>
00044 #include <pcl/pcl_macros.h>
00045 #include <pcl/point_cloud.h>
00046 #include <pcl/point_representation.h>
00047 #include <pcl/common/io.h>
00048 
00049 namespace pcl
00050 {
00055   template <typename PointT>
00056   class KdTree
00057   {
00058     public:
00059       typedef boost::shared_ptr <std::vector<int> > IndicesPtr;
00060       typedef boost::shared_ptr <const std::vector<int> > IndicesConstPtr;
00061 
00062       typedef pcl::PointCloud<PointT> PointCloud;
00063       typedef boost::shared_ptr<PointCloud> PointCloudPtr;
00064       typedef boost::shared_ptr<const PointCloud> PointCloudConstPtr;
00065 
00066       typedef pcl::PointRepresentation<PointT> PointRepresentation;
00067       //typedef boost::shared_ptr<PointRepresentation> PointRepresentationPtr;
00068       typedef boost::shared_ptr<const PointRepresentation> PointRepresentationConstPtr;
00069 
00070       // Boost shared pointers
00071       typedef boost::shared_ptr<KdTree<PointT> > Ptr;
00072       typedef boost::shared_ptr<const KdTree<PointT> > ConstPtr;
00073 
00077       KdTree (bool sorted = true) : input_(), indices_(), 
00078                                     epsilon_(0.0f), min_pts_(1), sorted_(sorted), 
00079                                     point_representation_ (new DefaultPointRepresentation<PointT>)
00080       {
00081       };
00082 
00087       virtual void
00088       setInputCloud (const PointCloudConstPtr &cloud, const IndicesConstPtr &indices = IndicesConstPtr ())
00089       {
00090         input_   = cloud;
00091         indices_ = indices;
00092       }
00093 
00095       inline IndicesConstPtr
00096       getIndices () const
00097       {
00098         return (indices_);
00099       }
00100 
00102       inline PointCloudConstPtr
00103       getInputCloud () const
00104       {
00105         return (input_);
00106       }
00107 
00111       inline void
00112       setPointRepresentation (const PointRepresentationConstPtr &point_representation)
00113       {
00114         point_representation_ = point_representation;
00115         setInputCloud (input_, indices_);  // Makes sense in derived classes to reinitialize the tree
00116       }
00117 
00119       inline PointRepresentationConstPtr
00120       getPointRepresentation () const
00121       {
00122         return (point_representation_);
00123       }
00124 
00126       virtual ~KdTree () {};
00127 
00136       virtual int 
00137       nearestKSearch (const PointT &p_q, int k, 
00138                       std::vector<int> &k_indices, std::vector<float> &k_sqr_distances) const = 0;
00139 
00156       virtual int 
00157       nearestKSearch (const PointCloud &cloud, int index, int k, 
00158                       std::vector<int> &k_indices, std::vector<float> &k_sqr_distances) const
00159       {
00160         assert (index >= 0 && index < static_cast<int> (cloud.points.size ()) && "Out-of-bounds error in nearestKSearch!");
00161         return (nearestKSearch (cloud.points[index], k, k_indices, k_sqr_distances));
00162       }
00163 
00173       template <typename PointTDiff> inline int 
00174       nearestKSearchT (const PointTDiff &point, int k, 
00175                        std::vector<int> &k_indices, std::vector<float> &k_sqr_distances) const
00176       {
00177         PointT p;
00178         // Copy all the data fields from the input cloud to the output one
00179         typedef typename pcl::traits::fieldList<PointT>::type FieldListInT;
00180         typedef typename pcl::traits::fieldList<PointTDiff>::type FieldListOutT;
00181         typedef typename pcl::intersect<FieldListInT, FieldListOutT>::type FieldList;
00182         pcl::for_each_type <FieldList> (pcl::NdConcatenateFunctor <PointTDiff, PointT> (point, p));
00183         return (nearestKSearch (p, k, k_indices, k_sqr_distances));
00184       }
00185 
00203       virtual int 
00204       nearestKSearch (int index, int k, 
00205                       std::vector<int> &k_indices, std::vector<float> &k_sqr_distances) const
00206       {
00207         if (indices_ == NULL)
00208         {
00209           assert (index >= 0 && index < static_cast<int> (input_->points.size ()) && "Out-of-bounds error in nearestKSearch!");
00210           return (nearestKSearch (input_->points[index], k, k_indices, k_sqr_distances));
00211         }
00212         else
00213         {
00214           assert (index >= 0 && index < static_cast<int> (indices_->size ()) && "Out-of-bounds error in nearestKSearch!");
00215           return (nearestKSearch (input_->points[(*indices_)[index]], k, k_indices, k_sqr_distances));
00216         }
00217       }
00218 
00229       virtual int 
00230       radiusSearch (const PointT &p_q, double radius, std::vector<int> &k_indices,
00231                     std::vector<float> &k_sqr_distances, unsigned int max_nn = 0) const = 0;
00232 
00250       virtual int 
00251       radiusSearch (const PointCloud &cloud, int index, double radius, 
00252                     std::vector<int> &k_indices, std::vector<float> &k_sqr_distances, 
00253                     unsigned int max_nn = 0) const
00254       {
00255         assert (index >= 0 && index < static_cast<int> (cloud.points.size ()) && "Out-of-bounds error in radiusSearch!");
00256         return (radiusSearch(cloud.points[index], radius, k_indices, k_sqr_distances, max_nn));
00257       }
00258 
00269       template <typename PointTDiff> inline int 
00270       radiusSearchT (const PointTDiff &point, double radius, std::vector<int> &k_indices,
00271                      std::vector<float> &k_sqr_distances, unsigned int max_nn = 0) const
00272       {
00273         PointT p;
00274         // Copy all the data fields from the input cloud to the output one
00275         typedef typename pcl::traits::fieldList<PointT>::type FieldListInT;
00276         typedef typename pcl::traits::fieldList<PointTDiff>::type FieldListOutT;
00277         typedef typename pcl::intersect<FieldListInT, FieldListOutT>::type FieldList;
00278         pcl::for_each_type <FieldList> (pcl::NdConcatenateFunctor <PointTDiff, PointT> (point, p));
00279         return (radiusSearch (p, radius, k_indices, k_sqr_distances, max_nn));
00280       }
00281 
00301       virtual int 
00302       radiusSearch (int index, double radius, std::vector<int> &k_indices,
00303                     std::vector<float> &k_sqr_distances, unsigned int max_nn = 0) const
00304       {
00305         if (indices_ == NULL)
00306         {
00307           assert (index >= 0 && index < static_cast<int> (input_->points.size ()) && "Out-of-bounds error in radiusSearch!");
00308           return (radiusSearch (input_->points[index], radius, k_indices, k_sqr_distances, max_nn));
00309         }
00310         else
00311         {
00312           assert (index >= 0 && index < static_cast<int> (indices_->size ()) && "Out-of-bounds error in radiusSearch!");
00313           return (radiusSearch (input_->points[(*indices_)[index]], radius, k_indices, k_sqr_distances, max_nn));
00314         }
00315       }
00316 
00320       virtual inline void
00321       setEpsilon (float eps)
00322       {
00323         epsilon_ = eps;
00324       }
00325 
00327       inline float
00328       getEpsilon () const
00329       {
00330         return (epsilon_);
00331       }
00332 
00336       inline void
00337       setMinPts (int min_pts)
00338       {
00339         min_pts_ = min_pts;
00340       }
00341 
00343       inline int
00344       getMinPts () const
00345       {
00346         return (min_pts_);
00347       }
00348 
00349     protected:
00351       PointCloudConstPtr input_;
00352 
00354       IndicesConstPtr indices_;
00355 
00357       float epsilon_;
00358 
00360       int min_pts_;
00361 
00363       bool sorted_;
00364 
00366       PointRepresentationConstPtr point_representation_;
00367 
00369       virtual std::string 
00370       getName () const = 0;
00371   };
00372 }
00373 
00374 #endif  //#ifndef _PCL_KDTREE_KDTREE_H_


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