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 #ifndef PCL_KDTREE_KDTREE_FLANN_H_
00041 #define PCL_KDTREE_KDTREE_FLANN_H_
00042
00043 #include <cstdio>
00044 #include <pcl/point_representation.h>
00045 #include <pcl/kdtree/kdtree.h>
00046 #include <pcl/kdtree/flann.h>
00047
00048 namespace pcl
00049 {
00056 template <typename PointT, typename Dist = flann::L2_Simple<float> >
00057 class KdTreeFLANN : public pcl::KdTree<PointT>
00058 {
00059 public:
00060 using KdTree<PointT>::input_;
00061 using KdTree<PointT>::indices_;
00062 using KdTree<PointT>::epsilon_;
00063 using KdTree<PointT>::sorted_;
00064 using KdTree<PointT>::point_representation_;
00065 using KdTree<PointT>::nearestKSearch;
00066 using KdTree<PointT>::radiusSearch;
00067
00068 typedef typename KdTree<PointT>::PointCloud PointCloud;
00069 typedef typename KdTree<PointT>::PointCloudConstPtr PointCloudConstPtr;
00070
00071 typedef boost::shared_ptr<std::vector<int> > IndicesPtr;
00072 typedef boost::shared_ptr<const std::vector<int> > IndicesConstPtr;
00073
00074 typedef flann::Index<Dist> FLANNIndex;
00075
00076
00077 typedef boost::shared_ptr<KdTreeFLANN<PointT> > Ptr;
00078 typedef boost::shared_ptr<const KdTreeFLANN<PointT> > ConstPtr;
00079
00085 KdTreeFLANN (bool sorted = true) :
00086 pcl::KdTree<PointT> (sorted),
00087 flann_index_ (NULL), cloud_ (NULL),
00088 index_mapping_ (), identity_mapping_ (false),
00089 dim_ (0), total_nr_points_ (0),
00090 param_k_ (flann::SearchParams (-1 , epsilon_)),
00091 param_radius_ (flann::SearchParams (-1, epsilon_, sorted))
00092 {
00093 }
00094
00098 KdTreeFLANN (const KdTreeFLANN<PointT> &k) :
00099 pcl::KdTree<PointT> (false),
00100 flann_index_ (NULL), cloud_ (NULL),
00101 index_mapping_ (), identity_mapping_ (false),
00102 dim_ (0), total_nr_points_ (0),
00103 param_k_ (flann::SearchParams (-1 , epsilon_)),
00104 param_radius_ (flann::SearchParams (-1, epsilon_, false))
00105 {
00106 *this = k;
00107 }
00108
00112 inline KdTreeFLANN<PointT>&
00113 operator = (const KdTreeFLANN<PointT>& k)
00114 {
00115 KdTree<PointT>::operator=(k);
00116 flann_index_ = k.flann_index_;
00117 cloud_ = k.cloud_;
00118 index_mapping_ = k.index_mapping_;
00119 identity_mapping_ = k.identity_mapping_;
00120 dim_ = k.dim_;
00121 total_nr_points_ = k.total_nr_points_;
00122 param_k_ = k.param_k_;
00123 param_radius_ = k.param_radius_;
00124 return (*this);
00125 }
00126
00130 inline void
00131 setEpsilon (float eps)
00132 {
00133 epsilon_ = eps;
00134 param_k_ = flann::SearchParams (-1 , epsilon_);
00135 param_radius_ = flann::SearchParams (-1 , epsilon_, sorted_);
00136 }
00137
00138 inline void
00139 setSortedResults (bool sorted)
00140 {
00141 sorted_ = sorted;
00142 param_k_ = flann::SearchParams (-1, epsilon_);
00143 param_radius_ = flann::SearchParams (-1, epsilon_, sorted_);
00144 }
00145
00146 inline Ptr makeShared () { return Ptr (new KdTreeFLANN<PointT> (*this)); }
00147
00151 virtual ~KdTreeFLANN ()
00152 {
00153 cleanup ();
00154 }
00155
00160 void
00161 setInputCloud (const PointCloudConstPtr &cloud, const IndicesConstPtr &indices = IndicesConstPtr ());
00162
00177 int
00178 nearestKSearch (const PointT &point, int k,
00179 std::vector<int> &k_indices, std::vector<float> &k_sqr_distances) const;
00180
00197 int
00198 radiusSearch (const PointT &point, double radius, std::vector<int> &k_indices,
00199 std::vector<float> &k_sqr_distances, unsigned int max_nn = 0) const;
00200
00201 private:
00203 void
00204 cleanup ();
00205
00210 void
00211 convertCloudToArray (const PointCloud &cloud);
00212
00218 void
00219 convertCloudToArray (const PointCloud &cloud, const std::vector<int> &indices);
00220
00221 private:
00223 virtual std::string
00224 getName () const { return ("KdTreeFLANN"); }
00225
00227 FLANNIndex* flann_index_;
00228
00230 float* cloud_;
00231
00233 std::vector<int> index_mapping_;
00234
00236 bool identity_mapping_;
00237
00239 int dim_;
00240
00242 int total_nr_points_;
00243
00245 flann::SearchParams param_k_;
00246
00248 flann::SearchParams param_radius_;
00249 };
00250
00257 template <>
00258 class KdTreeFLANN <Eigen::MatrixXf>
00259 {
00260 public:
00261 typedef pcl::PointCloud<Eigen::MatrixXf> PointCloud;
00262 typedef PointCloud::ConstPtr PointCloudConstPtr;
00263
00264 typedef boost::shared_ptr<std::vector<int> > IndicesPtr;
00265 typedef boost::shared_ptr<const std::vector<int> > IndicesConstPtr;
00266
00267 typedef flann::Index<flann::L2_Simple<float> > FLANNIndex;
00268
00269 typedef pcl::PointRepresentation<Eigen::MatrixXf> PointRepresentation;
00270 typedef boost::shared_ptr<const PointRepresentation> PointRepresentationConstPtr;
00271
00272
00273 typedef boost::shared_ptr<KdTreeFLANN<Eigen::MatrixXf> > Ptr;
00274 typedef boost::shared_ptr<const KdTreeFLANN<Eigen::MatrixXf> > ConstPtr;
00275
00281 KdTreeFLANN (bool sorted = true) :
00282 input_(), indices_(), epsilon_(0.0f), sorted_(sorted), flann_index_(NULL), cloud_(NULL),
00283 index_mapping_ (), identity_mapping_ (false), dim_ (0),
00284 param_k_ (flann::SearchParams (-1, epsilon_)),
00285 param_radius_ (flann::SearchParams (-1, epsilon_, sorted)),
00286 total_nr_points_ (0)
00287 {
00288 cleanup ();
00289 }
00290
00294 KdTreeFLANN (const KdTreeFLANN<Eigen::MatrixXf> &k) :
00295 input_(), indices_(), epsilon_(0.0f), sorted_(false), flann_index_(NULL), cloud_(NULL),
00296 index_mapping_ (), identity_mapping_ (false), dim_ (0),
00297 param_k_ (flann::SearchParams (-1, epsilon_)),
00298 param_radius_ (flann::SearchParams (-1, epsilon_, sorted_)),
00299 total_nr_points_ (0)
00300 {
00301 *this = k;
00302 }
00303
00307 inline KdTreeFLANN&
00308 operator = (const KdTreeFLANN<Eigen::MatrixXf>& k)
00309 {
00310 input_ = k.input_;
00311 indices_ = k.indices_;
00312 epsilon_ = k.epsilon_;
00313 sorted_ = k.sorted_;
00314 flann_index_ = k.flann_index_;
00315 cloud_ = k.cloud_;
00316 index_mapping_ = k.index_mapping_;
00317 identity_mapping_ = k.identity_mapping_;
00318 dim_ = k.dim_;
00319 param_k_ = k.param_k_;
00320 param_radius_ = k.param_radius_;
00321 total_nr_points_ = k.total_nr_points_;
00322 return (*this);
00323 }
00324
00328 inline void
00329 setEpsilon (float eps)
00330 {
00331 epsilon_ = eps;
00332 param_k_ = flann::SearchParams (-1 , epsilon_);
00333 param_radius_ = flann::SearchParams (-1, epsilon_, sorted_);
00334 }
00335
00336 inline Ptr
00337 makeShared () { return Ptr (new KdTreeFLANN<Eigen::MatrixXf> (*this)); }
00338
00342 virtual ~KdTreeFLANN ()
00343 {
00344 cleanup ();
00345 }
00346
00351 void
00352 setInputCloud (const PointCloudConstPtr &cloud, const IndicesConstPtr &indices = IndicesConstPtr ())
00353 {
00354 cleanup ();
00355
00356 if (cloud == NULL)
00357 return;
00358
00359 epsilon_ = 0.0f;
00360 input_ = cloud;
00361 indices_ = indices;
00362 dim_ = static_cast<int> (cloud->points.cols ());
00363
00364
00365 if (indices != NULL)
00366 {
00367 total_nr_points_ = static_cast<int> (indices_->size ());
00368 convertCloudToArray (*input_, *indices_);
00369 }
00370 else
00371 {
00372
00373 total_nr_points_ = static_cast<int> (cloud->points.rows ());
00374 convertCloudToArray (*input_);
00375 }
00376
00377 flann_index_ = new FLANNIndex (flann::Matrix<float> (cloud_, index_mapping_.size (), dim_),
00378 flann::KDTreeSingleIndexParams (15));
00379 flann_index_->buildIndex ();
00380 }
00381
00383 inline IndicesConstPtr
00384 getIndices () const
00385 {
00386 return (indices_);
00387 }
00388
00390 inline PointCloudConstPtr
00391 getInputCloud () const
00392 {
00393 return (input_);
00394 }
00395
00404 template <typename T> int
00405 nearestKSearch (const T &point, int k,
00406 std::vector<int> &k_indices, std::vector<float> &k_sqr_distances) const
00407 {
00408 assert (isRowValid (point) && "Invalid (NaN, Inf) point coordinates given to nearestKSearch!");
00409
00410 if (k > total_nr_points_)
00411 {
00412 PCL_ERROR ("[pcl::KdTreeFLANN::nearestKSearch] An invalid number of nearest neighbors was requested! (k = %d out of %d total points).\n", k, total_nr_points_);
00413 k = total_nr_points_;
00414 }
00415
00416 k_indices.resize (k);
00417 k_sqr_distances.resize (k);
00418
00419 size_t dim = point.size ();
00420 std::vector<float> query (dim);
00421 for (size_t i = 0; i < dim; ++i)
00422 query[i] = point[i];
00423
00424 flann::Matrix<int> k_indices_mat (&k_indices[0], 1, k);
00425 flann::Matrix<float> k_distances_mat (&k_sqr_distances[0], 1, k);
00426
00427 flann_index_->knnSearch (flann::Matrix<float> (&query[0], 1, dim),
00428 k_indices_mat, k_distances_mat,
00429 k, param_k_);
00430
00431
00432 if (!identity_mapping_)
00433 {
00434 for (size_t i = 0; i < static_cast<size_t> (k); ++i)
00435 {
00436 int& neighbor_index = k_indices[i];
00437 neighbor_index = index_mapping_[neighbor_index];
00438 }
00439 }
00440
00441 return (k);
00442 }
00443
00453 inline int
00454 nearestKSearch (const PointCloud &cloud, int index, int k,
00455 std::vector<int> &k_indices, std::vector<float> &k_sqr_distances) const
00456 {
00457 assert (index >= 0 && index < static_cast<int> (cloud.size ()) && "Out-of-bounds error in nearestKSearch!");
00458 return (nearestKSearch (cloud.points.row (index), k, k_indices, k_sqr_distances));
00459 }
00460
00470 inline int
00471 nearestKSearch (int index, int k,
00472 std::vector<int> &k_indices, std::vector<float> &k_sqr_distances) const
00473 {
00474 if (indices_ == NULL)
00475 {
00476 assert (index >= 0 && index < static_cast<int> (input_->size ()) && "Out-of-bounds error in nearestKSearch!");
00477 return (nearestKSearch (input_->points.row (index), k, k_indices, k_sqr_distances));
00478 }
00479 else
00480 {
00481 assert (index >= 0 && index < static_cast<int> (indices_->size ()) && "Out-of-bounds error in nearestKSearch!");
00482 return (nearestKSearch (input_->points.row ((*indices_)[index]), k, k_indices, k_sqr_distances));
00483 }
00484 }
00485
00496 template <typename T> int
00497 radiusSearch (const T &point, double radius, std::vector<int> &k_indices,
00498 std::vector<float> &k_sqr_dists, unsigned int max_nn = 0) const
00499 {
00500 assert (isRowValid (point) && "Invalid (NaN, Inf) point coordinates given to radiusSearch!");
00501
00502 size_t dim = point.size ();
00503 std::vector<float> query (dim);
00504 for (size_t i = 0; i < dim; ++i)
00505 query[i] = point[i];
00506
00507
00508 if (max_nn == 0 || max_nn > static_cast<unsigned int> (total_nr_points_))
00509 max_nn = total_nr_points_;
00510
00511 std::vector<std::vector<int> > indices(1);
00512 std::vector<std::vector<float> > dists(1);
00513
00514 flann::SearchParams params(param_radius_);
00515 if (max_nn == static_cast<unsigned int>(total_nr_points_))
00516 params.max_neighbors = -1;
00517 else
00518 params.max_neighbors = max_nn;
00519
00520 int neighbors_in_radius = flann_index_->radiusSearch (flann::Matrix<float> (&query[0], 1, dim_),
00521 indices,
00522 dists,
00523 static_cast<float> (radius * radius),
00524 params);
00525
00526 k_indices = indices[0];
00527 k_sqr_dists = dists[0];
00528
00529
00530 if (!identity_mapping_)
00531 {
00532 for (int i = 0; i < neighbors_in_radius; ++i)
00533 {
00534 int& neighbor_index = k_indices[i];
00535 neighbor_index = index_mapping_[neighbor_index];
00536 }
00537 }
00538
00539 return (neighbors_in_radius);
00540 }
00541
00553 inline int
00554 radiusSearch (const PointCloud &cloud, int index, double radius,
00555 std::vector<int> &k_indices, std::vector<float> &k_sqr_distances,
00556 unsigned int max_nn = 0) const
00557 {
00558 assert (index >= 0 && index < static_cast<int> (cloud.size ()) && "Out-of-bounds error in radiusSearch!");
00559 return (radiusSearch (cloud.points.row (index), radius, k_indices, k_sqr_distances, max_nn));
00560 }
00561
00573 inline int
00574 radiusSearch (int index, double radius, std::vector<int> &k_indices,
00575 std::vector<float> &k_sqr_distances, unsigned int max_nn = 0) const
00576 {
00577 if (indices_ == NULL)
00578 {
00579 assert (index >= 0 && index < static_cast<int> (input_->size ()) && "Out-of-bounds error in radiusSearch!");
00580 return (radiusSearch (input_->points.row (index), radius, k_indices, k_sqr_distances, max_nn));
00581 }
00582 else
00583 {
00584 assert (index >= 0 && index < static_cast<int> (indices_->size ()) && "Out-of-bounds error in radiusSearch!");
00585 return (radiusSearch (input_->points.row ((*indices_)[index]), radius, k_indices, k_sqr_distances, max_nn));
00586 }
00587 }
00588
00590 inline float
00591 getEpsilon () const
00592 {
00593 return (epsilon_);
00594 }
00595
00596 private:
00598 void
00599 cleanup ()
00600 {
00601 if (flann_index_)
00602 delete flann_index_;
00603
00604
00605 if (cloud_)
00606 {
00607 free (cloud_);
00608 cloud_ = NULL;
00609 }
00610 index_mapping_.clear ();
00611
00612 if (indices_)
00613 indices_.reset ();
00614 }
00615
00619 template <typename Expr> bool
00620 isRowValid (const Expr &pt) const
00621 {
00622 for (size_t i = 0; i < static_cast<size_t> (pt.size ()); ++i)
00623 if (!pcl_isfinite (pt[i]))
00624 return (false);
00625
00626 return (true);
00627 }
00628
00633 void
00634 convertCloudToArray (const PointCloud &cloud)
00635 {
00636
00637 if (cloud.empty ())
00638 {
00639 cloud_ = NULL;
00640 return;
00641 }
00642
00643 int original_no_of_points = static_cast<int> (cloud.points.rows ());
00644
00645 cloud_ = static_cast<float*> (malloc (original_no_of_points * dim_ * sizeof (float)));
00646 float* cloud_ptr = cloud_;
00647 index_mapping_.reserve (original_no_of_points);
00648 identity_mapping_ = true;
00649
00650 for (int cloud_index = 0; cloud_index < original_no_of_points; ++cloud_index)
00651 {
00652
00653 if (!isRowValid (cloud.points.row (cloud_index)))
00654 {
00655 identity_mapping_ = false;
00656 continue;
00657 }
00658
00659 index_mapping_.push_back (cloud_index);
00660
00661 for (size_t i = 0; i < static_cast<size_t> (dim_); ++i)
00662 {
00663 *cloud_ptr = cloud.points.coeffRef (cloud_index, i);
00664 cloud_ptr++;
00665 }
00666 }
00667 }
00668
00674 void
00675 convertCloudToArray (const PointCloud &cloud, const std::vector<int> &indices)
00676 {
00677
00678 if (cloud.empty ())
00679 {
00680 cloud_ = NULL;
00681 return;
00682 }
00683
00684 int original_no_of_points = static_cast<int> (indices.size ());
00685
00686 cloud_ = static_cast<float*> (malloc (original_no_of_points * dim_ * sizeof (float)));
00687 float* cloud_ptr = cloud_;
00688 index_mapping_.reserve (original_no_of_points);
00689 identity_mapping_ = true;
00690
00691 for (int indices_index = 0; indices_index < original_no_of_points; ++indices_index)
00692 {
00693 int cloud_index = indices[indices_index];
00694
00695 if (!isRowValid (cloud.points.row (cloud_index)))
00696 {
00697 identity_mapping_ = false;
00698 continue;
00699 }
00700
00701 index_mapping_.push_back (indices_index);
00702
00703 for (size_t i = 0; i < static_cast<size_t> (dim_); ++i)
00704 {
00705 *cloud_ptr = cloud.points.coeffRef (cloud_index, i);
00706 cloud_ptr++;
00707 }
00708 }
00709 }
00710
00711 protected:
00713 PointCloudConstPtr input_;
00714
00716 IndicesConstPtr indices_;
00717
00719 float epsilon_;
00720
00722 bool sorted_;
00723
00724 private:
00726 std::string
00727 getName () const { return ("KdTreeFLANN"); }
00728
00730 FLANNIndex* flann_index_;
00731
00733 float* cloud_;
00734
00736 std::vector<int> index_mapping_;
00737
00739 bool identity_mapping_;
00740
00742 int dim_;
00743
00745 flann::SearchParams param_k_;
00746
00748 flann::SearchParams param_radius_;
00749
00751 int total_nr_points_;
00752 };
00753 }
00754
00755 #endif