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 #ifndef PCL_SEARCH_FLANN_SEARCH_H_
00040 #define PCL_SEARCH_FLANN_SEARCH_H_
00041
00042 #include <pcl/search/search.h>
00043 #include <pcl/common/time.h>
00044 #include <pcl/point_representation.h>
00045
00046 namespace flann
00047 {
00048 template<typename T> class NNIndex;
00049 template<typename T> struct L2;
00050 template<typename T> struct L2_Simple;
00051 template<typename T> class Matrix;
00052 }
00053
00054 namespace pcl
00055 {
00056 namespace search
00057 {
00058
00066 template<typename PointT, typename FlannDistance=flann::L2_Simple <float> >
00067 class FlannSearch: public Search<PointT>
00068 {
00069 typedef typename Search<PointT>::PointCloud PointCloud;
00070 typedef typename Search<PointT>::PointCloudConstPtr PointCloudConstPtr;
00071
00072 typedef boost::shared_ptr<std::vector<int> > IndicesPtr;
00073 typedef boost::shared_ptr<const std::vector<int> > IndicesConstPtr;
00074 typedef flann::NNIndex< FlannDistance > Index;
00075 typedef boost::shared_ptr<flann::NNIndex <FlannDistance > > IndexPtr;
00076 typedef boost::shared_ptr<flann::Matrix <float> > MatrixPtr;
00077 typedef boost::shared_ptr<const flann::Matrix <float> > MatrixConstPtr;
00078
00079 typedef pcl::PointRepresentation<PointT> PointRepresentation;
00080
00081 typedef boost::shared_ptr<const PointRepresentation> PointRepresentationConstPtr;
00082
00083 using Search<PointT>::input_;
00084 using Search<PointT>::indices_;
00085 using Search<PointT>::sorted_results_;
00086
00087 public:
00088 typedef boost::shared_ptr<FlannSearch<PointT, FlannDistance> > Ptr;
00089 typedef boost::shared_ptr<const FlannSearch<PointT, FlannDistance> > ConstPtr;
00090
00096 class FlannIndexCreator
00097 {
00098 public:
00103 virtual IndexPtr createIndex (MatrixConstPtr data)=0;
00104
00107 virtual ~FlannIndexCreator () {}
00108 };
00109 typedef boost::shared_ptr<FlannIndexCreator> FlannIndexCreatorPtr;
00110
00113 class KdTreeIndexCreator: public FlannIndexCreator
00114 {
00115 public:
00120 KdTreeIndexCreator (unsigned int max_leaf_size=15) : max_leaf_size_ (max_leaf_size){}
00121
00123 virtual ~KdTreeIndexCreator () {}
00124
00129 virtual IndexPtr createIndex (MatrixConstPtr data);
00130 private:
00131 unsigned int max_leaf_size_;
00132 };
00133
00136 class KMeansIndexCreator: public FlannIndexCreator
00137 {
00138 public:
00143 KMeansIndexCreator (){}
00144
00146 virtual ~KMeansIndexCreator () {}
00147
00152 virtual IndexPtr createIndex (MatrixConstPtr data);
00153 private:
00154 };
00155
00156 FlannSearch (bool sorted = true, FlannIndexCreatorPtr creator = FlannIndexCreatorPtr (new KdTreeIndexCreator ()));
00157
00159 virtual
00160 ~FlannSearch ();
00161
00162
00163
00164
00165
00169 inline void
00170 setEpsilon (double eps)
00171 {
00172 eps_ = eps;
00173 }
00174
00176 inline double
00177 getEpsilon ()
00178 {
00179 return (eps_);
00180 }
00181
00186 virtual void
00187 setInputCloud (const PointCloudConstPtr& cloud, const IndicesConstPtr& indices = IndicesConstPtr ());
00188
00197 int
00198 nearestKSearch (const PointT &point, int k, std::vector<int> &k_indices, std::vector<float> &k_sqr_distances) const;
00199
00200
00208 virtual void
00209 nearestKSearch (const PointCloud& cloud, const std::vector<int>& indices, int k,
00210 std::vector< std::vector<int> >& k_indices, std::vector< std::vector<float> >& k_sqr_distances) const;
00211
00222 int
00223 radiusSearch (const PointT& point, double radius,
00224 std::vector<int> &k_indices, std::vector<float> &k_sqr_distances,
00225 unsigned int max_nn = 0) const;
00226
00235 virtual void
00236 radiusSearch (const PointCloud& cloud, const std::vector<int>& indices, double radius, std::vector< std::vector<int> >& k_indices,
00237 std::vector< std::vector<float> >& k_sqr_distances, unsigned int max_nn=0) const;
00238
00242 inline void
00243 setPointRepresentation (const PointRepresentationConstPtr &point_representation)
00244 {
00245 point_representation_ = point_representation;
00246 dim_ = point_representation->getNumberOfDimensions ();
00247 if (input_)
00248 setInputCloud (input_, indices_);
00249 }
00250
00252 inline PointRepresentationConstPtr const
00253 getPointRepresentation ()
00254 {
00255 return (point_representation_);
00256 }
00257
00258 protected:
00259
00262 void convertInputToFlannMatrix();
00263
00266 IndexPtr index_;
00267
00270 FlannIndexCreatorPtr creator_;
00271
00274 MatrixPtr input_flann_;
00275
00278 float eps_;
00279 bool input_copied_for_flann_;
00280
00281 PointRepresentationConstPtr point_representation_;
00282
00283 int dim_;
00284
00285 std::vector<int> index_mapping_;
00286 bool identity_mapping_;
00287
00288 };
00289 }
00290 }
00291
00292 #define PCL_INSTANTIATE_FlannSearch(T) template class PCL_EXPORTS pcl::search::FlannSearch<T>;
00293
00294 #endif // PCL_SEARCH_KDTREE_H_
00295