search.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: search.h 4914 2012-03-05 17:26:23Z rusu $
00037  *
00038  */
00039 
00040 #ifndef PCL_SEARCH_SEARCH_H_
00041 #define PCL_SEARCH_SEARCH_H_
00042 
00043 #include <pcl/point_cloud.h>
00044 #include <pcl/common/io.h>
00045 
00046 namespace pcl
00047 {
00048   namespace search
00049   {
00072     template<typename PointT>
00073     class Search
00074     {
00075       public:
00076         typedef pcl::PointCloud<PointT> PointCloud;
00077         typedef typename PointCloud::Ptr PointCloudPtr;
00078         typedef typename PointCloud::ConstPtr PointCloudConstPtr;
00079 
00080         typedef boost::shared_ptr<pcl::search::Search<PointT> > Ptr;
00081         typedef boost::shared_ptr<const pcl::search::Search<PointT> > ConstPtr;
00082 
00083         typedef boost::shared_ptr<std::vector<int> > IndicesPtr;
00084         typedef boost::shared_ptr<const std::vector<int> > IndicesConstPtr;
00085 
00087         Search (const std::string& name = "", bool sorted = false)
00088           : input_ () 
00089           , indices_ ()
00090           , sorted_results_ (sorted)
00091           , name_ (name)
00092         {
00093         }
00094 
00096         virtual
00097         ~Search ()
00098         {
00099         }
00100 
00103         virtual const std::string& 
00104         getName () const
00105         {
00106           return (name_);
00107         }
00108 
00113         virtual void 
00114         setSortedResults (bool sorted)
00115         {
00116           sorted_results_ = sorted;
00117         }
00118         
00123         virtual void
00124         setInputCloud (const PointCloudConstPtr& cloud, const IndicesConstPtr &indices = IndicesConstPtr ())
00125         {
00126           input_ = cloud;
00127           indices_ = indices;
00128         }
00129 
00131         virtual PointCloudConstPtr
00132         getInputCloud () const
00133         {
00134           return (input_);
00135         }
00136 
00138         virtual IndicesConstPtr
00139         getIndices () const
00140         {
00141           return (indices_);
00142         }
00143 
00152         virtual int
00153         nearestKSearch (const PointT &point, int k, std::vector<int> &k_indices,
00154                         std::vector<float> &k_sqr_distances) const = 0;
00155 
00165         template <typename PointTDiff> inline int
00166         nearestKSearchT (const PointTDiff &point, int k,
00167                          std::vector<int> &k_indices, std::vector<float> &k_sqr_distances) const
00168         {
00169           PointT p;
00170           // Copy all the data fields from the input cloud to the output one
00171           typedef typename pcl::traits::fieldList<PointT>::type FieldListInT;
00172           typedef typename pcl::traits::fieldList<PointTDiff>::type FieldListOutT;
00173           typedef typename pcl::intersect<FieldListInT, FieldListOutT>::type FieldList;
00174           pcl::for_each_type <FieldList> (pcl::NdConcatenateFunctor <PointTDiff, PointT> (point, p));
00175           return (nearestKSearch (p, k, k_indices, k_sqr_distances));
00176         }
00177 
00194         virtual int
00195         nearestKSearch (const PointCloud &cloud, int index, int k,
00196                         std::vector<int> &k_indices, std::vector<float> &k_sqr_distances) const
00197         {
00198           assert (index >= 0 && index < static_cast<int> (cloud.points.size ()) && "Out-of-bounds error in nearestKSearch!");
00199           return (nearestKSearch (cloud.points[index], k, k_indices, k_sqr_distances));
00200         }
00201 
00219         virtual int
00220         nearestKSearch (int index, int k,
00221                         std::vector<int> &k_indices, std::vector<float> &k_sqr_distances) const
00222         {
00223           if (indices_ == NULL)
00224           {
00225             assert (index >= 0 && index < static_cast<int> (input_->points.size ()) && "Out-of-bounds error in nearestKSearch!");
00226             return (nearestKSearch (input_->points[index], k, k_indices, k_sqr_distances));
00227           }
00228           else
00229           {
00230             assert (index >= 0 && index < static_cast<int> (indices_->size ()) && "Out-of-bounds error in nearestKSearch!");
00231             if (index >= static_cast<int> (indices_->size ()) || index < 0)
00232               return (0);
00233             return (nearestKSearch (input_->points[(*indices_)[index]], k, k_indices, k_sqr_distances));
00234           }
00235         }
00236 
00244         virtual void
00245         nearestKSearch (const PointCloud& cloud, const std::vector<int>& indices, int k, std::vector< std::vector<int> >& k_indices,
00246                         std::vector< std::vector<float> >& k_sqr_distances) const
00247         {
00248           if (indices.empty ())
00249           {
00250             k_indices.resize (cloud.size ());
00251             k_sqr_distances.resize (cloud.size ());
00252             for (size_t i = 0; i < cloud.size (); i++)
00253               nearestKSearch (cloud, static_cast<int> (i), k, k_indices[i], k_sqr_distances[i]);
00254           }
00255           else
00256           {
00257             k_indices.resize (indices.size ());
00258             k_sqr_distances.resize (indices.size ());
00259             for (size_t i = 0; i < indices.size (); i++)
00260               nearestKSearch (cloud, indices[i], k, k_indices[i], k_sqr_distances[i]);
00261           }
00262         }
00263 
00272         template <typename PointTDiff> void
00273         nearestKSearchT (const pcl::PointCloud<PointTDiff> &cloud, const std::vector<int>& indices, int k, std::vector< std::vector<int> > &k_indices,
00274                          std::vector< std::vector<float> > &k_sqr_distances) const
00275         {
00276           // Copy all the data fields from the input cloud to the output one
00277           typedef typename pcl::traits::fieldList<PointT>::type FieldListInT;
00278           typedef typename pcl::traits::fieldList<PointTDiff>::type FieldListOutT;
00279           typedef typename pcl::intersect<FieldListInT, FieldListOutT>::type FieldList;
00280 
00281           pcl::PointCloud<PointT> pc;
00282           if (indices.empty ())
00283           {
00284             pc.resize (cloud.size());
00285             for (size_t i = 0; i < cloud.size(); i++)
00286             {
00287               pcl::for_each_type <FieldList> (pcl::NdConcatenateFunctor <PointTDiff, PointT> (
00288                                               cloud[i], pc[i]));
00289             }
00290             nearestKSearch (pc,std::vector<int>(),k,k_indices,k_sqr_distances);
00291           }
00292           else
00293           {
00294             pc.resize (indices.size());
00295             for (size_t i = 0; i < indices.size(); i++)
00296             {
00297               pcl::for_each_type <FieldList> (pcl::NdConcatenateFunctor <PointTDiff, PointT> (
00298                                               cloud[indices[i]], pc[i]));
00299             }
00300             nearestKSearch (pc,std::vector<int>(),k,k_indices,k_sqr_distances);
00301           }
00302         }
00303 
00314         virtual int
00315         radiusSearch (const PointT& point, double radius, std::vector<int>& k_indices,
00316                       std::vector<float>& k_sqr_distances, unsigned int max_nn = 0) const = 0;
00317 
00328         template <typename PointTDiff> inline int
00329         radiusSearchT (const PointTDiff &point, double radius, std::vector<int> &k_indices,
00330                        std::vector<float> &k_sqr_distances, unsigned int max_nn = 0) const
00331         {
00332           PointT p;
00333           // Copy all the data fields from the input cloud to the output one
00334           typedef typename pcl::traits::fieldList<PointT>::type FieldListInT;
00335           typedef typename pcl::traits::fieldList<PointTDiff>::type FieldListOutT;
00336           typedef typename pcl::intersect<FieldListInT, FieldListOutT>::type FieldList;
00337           pcl::for_each_type <FieldList> (pcl::NdConcatenateFunctor <PointTDiff, PointT> (point, p));
00338           return (radiusSearch (p, radius, k_indices, k_sqr_distances, max_nn));
00339         }
00340 
00358         virtual int
00359         radiusSearch (const PointCloud &cloud, int index, double radius,
00360                       std::vector<int> &k_indices, std::vector<float> &k_sqr_distances,
00361                       unsigned int max_nn = 0) const
00362         {
00363           assert (index >= 0 && index < static_cast<int> (cloud.points.size ()) && "Out-of-bounds error in radiusSearch!");
00364           return (radiusSearch(cloud.points[index], radius, k_indices, k_sqr_distances, max_nn));
00365         }
00366 
00386         virtual int
00387         radiusSearch (int index, double radius, std::vector<int> &k_indices,
00388                       std::vector<float> &k_sqr_distances, unsigned int max_nn = 0) const
00389         {
00390           if (indices_ == NULL)
00391           {
00392             assert (index >= 0 && index < static_cast<int> (input_->points.size ()) && "Out-of-bounds error in radiusSearch!");
00393             return (radiusSearch (input_->points[index], radius, k_indices, k_sqr_distances, max_nn));
00394           }
00395           else
00396           {
00397             assert (index >= 0 && index < static_cast<int> (indices_->size ()) && "Out-of-bounds error in radiusSearch!");
00398             return (radiusSearch (input_->points[(*indices_)[index]], radius, k_indices, k_sqr_distances, max_nn));
00399           }
00400         }
00401 
00412         virtual void
00413         radiusSearch (const PointCloud& cloud,
00414                       const std::vector<int>& indices,
00415                       double radius,
00416                       std::vector< std::vector<int> >& k_indices,
00417                       std::vector< std::vector<float> > &k_sqr_distances,
00418                       unsigned int max_nn = 0) const
00419         {
00420           if (indices.empty ())
00421           {
00422             k_indices.resize (cloud.size ());
00423             k_sqr_distances.resize (cloud.size ());
00424             for (size_t i = 0; i < cloud.size (); i++)
00425               radiusSearch (cloud, static_cast<int> (i), radius,k_indices[i], k_sqr_distances[i], max_nn);
00426           }
00427           else
00428           {
00429             k_indices.resize (indices.size ());
00430             k_sqr_distances.resize (indices.size ());
00431             for (size_t i = 0; i < indices.size (); i++)
00432               radiusSearch (cloud,indices[i],radius,k_indices[i],k_sqr_distances[i], max_nn);
00433           }
00434         }
00435 
00436 
00448         template <typename PointTDiff> void
00449         radiusSearchT (const pcl::PointCloud<PointTDiff> &cloud,
00450                        const std::vector<int>& indices,
00451                        double radius,
00452                        std::vector< std::vector<int> > &k_indices,
00453                        std::vector< std::vector<float> > &k_sqr_distances,
00454                        unsigned int max_nn = 0) const
00455         {
00456           // Copy all the data fields from the input cloud to the output one
00457           typedef typename pcl::traits::fieldList<PointT>::type FieldListInT;
00458           typedef typename pcl::traits::fieldList<PointTDiff>::type FieldListOutT;
00459           typedef typename pcl::intersect<FieldListInT, FieldListOutT>::type FieldList;
00460 
00461           pcl::PointCloud<PointT> pc;
00462           if (indices.empty ())
00463           {
00464             pc.resize (cloud.size ());
00465             for (size_t i = 0; i < cloud.size (); ++i)
00466               pcl::for_each_type <FieldList> (pcl::NdConcatenateFunctor <PointTDiff, PointT> (cloud[i], pc[i]));
00467             radiusSearch (pc, std::vector<int> (), radius, k_indices, k_sqr_distances, max_nn);
00468           }
00469           else
00470           {
00471             pc.resize (indices.size ());
00472             for (size_t i = 0; i < indices.size (); ++i)
00473               pcl::for_each_type <FieldList> (pcl::NdConcatenateFunctor <PointTDiff, PointT> (cloud[indices[i]], pc[i]));
00474             radiusSearch (pc, std::vector<int>(), radius, k_indices, k_sqr_distances, max_nn);
00475           }
00476         }
00477 
00478       protected:
00479         void sortResults (std::vector<int>& indices, std::vector<float>& distances) const;
00480         PointCloudConstPtr input_;
00481         IndicesConstPtr indices_;
00482         bool sorted_results_;
00483         std::string name_;
00484         
00485       private:
00486         struct Compare
00487         {
00488           Compare (const std::vector<float>& distances)
00489           : distances_ (distances)
00490           {
00491           }
00492           
00493           bool operator () (int first, int second) const
00494           {
00495             return distances_ [first] < distances_[second];
00496           }
00497           
00498           const std::vector<float>& distances_;
00499         };
00500     }; // class Search
00501     
00502     // implementation
00503     template<typename PointT> void
00504     Search<PointT>::sortResults (std::vector<int>& indices, std::vector<float>& distances) const
00505     {
00506       std::vector<int> order (indices.size ());
00507       for (size_t idx = 0; idx < order.size (); ++idx)
00508         order [idx] = static_cast<int> (idx);
00509 
00510       Compare compare (distances);
00511       sort (order.begin (), order.end (), compare);
00512 
00513       std::vector<int> sorted (indices.size ());
00514       for (size_t idx = 0; idx < order.size (); ++idx)
00515         sorted [idx] = indices[order [idx]];
00516 
00517       indices = sorted;
00518   
00519       // sort  the according distances.
00520       sort (distances.begin (), distances.end ());
00521     }
00522   } // namespace search
00523 } // namespace pcl
00524 
00525 #endif  //#ifndef _PCL_SEARCH_GENERIC_SEARCH_H_


pcl
Author(s): Open Perception
autogenerated on Mon Oct 6 2014 03:17:53