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 #ifndef PCL_KDTREE_KDTREE_FLANN_H_
00039 #define PCL_KDTREE_KDTREE_FLANN_H_
00040
00041 #include <cstdio>
00042 #include "pcl/kdtree/kdtree.h"
00043 #include <boost/thread/mutex.hpp>
00044 #include <flann/flann.hpp>
00045
00046 namespace pcl
00047 {
00049
00055 template <typename PointT>
00056 class KdTreeFLANN : public KdTree<PointT>
00057 {
00058 using KdTree<PointT>::input_;
00059 using KdTree<PointT>::indices_;
00060 using KdTree<PointT>::epsilon_;
00061 using KdTree<PointT>::sorted_;
00062 using KdTree<PointT>::point_representation_;
00063
00064 typedef typename KdTree<PointT>::PointCloud PointCloud;
00065 typedef typename KdTree<PointT>::PointCloudConstPtr PointCloudConstPtr;
00066
00067 typedef boost::shared_ptr <std::vector<int> > IndicesPtr;
00068 typedef boost::shared_ptr <const std::vector<int> > IndicesConstPtr;
00069
00070 typedef flann::Index< flann::L2_Simple<float> > FLANNIndex;
00071
00072 public:
00073
00074 typedef boost::shared_ptr<KdTreeFLANN<PointT> > Ptr;
00075 typedef boost::shared_ptr<const KdTreeFLANN<PointT> > ConstPtr;
00076
00084
00085 KdTreeFLANN (bool sorted = true) : KdTree<PointT> (sorted), flann_index_(NULL), cloud_(NULL)
00086 {
00087 cleanup ();
00088 }
00089
00097 KdTreeFLANN (const KdTreeFLANN& tree) : KdTree<PointT> (tree)
00098 {
00099 shallowCopy (tree);
00100 }
00101
00102 inline Ptr makeShared () const { return Ptr (new KdTreeFLANN<PointT> (*this)); }
00103
00104 KdTreeFLANN& operator= (const KdTreeFLANN& tree)
00105 {
00106 if (this != &tree)
00107 {
00108 shallowCopy (tree);
00109 }
00110 return (*this);
00111 }
00112
00113
00114 inline void shallowCopy (const KdTreeFLANN& tree)
00115 {
00116 flann_index_ = tree.flann_index_;
00117 cloud_ = tree.cloud_;
00118 index_mapping_ = tree.index_mapping_;
00119 dim_ = tree.dim_;
00120 sorted_ = tree.sorted_;
00121 }
00122
00123
00125 virtual ~KdTreeFLANN ()
00126 {
00127 cleanup ();
00128 }
00129
00134 void setInputCloud (const PointCloudConstPtr &cloud, const IndicesConstPtr &indices=IndicesConstPtr());
00135
00144 int
00145 nearestKSearch (const PointT &point, int k,
00146 std::vector<int> &k_indices, std::vector<float> &k_distances);
00147
00157 inline int
00158 nearestKSearch (const PointCloud &cloud, int index, int k,
00159 std::vector<int> &k_indices, std::vector<float> &k_distances)
00160 {
00161 if (index >= (int)cloud.points.size ())
00162 return (0);
00163 return (nearestKSearch (cloud.points[index], k, k_indices, k_distances));
00164 }
00165
00175 inline int
00176 nearestKSearch (int index, int k,
00177 std::vector<int> &k_indices, std::vector<float> &k_distances)
00178 {
00179 if (indices_ == NULL)
00180 {
00181 if (index >= (int)input_->points.size ())
00182 return (0);
00183 return (nearestKSearch (input_->points[index], k, k_indices, k_distances));
00184 }
00185 else
00186 {
00187 if (index >= (int)indices_->size())
00188 return (0);
00189 return (nearestKSearch (input_->points[(*indices_)[index]], k, k_indices, k_distances));
00190 }
00191 }
00192
00201 int radiusSearch (const PointT &point, double radius, std::vector<int> &k_indices,
00202 std::vector<float> &k_distances, int max_nn = -1) const;
00203
00213 inline int
00214 radiusSearch (const PointCloud &cloud, int index, double radius,
00215 std::vector<int> &k_indices, std::vector<float> &k_distances,
00216 int max_nn = -1) const
00217 {
00218 if (index >= (int)cloud.points.size ())
00219 return 0;
00220 return (radiusSearch(cloud.points[index], radius, k_indices, k_distances, max_nn));
00221 }
00222
00232 inline int
00233 radiusSearch (int index, double radius, std::vector<int> &k_indices,
00234 std::vector<float> &k_distances, int max_nn = -1) const
00235 {
00236 if (indices_ == NULL)
00237 {
00238 if (index >= (int)input_->points.size ())
00239 return 0;
00240 return (radiusSearch (input_->points[index], radius, k_indices, k_distances, max_nn));
00241 }
00242 else
00243 {
00244 if (index >= (int)indices_->size ())
00245 return 0;
00246 return (radiusSearch (input_->points[(*indices_)[index]], radius, k_indices, k_distances, max_nn));
00247 }
00248 }
00249
00250 private:
00252 void cleanup ();
00253
00255 bool initParameters ();
00256
00258 void initData ();
00259
00264 void convertCloudToArray (const PointCloud &ros_cloud);
00265
00274 void convertCloudToArray (const PointCloud &ros_cloud, const std::vector<int> &indices);
00275
00276 private:
00278 virtual std::string getName () const { return ("KdTreeFLANN"); }
00279
00280 boost::mutex m_lock_;
00281
00283 FLANNIndex* flann_index_;
00284
00286 float* cloud_;
00287
00289 std::vector<int> index_mapping_;
00290
00292 int dim_;
00293 };
00294
00295 }
00296
00297 #endif