Go to the documentation of this file.00001 
00002 
00003 
00004 
00005 
00006 
00007 
00008 
00009 
00010 
00011 
00012 
00013 
00014 
00015 
00016 
00017 
00018 
00019 
00020 
00021 
00022 
00023 
00024 
00025 
00026 
00027 
00028 
00029 
00030 
00031 
00032 
00033 
00034 
00035 
00036 
00037 
00038 
00039 
00040 
00041 #ifndef PCL_KDTREE_KDTREE_FLANN_H_
00042 #define PCL_KDTREE_KDTREE_FLANN_H_
00043 
00044 #include <pcl/kdtree/kdtree.h>
00045 
00046 
00047 namespace flann
00048 {
00049   struct SearchParams;
00050   template <typename T> struct L2_Simple;
00051   template <typename T> class Index;
00052 }
00053 
00054 namespace pcl
00055 {
00056   
00057   template <typename T> class PointRepresentation;
00058 
00065   template <typename PointT, typename Dist = ::flann::L2_Simple<float> >
00066   class KdTreeFLANN : public pcl::KdTree<PointT>
00067   {
00068     public:
00069       using KdTree<PointT>::input_;
00070       using KdTree<PointT>::indices_;
00071       using KdTree<PointT>::epsilon_;
00072       using KdTree<PointT>::sorted_;
00073       using KdTree<PointT>::point_representation_;
00074       using KdTree<PointT>::nearestKSearch;
00075       using KdTree<PointT>::radiusSearch;
00076 
00077       typedef typename KdTree<PointT>::PointCloud PointCloud;
00078       typedef typename KdTree<PointT>::PointCloudConstPtr PointCloudConstPtr;
00079 
00080       typedef boost::shared_ptr<std::vector<int> > IndicesPtr;
00081       typedef boost::shared_ptr<const std::vector<int> > IndicesConstPtr;
00082 
00083       typedef ::flann::Index<Dist> FLANNIndex;
00084 
00085       
00086       typedef boost::shared_ptr<KdTreeFLANN<PointT> > Ptr;
00087       typedef boost::shared_ptr<const KdTreeFLANN<PointT> > ConstPtr;
00088 
00094       KdTreeFLANN (bool sorted = true);
00095 
00099       KdTreeFLANN (const KdTreeFLANN<PointT> &k);
00100 
00104       inline KdTreeFLANN<PointT>&
00105       operator = (const KdTreeFLANN<PointT>& k)
00106       {
00107         KdTree<PointT>::operator=(k);
00108         flann_index_ = k.flann_index_;
00109         cloud_ = k.cloud_;
00110         index_mapping_ = k.index_mapping_;
00111         identity_mapping_ = k.identity_mapping_;
00112         dim_ = k.dim_;
00113         total_nr_points_ = k.total_nr_points_;
00114         param_k_ = k.param_k_;
00115         param_radius_ = k.param_radius_;
00116         return (*this);
00117       }
00118 
00122       void
00123       setEpsilon (float eps);
00124 
00125       void 
00126       setSortedResults (bool sorted);
00127       
00128       inline Ptr makeShared () { return Ptr (new KdTreeFLANN<PointT> (*this)); } 
00129 
00133       virtual ~KdTreeFLANN ()
00134       {
00135         cleanup ();
00136       }
00137 
00142       void 
00143       setInputCloud (const PointCloudConstPtr &cloud, const IndicesConstPtr &indices = IndicesConstPtr ());
00144 
00159       int 
00160       nearestKSearch (const PointT &point, int k, 
00161                       std::vector<int> &k_indices, std::vector<float> &k_sqr_distances) const;
00162 
00179       int 
00180       radiusSearch (const PointT &point, double radius, std::vector<int> &k_indices,
00181                     std::vector<float> &k_sqr_distances, unsigned int max_nn = 0) const;
00182 
00183     private:
00185       void 
00186       cleanup ();
00187 
00192       void 
00193       convertCloudToArray (const PointCloud &cloud);
00194 
00200       void 
00201       convertCloudToArray (const PointCloud &cloud, const std::vector<int> &indices);
00202 
00203     private:
00205       virtual std::string 
00206       getName () const { return ("KdTreeFLANN"); }
00207 
00209       boost::shared_ptr<FLANNIndex> flann_index_;
00210 
00212       float* cloud_;
00213       
00215       std::vector<int> index_mapping_;
00216       
00218       bool identity_mapping_;
00219 
00221       int dim_;
00222 
00224       int total_nr_points_;
00225 
00227       boost::shared_ptr<flann::SearchParams> param_k_;
00228 
00230       boost::shared_ptr<flann::SearchParams> param_radius_;
00231   };
00232 }
00233 
00234 #ifdef PCL_NO_PRECOMPILE
00235 #include <pcl/kdtree/impl/kdtree_flann.hpp>
00236 #endif
00237 
00238 #endif