voxel_grid_covariance_omp.h 20 KB

123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384858687888990919293949596979899100101102103104105106107108109110111112113114115116117118119120121122123124125126127128129130131132133134135136137138139140141142143144145146147148149150151152153154155156157158159160161162163164165166167168169170171172173174175176177178179180181182183184185186187188189190191192193194195196197198199200201202203204205206207208209210211212213214215216217218219220221222223224225226227228229230231232233234235236237238239240241242243244245246247248249250251252253254255256257258259260261262263264265266267268269270271272273274275276277278279280281282283284285286287288289290291292293294295296297298299300301302303304305306307308309310311312313314315316317318319320321322323324325326327328329330331332333334335336337338339340341342343344345346347348349350351352353354355356357358359360361362363364365366367368369370371372373374375376377378379380381382383384385386387388389390391392393394395396397398399400401402403404405406407408409410411412413414415416417418419420421422423424425426427428429430431432433434435436437438439440441442443444445446447448449450451452453454455456457458459460461462463464465466467468469470471472473474475476477478479480481482483484485486487488489490491492493494495496497498499500501502503504505506507508509510511512513514515516517518519520521522523524525526527528529530531532533534535536537538539540541542543544545546547548549550551
  1. /*
  2. * Software License Agreement (BSD License)
  3. *
  4. * Point Cloud Library (PCL) - www.pointclouds.org
  5. * Copyright (c) 2010-2011, Willow Garage, Inc.
  6. *
  7. * All rights reserved.
  8. *
  9. * Redistribution and use in source and binary forms, with or without
  10. * modification, are permitted provided that the following conditions
  11. * are met:
  12. *
  13. * * Redistributions of source code must retain the above copyright
  14. * notice, this list of conditions and the following disclaimer.
  15. * * Redistributions in binary form must reproduce the above
  16. * copyright notice, this list of conditions and the following
  17. * disclaimer in the documentation and/or other materials provided
  18. * with the distribution.
  19. * * Neither the name of the copyright holder(s) nor the names of its
  20. * contributors may be used to endorse or promote products derived
  21. * from this software without specific prior written permission.
  22. *
  23. * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
  24. * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
  25. * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
  26. * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
  27. * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
  28. * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
  29. * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
  30. * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
  31. * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
  32. * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
  33. * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
  34. * POSSIBILITY OF SUCH DAMAGE.
  35. *
  36. */
  37. #ifndef PCL_VOXEL_GRID_COVARIANCE_OMP_H_
  38. #define PCL_VOXEL_GRID_COVARIANCE_OMP_H_
  39. #include <pcl/filters/boost.h>
  40. #include <pcl/filters/voxel_grid.h>
  41. #include <map>
  42. #include <unordered_map>
  43. #include <pcl/point_types.h>
  44. #include <pcl/kdtree/kdtree_flann.h>
  45. namespace pclomp
  46. {
  47. /** \brief A searchable voxel strucure containing the mean and covariance of the data.
  48. * \note For more information please see
  49. * <b>Magnusson, M. (2009). The Three-Dimensional Normal-Distributions Transform —
  50. * an Efficient Representation for Registration, Surface Analysis, and Loop Detection.
  51. * PhD thesis, Orebro University. Orebro Studies in Technology 36</b>
  52. * \author Brian Okorn (Space and Naval Warfare Systems Center Pacific)
  53. */
  54. template<typename PointT>
  55. class VoxelGridCovariance : public pcl::VoxelGrid<PointT>
  56. {
  57. protected:
  58. using pcl::VoxelGrid<PointT>::filter_name_;
  59. using pcl::VoxelGrid<PointT>::getClassName;
  60. using pcl::VoxelGrid<PointT>::input_;
  61. using pcl::VoxelGrid<PointT>::indices_;
  62. using pcl::VoxelGrid<PointT>::filter_limit_negative_;
  63. using pcl::VoxelGrid<PointT>::filter_limit_min_;
  64. using pcl::VoxelGrid<PointT>::filter_limit_max_;
  65. using pcl::VoxelGrid<PointT>::filter_field_name_;
  66. using pcl::VoxelGrid<PointT>::downsample_all_data_;
  67. using pcl::VoxelGrid<PointT>::leaf_layout_;
  68. using pcl::VoxelGrid<PointT>::save_leaf_layout_;
  69. using pcl::VoxelGrid<PointT>::leaf_size_;
  70. using pcl::VoxelGrid<PointT>::min_b_;
  71. using pcl::VoxelGrid<PointT>::max_b_;
  72. using pcl::VoxelGrid<PointT>::inverse_leaf_size_;
  73. using pcl::VoxelGrid<PointT>::div_b_;
  74. using pcl::VoxelGrid<PointT>::divb_mul_;
  75. typedef typename pcl::traits::fieldList<PointT>::type FieldList;
  76. typedef typename pcl::Filter<PointT>::PointCloud PointCloud;
  77. typedef typename PointCloud::Ptr PointCloudPtr;
  78. typedef typename PointCloud::ConstPtr PointCloudConstPtr;
  79. public:
  80. typedef boost::shared_ptr< pcl::VoxelGrid<PointT> > Ptr;
  81. typedef boost::shared_ptr< const pcl::VoxelGrid<PointT> > ConstPtr;
  82. /** \brief Simple structure to hold a centroid, covarince and the number of points in a leaf.
  83. * Inverse covariance, eigen vectors and engen values are precomputed. */
  84. struct Leaf
  85. {
  86. /** \brief Constructor.
  87. * Sets \ref nr_points, \ref icov_, \ref mean_ and \ref evals_ to 0 and \ref cov_ and \ref evecs_ to the identity matrix
  88. */
  89. Leaf () :
  90. nr_points (0),
  91. mean_ (Eigen::Vector3d::Zero ()),
  92. centroid (),
  93. cov_ (Eigen::Matrix3d::Identity ()),
  94. icov_ (Eigen::Matrix3d::Zero ()),
  95. evecs_ (Eigen::Matrix3d::Identity ()),
  96. evals_ (Eigen::Vector3d::Zero ())
  97. {
  98. }
  99. /** \brief Get the voxel covariance.
  100. * \return covariance matrix
  101. */
  102. Eigen::Matrix3d
  103. getCov () const
  104. {
  105. return (cov_);
  106. }
  107. /** \brief Get the inverse of the voxel covariance.
  108. * \return inverse covariance matrix
  109. */
  110. Eigen::Matrix3d
  111. getInverseCov () const
  112. {
  113. return (icov_);
  114. }
  115. /** \brief Get the voxel centroid.
  116. * \return centroid
  117. */
  118. Eigen::Vector3d
  119. getMean () const
  120. {
  121. return (mean_);
  122. }
  123. /** \brief Get the eigen vectors of the voxel covariance.
  124. * \note Order corresponds with \ref getEvals
  125. * \return matrix whose columns contain eigen vectors
  126. */
  127. Eigen::Matrix3d
  128. getEvecs () const
  129. {
  130. return (evecs_);
  131. }
  132. /** \brief Get the eigen values of the voxel covariance.
  133. * \note Order corresponds with \ref getEvecs
  134. * \return vector of eigen values
  135. */
  136. Eigen::Vector3d
  137. getEvals () const
  138. {
  139. return (evals_);
  140. }
  141. /** \brief Get the number of points contained by this voxel.
  142. * \return number of points
  143. */
  144. int
  145. getPointCount () const
  146. {
  147. return (nr_points);
  148. }
  149. /** \brief Number of points contained by voxel */
  150. int nr_points;
  151. /** \brief 3D voxel centroid */
  152. Eigen::Vector3d mean_;
  153. /** \brief Nd voxel centroid
  154. * \note Differs from \ref mean_ when color data is used
  155. */
  156. Eigen::VectorXf centroid;
  157. /** \brief Voxel covariance matrix */
  158. Eigen::Matrix3d cov_;
  159. /** \brief Inverse of voxel covariance matrix */
  160. Eigen::Matrix3d icov_;
  161. /** \brief Eigen vectors of voxel covariance matrix */
  162. Eigen::Matrix3d evecs_;
  163. /** \brief Eigen values of voxel covariance matrix */
  164. Eigen::Vector3d evals_;
  165. };
  166. /** \brief Pointer to VoxelGridCovariance leaf structure */
  167. typedef Leaf* LeafPtr;
  168. /** \brief Const pointer to VoxelGridCovariance leaf structure */
  169. typedef const Leaf* LeafConstPtr;
  170. typedef std::map<size_t, Leaf> Map;
  171. public:
  172. /** \brief Constructor.
  173. * Sets \ref leaf_size_ to 0 and \ref searchable_ to false.
  174. */
  175. VoxelGridCovariance () :
  176. searchable_ (true),
  177. min_points_per_voxel_ (6),
  178. min_covar_eigvalue_mult_ (0.01),
  179. leaves_ (),
  180. voxel_centroids_ (),
  181. voxel_centroids_leaf_indices_ (),
  182. kdtree_ ()
  183. {
  184. downsample_all_data_ = false;
  185. save_leaf_layout_ = false;
  186. leaf_size_.setZero ();
  187. min_b_.setZero ();
  188. max_b_.setZero ();
  189. filter_name_ = "VoxelGridCovariance";
  190. }
  191. /** \brief Set the minimum number of points required for a cell to be used (must be 3 or greater for covariance calculation).
  192. * \param[in] min_points_per_voxel the minimum number of points for required for a voxel to be used
  193. */
  194. inline void
  195. setMinPointPerVoxel (int min_points_per_voxel)
  196. {
  197. if(min_points_per_voxel > 2)
  198. {
  199. min_points_per_voxel_ = min_points_per_voxel;
  200. }
  201. else
  202. {
  203. PCL_WARN ("%s: Covariance calculation requires at least 3 points, setting Min Point per Voxel to 3 ", this->getClassName ().c_str ());
  204. min_points_per_voxel_ = 3;
  205. }
  206. }
  207. /** \brief Get the minimum number of points required for a cell to be used.
  208. * \return the minimum number of points for required for a voxel to be used
  209. */
  210. inline int
  211. getMinPointPerVoxel ()
  212. {
  213. return min_points_per_voxel_;
  214. }
  215. /** \brief Set the minimum allowable ratio between eigenvalues to prevent singular covariance matrices.
  216. * \param[in] min_covar_eigvalue_mult the minimum allowable ratio between eigenvalues
  217. */
  218. inline void
  219. setCovEigValueInflationRatio (double min_covar_eigvalue_mult)
  220. {
  221. min_covar_eigvalue_mult_ = min_covar_eigvalue_mult;
  222. }
  223. /** \brief Get the minimum allowable ratio between eigenvalues to prevent singular covariance matrices.
  224. * \return the minimum allowable ratio between eigenvalues
  225. */
  226. inline double
  227. getCovEigValueInflationRatio ()
  228. {
  229. return min_covar_eigvalue_mult_;
  230. }
  231. /** \brief Filter cloud and initializes voxel structure.
  232. * \param[out] output cloud containing centroids of voxels containing a sufficient number of points
  233. * \param[in] searchable flag if voxel structure is searchable, if true then kdtree is built
  234. */
  235. inline void
  236. filter (PointCloud &output, bool searchable = false)
  237. {
  238. searchable_ = searchable;
  239. applyFilter (output);
  240. voxel_centroids_ = PointCloudPtr (new PointCloud (output));
  241. if (searchable_ && voxel_centroids_->size() > 0)
  242. {
  243. // Initiates kdtree of the centroids of voxels containing a sufficient number of points
  244. kdtree_.setInputCloud (voxel_centroids_);
  245. }
  246. }
  247. /** \brief Initializes voxel structure.
  248. * \param[in] searchable flag if voxel structure is searchable, if true then kdtree is built
  249. */
  250. inline void
  251. filter (bool searchable = false)
  252. {
  253. searchable_ = searchable;
  254. voxel_centroids_ = PointCloudPtr (new PointCloud);
  255. applyFilter (*voxel_centroids_);
  256. if (searchable_ && voxel_centroids_->size() > 0)
  257. {
  258. // Initiates kdtree of the centroids of voxels containing a sufficient number of points
  259. kdtree_.setInputCloud (voxel_centroids_);
  260. }
  261. }
  262. /** \brief Get the voxel containing point p.
  263. * \param[in] index the index of the leaf structure node
  264. * \return const pointer to leaf structure
  265. */
  266. inline LeafConstPtr
  267. getLeaf (int index)
  268. {
  269. auto leaf_iter = leaves_.find (index);
  270. if (leaf_iter != leaves_.end ())
  271. {
  272. LeafConstPtr ret (&(leaf_iter->second));
  273. return ret;
  274. }
  275. else
  276. return NULL;
  277. }
  278. /** \brief Get the voxel containing point p.
  279. * \param[in] p the point to get the leaf structure at
  280. * \return const pointer to leaf structure
  281. */
  282. inline LeafConstPtr
  283. getLeaf (PointT &p)
  284. {
  285. // Generate index associated with p
  286. int ijk0 = static_cast<int> (floor (p.x * inverse_leaf_size_[0]) - min_b_[0]);
  287. int ijk1 = static_cast<int> (floor (p.y * inverse_leaf_size_[1]) - min_b_[1]);
  288. int ijk2 = static_cast<int> (floor (p.z * inverse_leaf_size_[2]) - min_b_[2]);
  289. // Compute the centroid leaf index
  290. int idx = ijk0 * divb_mul_[0] + ijk1 * divb_mul_[1] + ijk2 * divb_mul_[2];
  291. // Find leaf associated with index
  292. auto leaf_iter = leaves_.find (idx);
  293. if (leaf_iter != leaves_.end ())
  294. {
  295. // If such a leaf exists return the pointer to the leaf structure
  296. LeafConstPtr ret (&(leaf_iter->second));
  297. return ret;
  298. }
  299. else
  300. return NULL;
  301. }
  302. /** \brief Get the voxel containing point p.
  303. * \param[in] p the point to get the leaf structure at
  304. * \return const pointer to leaf structure
  305. */
  306. inline LeafConstPtr
  307. getLeaf (Eigen::Vector3f &p)
  308. {
  309. // Generate index associated with p
  310. int ijk0 = static_cast<int> (floor (p[0] * inverse_leaf_size_[0]) - min_b_[0]);
  311. int ijk1 = static_cast<int> (floor (p[1] * inverse_leaf_size_[1]) - min_b_[1]);
  312. int ijk2 = static_cast<int> (floor (p[2] * inverse_leaf_size_[2]) - min_b_[2]);
  313. // Compute the centroid leaf index
  314. int idx = ijk0 * divb_mul_[0] + ijk1 * divb_mul_[1] + ijk2 * divb_mul_[2];
  315. // Find leaf associated with index
  316. auto leaf_iter = leaves_.find (idx);
  317. if (leaf_iter != leaves_.end ())
  318. {
  319. // If such a leaf exists return the pointer to the leaf structure
  320. LeafConstPtr ret (&(leaf_iter->second));
  321. return ret;
  322. }
  323. else
  324. return NULL;
  325. }
  326. /** \brief Get the voxels surrounding point p, not including the voxel contating point p.
  327. * \note Only voxels containing a sufficient number of points are used (slower than radius search in practice).
  328. * \param[in] reference_point the point to get the leaf structure at
  329. * \param[out] neighbors
  330. * \return number of neighbors found
  331. */
  332. int getNeighborhoodAtPoint(const Eigen::MatrixXi&, const PointT& reference_point, std::vector<LeafConstPtr> &neighbors) const ;
  333. int getNeighborhoodAtPoint(const PointT& reference_point, std::vector<LeafConstPtr> &neighbors) const ;
  334. int getNeighborhoodAtPoint7(const PointT& reference_point, std::vector<LeafConstPtr> &neighbors) const ;
  335. int getNeighborhoodAtPoint1(const PointT& reference_point, std::vector<LeafConstPtr> &neighbors) const ;
  336. /** \brief Get the leaf structure map
  337. * \return a map contataining all leaves
  338. */
  339. inline const Map&
  340. getLeaves ()
  341. {
  342. return leaves_;
  343. }
  344. /** \brief Get a pointcloud containing the voxel centroids
  345. * \note Only voxels containing a sufficient number of points are used.
  346. * \return a map contataining all leaves
  347. */
  348. inline PointCloudPtr
  349. getCentroids ()
  350. {
  351. return voxel_centroids_;
  352. }
  353. /** \brief Get a cloud to visualize each voxels normal distribution.
  354. * \param[out] cell_cloud a cloud created by sampling the normal distributions of each voxel
  355. */
  356. void
  357. getDisplayCloud (pcl::PointCloud<pcl::PointXYZ>& cell_cloud);
  358. /** \brief Search for the k-nearest occupied voxels for the given query point.
  359. * \note Only voxels containing a sufficient number of points are used.
  360. * \param[in] point the given query point
  361. * \param[in] k the number of neighbors to search for
  362. * \param[out] k_leaves the resultant leaves of the neighboring points
  363. * \param[out] k_sqr_distances the resultant squared distances to the neighboring points
  364. * \return number of neighbors found
  365. */
  366. int
  367. nearestKSearch (const PointT &point, int k,
  368. std::vector<LeafConstPtr> &k_leaves, std::vector<float> &k_sqr_distances)
  369. {
  370. k_leaves.clear ();
  371. // Check if kdtree has been built
  372. if (!searchable_)
  373. {
  374. PCL_WARN ("%s: Not Searchable", this->getClassName ().c_str ());
  375. return 0;
  376. }
  377. // Find k-nearest neighbors in the occupied voxel centroid cloud
  378. std::vector<int> k_indices;
  379. k = kdtree_.nearestKSearch (point, k, k_indices, k_sqr_distances);
  380. // Find leaves corresponding to neighbors
  381. k_leaves.reserve (k);
  382. for (std::vector<int>::iterator iter = k_indices.begin (); iter != k_indices.end (); iter++)
  383. {
  384. k_leaves.push_back (&leaves_[voxel_centroids_leaf_indices_[*iter]]);
  385. }
  386. return k;
  387. }
  388. /** \brief Search for the k-nearest occupied voxels for the given query point.
  389. * \note Only voxels containing a sufficient number of points are used.
  390. * \param[in] cloud the given query point
  391. * \param[in] index the index
  392. * \param[in] k the number of neighbors to search for
  393. * \param[out] k_leaves the resultant leaves of the neighboring points
  394. * \param[out] k_sqr_distances the resultant squared distances to the neighboring points
  395. * \return number of neighbors found
  396. */
  397. inline int
  398. nearestKSearch (const PointCloud &cloud, int index, int k,
  399. std::vector<LeafConstPtr> &k_leaves, std::vector<float> &k_sqr_distances)
  400. {
  401. if (index >= static_cast<int> (cloud.points.size ()) || index < 0)
  402. return (0);
  403. return (nearestKSearch (cloud.points[index], k, k_leaves, k_sqr_distances));
  404. }
  405. /** \brief Search for all the nearest occupied voxels of the query point in a given radius.
  406. * \note Only voxels containing a sufficient number of points are used.
  407. * \param[in] point the given query point
  408. * \param[in] radius the radius of the sphere bounding all of p_q's neighbors
  409. * \param[out] k_leaves the resultant leaves of the neighboring points
  410. * \param[out] k_sqr_distances the resultant squared distances to the neighboring points
  411. * \param[in] max_nn
  412. * \return number of neighbors found
  413. */
  414. int
  415. radiusSearch (const PointT &point, double radius, std::vector<LeafConstPtr> &k_leaves,
  416. std::vector<float> &k_sqr_distances, unsigned int max_nn = 0) const
  417. {
  418. k_leaves.clear ();
  419. // Check if kdtree has been built
  420. if (!searchable_)
  421. {
  422. PCL_WARN ("%s: Not Searchable", this->getClassName ().c_str ());
  423. return 0;
  424. }
  425. // Find neighbors within radius in the occupied voxel centroid cloud
  426. std::vector<int> k_indices;
  427. int k = kdtree_.radiusSearch (point, radius, k_indices, k_sqr_distances, max_nn);
  428. // Find leaves corresponding to neighbors
  429. k_leaves.reserve (k);
  430. for (std::vector<int>::iterator iter = k_indices.begin (); iter != k_indices.end (); iter++)
  431. {
  432. auto leaf = leaves_.find(voxel_centroids_leaf_indices_[*iter]);
  433. if (leaf == leaves_.end()) {
  434. std::cerr << "error : could not find the leaf corresponding to the voxel" << std::endl;
  435. std::cin.ignore(1);
  436. }
  437. k_leaves.push_back (&(leaf->second));
  438. }
  439. return k;
  440. }
  441. /** \brief Search for all the nearest occupied voxels of the query point in a given radius.
  442. * \note Only voxels containing a sufficient number of points are used.
  443. * \param[in] cloud the given query point
  444. * \param[in] index a valid index in cloud representing a valid (i.e., finite) query point
  445. * \param[in] radius the radius of the sphere bounding all of p_q's neighbors
  446. * \param[out] k_leaves the resultant leaves of the neighboring points
  447. * \param[out] k_sqr_distances the resultant squared distances to the neighboring points
  448. * \param[in] max_nn
  449. * \return number of neighbors found
  450. */
  451. inline int
  452. radiusSearch (const PointCloud &cloud, int index, double radius,
  453. std::vector<LeafConstPtr> &k_leaves, std::vector<float> &k_sqr_distances,
  454. unsigned int max_nn = 0) const
  455. {
  456. if (index >= static_cast<int> (cloud.points.size ()) || index < 0)
  457. return (0);
  458. return (radiusSearch (cloud.points[index], radius, k_leaves, k_sqr_distances, max_nn));
  459. }
  460. protected:
  461. /** \brief Filter cloud and initializes voxel structure.
  462. * \param[out] output cloud containing centroids of voxels containing a sufficient number of points
  463. */
  464. void applyFilter (PointCloud &output);
  465. /** \brief Flag to determine if voxel structure is searchable. */
  466. bool searchable_;
  467. /** \brief Minimum points contained with in a voxel to allow it to be useable. */
  468. int min_points_per_voxel_;
  469. /** \brief Minimum allowable ratio between eigenvalues to prevent singular covariance matrices. */
  470. double min_covar_eigvalue_mult_;
  471. /** \brief Voxel structure containing all leaf nodes (includes voxels with less than a sufficient number of points). */
  472. Map leaves_;
  473. /** \brief Point cloud containing centroids of voxels containing atleast minimum number of points. */
  474. PointCloudPtr voxel_centroids_;
  475. /** \brief Indices of leaf structurs associated with each point in \ref voxel_centroids_ (used for searching). */
  476. std::vector<int> voxel_centroids_leaf_indices_;
  477. /** \brief KdTree generated using \ref voxel_centroids_ (used for searching). */
  478. pcl::KdTreeFLANN<PointT> kdtree_;
  479. };
  480. }
  481. #endif //#ifndef PCL_VOXEL_GRID_COVARIANCE_H_