nanoflann.hpp 6.5 KB

123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384858687888990919293949596979899100101102103104105106107108109110111112113114115116117118119120121122123124125126127128129130131132133134135136137138139140141142143144145146147148149150151152153154155156157158159160161162163164165166167168169170171172173174175176177178179180181182183184185186187188189190191192193194195196
  1. /************************************************************
  2. *
  3. * Copyright (c) 2021, University of California, Los Angeles
  4. *
  5. * Authors: Kenny J. Chen, Brett T. Lopez
  6. * Contact: kennyjchen@ucla.edu, btlopez@ucla.edu
  7. *
  8. ***********************************************************/
  9. /***********************************************************************
  10. * Software License Agreement (BSD License)
  11. *
  12. * Copyright 2008-2009 Marius Muja (mariusm@cs.ubc.ca). All rights reserved.
  13. * Copyright 2008-2009 David G. Lowe (lowe@cs.ubc.ca). All rights reserved.
  14. * Copyright 2011-2021 Jose Luis Blanco (joseluisblancoc@gmail.com).
  15. * All rights reserved.
  16. *
  17. * THE BSD LICENSE
  18. *
  19. * Redistribution and use in source and binary forms, with or without
  20. * modification, are permitted provided that the following conditions
  21. * are met:
  22. *
  23. * 1. Redistributions of source code must retain the above copyright
  24. * notice, this list of conditions and the following disclaimer.
  25. * 2. Redistributions in binary form must reproduce the above copyright
  26. * notice, this list of conditions and the following disclaimer in the
  27. * documentation and/or other materials provided with the distribution.
  28. *
  29. * THIS SOFTWARE IS PROVIDED BY THE AUTHOR ``AS IS'' AND ANY EXPRESS OR
  30. * IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED WARRANTIES
  31. * OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE DISCLAIMED.
  32. * IN NO EVENT SHALL THE AUTHOR BE LIABLE FOR ANY DIRECT, INDIRECT,
  33. * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, BUT
  34. * NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS OF USE,
  35. * DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND ON ANY
  36. * THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT
  37. * (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF
  38. * THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
  39. *************************************************************************/
  40. #ifndef NANO_KDTREE_KDTREE_FLANN_H_
  41. #define NANO_KDTREE_KDTREE_FLANN_H_
  42. #include <boost/shared_ptr.hpp>
  43. #include <pcl/point_cloud.h>
  44. #include <pcl/point_types.h>
  45. #include <pcl/kdtree/kdtree_flann.h>
  46. #include "nano_gicp/impl/nanoflann_impl.hpp"
  47. namespace nanoflann
  48. {
  49. template <typename PointT>
  50. class KdTreeFLANN
  51. {
  52. public:
  53. typedef typename pcl::PointCloud<PointT> PointCloud;
  54. typedef typename pcl::PointCloud<PointT>::Ptr PointCloudPtr;
  55. typedef typename pcl::PointCloud<PointT>::ConstPtr PointCloudConstPtr;
  56. typedef boost::shared_ptr<KdTreeFLANN<PointT>> Ptr;
  57. typedef boost::shared_ptr<const KdTreeFLANN<PointT>> ConstPtr;
  58. typedef boost::shared_ptr<std::vector<int>> IndicesPtr;
  59. typedef boost::shared_ptr<const std::vector<int>> IndicesConstPtr;
  60. KdTreeFLANN (bool sorted = false);
  61. KdTreeFLANN (const KdTreeFLANN<PointT> &k);
  62. void setEpsilon (float eps);
  63. void setSortedResults (bool sorted);
  64. inline Ptr makeShared () { return Ptr (new KdTreeFLANN<PointT> (*this)); }
  65. void setInputCloud (const PointCloudConstPtr &cloud, const IndicesConstPtr &indices = IndicesConstPtr ());
  66. inline PointCloudConstPtr getInputCloud() const { return _adaptor.pcl; }
  67. int nearestKSearch (const PointT &point, int k, std::vector<int> &k_indices,
  68. std::vector<float> &k_sqr_distances) const;
  69. int radiusSearch (const PointT &point, double radius, std::vector<int> &k_indices,
  70. std::vector<float> &k_sqr_distances) const;
  71. protected:
  72. nanoflann::SearchParams _params;
  73. struct PointCloud_Adaptor
  74. {
  75. inline size_t kdtree_get_point_count() const;
  76. inline float kdtree_get_pt(const size_t idx, int dim) const;
  77. template <class BBOX> bool kdtree_get_bbox(BBOX&) const { return false; }
  78. PointCloudConstPtr pcl;
  79. IndicesConstPtr indices;
  80. };
  81. typedef nanoflann::KDTreeSingleIndexAdaptor<
  82. nanoflann::SO3_Adaptor<float, PointCloud_Adaptor > ,
  83. PointCloud_Adaptor, 3, int> KDTreeFlann_PCL_SO3;
  84. PointCloud_Adaptor _adaptor;
  85. KDTreeFlann_PCL_SO3 _kdtree;
  86. };
  87. //---------- Definitions ---------------------
  88. template<typename PointT> inline
  89. KdTreeFLANN<PointT>::KdTreeFLANN(bool sorted):
  90. _kdtree(3,_adaptor, KDTreeSingleIndexAdaptorParams(100))
  91. {
  92. _params.sorted = sorted;
  93. }
  94. template<typename PointT> inline
  95. void KdTreeFLANN<PointT>::setEpsilon(float eps)
  96. {
  97. _params.eps = eps;
  98. }
  99. template<typename PointT> inline
  100. void KdTreeFLANN<PointT>::setSortedResults(bool sorted)
  101. {
  102. _params.sorted = sorted;
  103. }
  104. template<typename PointT> inline
  105. void KdTreeFLANN<PointT>::setInputCloud(const KdTreeFLANN::PointCloudConstPtr &cloud,
  106. const IndicesConstPtr &indices)
  107. {
  108. _adaptor.pcl = cloud;
  109. _adaptor.indices = indices;
  110. _kdtree.buildIndex();
  111. }
  112. template<typename PointT> inline
  113. int KdTreeFLANN<PointT>::nearestKSearch(const PointT &point, int num_closest,
  114. std::vector<int> &k_indices,
  115. std::vector<float> &k_sqr_distances) const
  116. {
  117. k_indices.resize(num_closest);
  118. k_sqr_distances.resize(num_closest);
  119. nanoflann::KNNResultSet<float,int> resultSet(num_closest);
  120. resultSet.init( k_indices.data(), k_sqr_distances.data());
  121. _kdtree.findNeighbors(resultSet, point.data, nanoflann::SearchParams() );
  122. return resultSet.size();
  123. }
  124. template<typename PointT> inline
  125. int KdTreeFLANN<PointT>::radiusSearch(const PointT &point, double radius,
  126. std::vector<int> &k_indices,
  127. std::vector<float> &k_sqr_distances) const
  128. {
  129. static std::vector<std::pair<int, float> > indices_dist;
  130. indices_dist.reserve( 128 );
  131. RadiusResultSet<float, int> resultSet(radius, indices_dist);
  132. const size_t nFound = _kdtree.findNeighbors(resultSet, point.data, _params);
  133. if (_params.sorted)
  134. std::sort(indices_dist.begin(), indices_dist.end(), IndexDist_Sorter() );
  135. k_indices.resize(nFound);
  136. k_sqr_distances.resize(nFound);
  137. for(int i=0; i<nFound; i++ ){
  138. k_indices[i] = indices_dist[i].first;
  139. k_sqr_distances[i] = indices_dist[i].second;
  140. }
  141. return nFound;
  142. }
  143. template<typename PointT> inline
  144. size_t KdTreeFLANN<PointT>::PointCloud_Adaptor::kdtree_get_point_count() const {
  145. if( indices ) return indices->size();
  146. if( pcl) return pcl->points.size();
  147. return 0;
  148. }
  149. template<typename PointT> inline
  150. float KdTreeFLANN<PointT>::PointCloud_Adaptor::kdtree_get_pt(const size_t idx, int dim) const{
  151. const PointT& p = ( indices ) ? pcl->points[(*indices)[idx]] : pcl->points[idx];
  152. if (dim==0) return p.x;
  153. else if (dim==1) return p.y;
  154. else if (dim==2) return p.z;
  155. else return 0.0;
  156. }
  157. }
  158. #endif