gicp_omp.h 16 KB

123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384858687888990919293949596979899100101102103104105106107108109110111112113114115116117118119120121122123124125126127128129130131132133134135136137138139140141142143144145146147148149150151152153154155156157158159160161162163164165166167168169170171172173174175176177178179180181182183184185186187188189190191192193194195196197198199200201202203204205206207208209210211212213214215216217218219220221222223224225226227228229230231232233234235236237238239240241242243244245246247248249250251252253254255256257258259260261262263264265266267268269270271272273274275276277278279280281282283284285286287288289290291292293294295296297298299300301302303304305306307308309310311312313314315316317318319320321322323324325326327328329330331332333334335336337338339340341342343344345346347348349350351352353354355356357358359360361362363364365366367368369370371372373
  1. /*
  2. * Software License Agreement (BSD License)
  3. *
  4. * Point Cloud Library (PCL) - www.pointclouds.org
  5. * Copyright (c) 2010, Willow Garage, Inc.
  6. * Copyright (c) 2012-, Open Perception, Inc.
  7. *
  8. * All rights reserved.
  9. *
  10. * Redistribution and use in source and binary forms, with or without
  11. * modification, are permitted provided that the following conditions
  12. * are met:
  13. *
  14. * * Redistributions of source code must retain the above copyright
  15. * notice, this list of conditions and the following disclaimer.
  16. * * Redistributions in binary form must reproduce the above
  17. * copyright notice, this list of conditions and the following
  18. * disclaimer in the documentation and/or other materials provided
  19. * with the distribution.
  20. * * Neither the name of the copyright holder(s) nor the names of its
  21. * contributors may be used to endorse or promote products derived
  22. * from this software without specific prior written permission.
  23. *
  24. * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
  25. * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
  26. * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
  27. * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
  28. * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
  29. * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
  30. * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
  31. * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
  32. * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
  33. * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
  34. * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
  35. * POSSIBILITY OF SUCH DAMAGE.
  36. *
  37. * $Id$
  38. *
  39. */
  40. #ifndef PCL_GICP_OMP_H_
  41. #define PCL_GICP_OMP_H_
  42. #include <pcl/registration/icp.h>
  43. #include <pcl/registration/bfgs.h>
  44. namespace pclomp
  45. {
  46. /** \brief GeneralizedIterativeClosestPoint is an ICP variant that implements the
  47. * generalized iterative closest point algorithm as described by Alex Segal et al. in
  48. * http://www.robots.ox.ac.uk/~avsegal/resources/papers/Generalized_ICP.pdf
  49. * The approach is based on using anistropic cost functions to optimize the alignment
  50. * after closest point assignments have been made.
  51. * The original code uses GSL and ANN while in ours we use an eigen mapped BFGS and
  52. * FLANN.
  53. * \author Nizar Sallem
  54. * \ingroup registration
  55. */
  56. template <typename PointSource, typename PointTarget>
  57. class GeneralizedIterativeClosestPoint : public pcl::IterativeClosestPoint<PointSource, PointTarget>
  58. {
  59. public:
  60. using pcl::IterativeClosestPoint<PointSource, PointTarget>::reg_name_;
  61. using pcl::IterativeClosestPoint<PointSource, PointTarget>::getClassName;
  62. using pcl::IterativeClosestPoint<PointSource, PointTarget>::indices_;
  63. using pcl::IterativeClosestPoint<PointSource, PointTarget>::target_;
  64. using pcl::IterativeClosestPoint<PointSource, PointTarget>::input_;
  65. using pcl::IterativeClosestPoint<PointSource, PointTarget>::tree_;
  66. using pcl::IterativeClosestPoint<PointSource, PointTarget>::tree_reciprocal_;
  67. using pcl::IterativeClosestPoint<PointSource, PointTarget>::nr_iterations_;
  68. using pcl::IterativeClosestPoint<PointSource, PointTarget>::max_iterations_;
  69. using pcl::IterativeClosestPoint<PointSource, PointTarget>::previous_transformation_;
  70. using pcl::IterativeClosestPoint<PointSource, PointTarget>::final_transformation_;
  71. using pcl::IterativeClosestPoint<PointSource, PointTarget>::transformation_;
  72. using pcl::IterativeClosestPoint<PointSource, PointTarget>::transformation_epsilon_;
  73. using pcl::IterativeClosestPoint<PointSource, PointTarget>::converged_;
  74. using pcl::IterativeClosestPoint<PointSource, PointTarget>::corr_dist_threshold_;
  75. using pcl::IterativeClosestPoint<PointSource, PointTarget>::inlier_threshold_;
  76. using pcl::IterativeClosestPoint<PointSource, PointTarget>::min_number_correspondences_;
  77. using pcl::IterativeClosestPoint<PointSource, PointTarget>::update_visualizer_;
  78. typedef pcl::PointCloud<PointSource> PointCloudSource;
  79. typedef typename PointCloudSource::Ptr PointCloudSourcePtr;
  80. typedef typename PointCloudSource::ConstPtr PointCloudSourceConstPtr;
  81. typedef pcl::PointCloud<PointTarget> PointCloudTarget;
  82. typedef typename PointCloudTarget::Ptr PointCloudTargetPtr;
  83. typedef typename PointCloudTarget::ConstPtr PointCloudTargetConstPtr;
  84. typedef pcl::PointIndices::Ptr PointIndicesPtr;
  85. typedef pcl::PointIndices::ConstPtr PointIndicesConstPtr;
  86. typedef std::vector< Eigen::Matrix3d, Eigen::aligned_allocator<Eigen::Matrix3d> > MatricesVector;
  87. typedef boost::shared_ptr< MatricesVector > MatricesVectorPtr;
  88. typedef boost::shared_ptr< const MatricesVector > MatricesVectorConstPtr;
  89. typedef typename pcl::Registration<PointSource, PointTarget>::KdTree InputKdTree;
  90. typedef typename pcl::Registration<PointSource, PointTarget>::KdTreePtr InputKdTreePtr;
  91. typedef boost::shared_ptr< GeneralizedIterativeClosestPoint<PointSource, PointTarget> > Ptr;
  92. typedef boost::shared_ptr< const GeneralizedIterativeClosestPoint<PointSource, PointTarget> > ConstPtr;
  93. typedef Eigen::Matrix<double, 6, 1> Vector6d;
  94. /** \brief Empty constructor. */
  95. GeneralizedIterativeClosestPoint ()
  96. : k_correspondences_(20)
  97. , gicp_epsilon_(0.001)
  98. , rotation_epsilon_(2e-3)
  99. , mahalanobis_(0)
  100. , max_inner_iterations_(20)
  101. {
  102. min_number_correspondences_ = 4;
  103. reg_name_ = "GeneralizedIterativeClosestPoint";
  104. max_iterations_ = 200;
  105. transformation_epsilon_ = 5e-4;
  106. corr_dist_threshold_ = 5.;
  107. rigid_transformation_estimation_ =
  108. boost::bind (&GeneralizedIterativeClosestPoint<PointSource, PointTarget>::estimateRigidTransformationBFGS,
  109. this, _1, _2, _3, _4, _5);
  110. }
  111. /** \brief Provide a pointer to the input dataset
  112. * \param cloud the const boost shared pointer to a PointCloud message
  113. */
  114. // PCL_DEPRECATED ("[pcl::registration::GeneralizedIterativeClosestPoint::setInputCloud] setInputCloud is deprecated. Please use setInputSource instead.")
  115. void
  116. setInputCloud (const PointCloudSourceConstPtr &cloud);
  117. /** \brief Provide a pointer to the input dataset
  118. * \param cloud the const boost shared pointer to a PointCloud message
  119. */
  120. inline void
  121. setInputSource (const PointCloudSourceConstPtr &cloud)
  122. {
  123. if (cloud->points.empty ())
  124. {
  125. PCL_ERROR ("[pcl::%s::setInputSource] Invalid or empty point cloud dataset given!\n", getClassName ().c_str ());
  126. return;
  127. }
  128. PointCloudSource input = *cloud;
  129. // Set all the point.data[3] values to 1 to aid the rigid transformation
  130. for (size_t i = 0; i < input.size (); ++i)
  131. input[i].data[3] = 1.0;
  132. pcl::IterativeClosestPoint<PointSource, PointTarget>::setInputSource (cloud);
  133. input_covariances_.reset ();
  134. }
  135. /** \brief Provide a pointer to the covariances of the input source (if computed externally!).
  136. * If not set, GeneralizedIterativeClosestPoint will compute the covariances itself.
  137. * Make sure to set the covariances AFTER setting the input source point cloud (setting the input source point cloud will reset the covariances).
  138. * \param[in] target the input point cloud target
  139. */
  140. inline void
  141. setSourceCovariances (const MatricesVectorPtr& covariances)
  142. {
  143. input_covariances_ = covariances;
  144. }
  145. /** \brief Provide a pointer to the input target (e.g., the point cloud that we want to align the input source to)
  146. * \param[in] target the input point cloud target
  147. */
  148. inline void
  149. setInputTarget (const PointCloudTargetConstPtr &target)
  150. {
  151. pcl::IterativeClosestPoint<PointSource, PointTarget>::setInputTarget(target);
  152. target_covariances_.reset ();
  153. }
  154. /** \brief Provide a pointer to the covariances of the input target (if computed externally!).
  155. * If not set, GeneralizedIterativeClosestPoint will compute the covariances itself.
  156. * Make sure to set the covariances AFTER setting the input source point cloud (setting the input source point cloud will reset the covariances).
  157. * \param[in] target the input point cloud target
  158. */
  159. inline void
  160. setTargetCovariances (const MatricesVectorPtr& covariances)
  161. {
  162. target_covariances_ = covariances;
  163. }
  164. /** \brief Estimate a rigid rotation transformation between a source and a target point cloud using an iterative
  165. * non-linear Levenberg-Marquardt approach.
  166. * \param[in] cloud_src the source point cloud dataset
  167. * \param[in] indices_src the vector of indices describing the points of interest in \a cloud_src
  168. * \param[in] cloud_tgt the target point cloud dataset
  169. * \param[in] indices_tgt the vector of indices describing the correspondences of the interst points from \a indices_src
  170. * \param[out] transformation_matrix the resultant transformation matrix
  171. */
  172. void
  173. estimateRigidTransformationBFGS (const PointCloudSource &cloud_src,
  174. const std::vector<int> &indices_src,
  175. const PointCloudTarget &cloud_tgt,
  176. const std::vector<int> &indices_tgt,
  177. Eigen::Matrix4f &transformation_matrix);
  178. /** \brief \return Mahalanobis distance matrix for the given point index */
  179. inline const Eigen::Matrix3d& mahalanobis(size_t index) const
  180. {
  181. assert(index < mahalanobis_.size());
  182. return mahalanobis_[index];
  183. }
  184. /** \brief Computes rotation matrix derivative.
  185. * rotation matrix is obtainded from rotation angles x[3], x[4] and x[5]
  186. * \return d/d_rx, d/d_ry and d/d_rz respectively in g[3], g[4] and g[5]
  187. * param x array representing 3D transformation
  188. * param R rotation matrix
  189. * param g gradient vector
  190. */
  191. void
  192. computeRDerivative(const Vector6d &x, const Eigen::Matrix3d &R, Vector6d &g) const;
  193. /** \brief Set the rotation epsilon (maximum allowable difference between two
  194. * consecutive rotations) in order for an optimization to be considered as having
  195. * converged to the final solution.
  196. * \param epsilon the rotation epsilon
  197. */
  198. inline void
  199. setRotationEpsilon (double epsilon) { rotation_epsilon_ = epsilon; }
  200. /** \brief Get the rotation epsilon (maximum allowable difference between two
  201. * consecutive rotations) as set by the user.
  202. */
  203. inline double
  204. getRotationEpsilon () { return (rotation_epsilon_); }
  205. /** \brief Set the number of neighbors used when selecting a point neighbourhood
  206. * to compute covariances.
  207. * A higher value will bring more accurate covariance matrix but will make
  208. * covariances computation slower.
  209. * \param k the number of neighbors to use when computing covariances
  210. */
  211. void
  212. setCorrespondenceRandomness (int k) { k_correspondences_ = k; }
  213. /** \brief Get the number of neighbors used when computing covariances as set by
  214. * the user
  215. */
  216. int
  217. getCorrespondenceRandomness () { return (k_correspondences_); }
  218. /** set maximum number of iterations at the optimization step
  219. * \param[in] max maximum number of iterations for the optimizer
  220. */
  221. void
  222. setMaximumOptimizerIterations (int max) { max_inner_iterations_ = max; }
  223. ///\return maximum number of iterations at the optimization step
  224. int
  225. getMaximumOptimizerIterations () { return (max_inner_iterations_); }
  226. protected:
  227. /** \brief The number of neighbors used for covariances computation.
  228. * default: 20
  229. */
  230. int k_correspondences_;
  231. /** \brief The epsilon constant for gicp paper; this is NOT the convergence
  232. * tolerence
  233. * default: 0.001
  234. */
  235. double gicp_epsilon_;
  236. /** The epsilon constant for rotation error. (In GICP the transformation epsilon
  237. * is split in rotation part and translation part).
  238. * default: 2e-3
  239. */
  240. double rotation_epsilon_;
  241. /** \brief base transformation */
  242. Eigen::Matrix4f base_transformation_;
  243. /** \brief Temporary pointer to the source dataset. */
  244. const PointCloudSource *tmp_src_;
  245. /** \brief Temporary pointer to the target dataset. */
  246. const PointCloudTarget *tmp_tgt_;
  247. /** \brief Temporary pointer to the source dataset indices. */
  248. const std::vector<int> *tmp_idx_src_;
  249. /** \brief Temporary pointer to the target dataset indices. */
  250. const std::vector<int> *tmp_idx_tgt_;
  251. /** \brief Input cloud points covariances. */
  252. MatricesVectorPtr input_covariances_;
  253. /** \brief Target cloud points covariances. */
  254. MatricesVectorPtr target_covariances_;
  255. /** \brief Mahalanobis matrices holder. */
  256. std::vector<Eigen::Matrix3d> mahalanobis_;
  257. /** \brief maximum number of optimizations */
  258. int max_inner_iterations_;
  259. /** \brief compute points covariances matrices according to the K nearest
  260. * neighbors. K is set via setCorrespondenceRandomness() methode.
  261. * \param cloud pointer to point cloud
  262. * \param tree KD tree performer for nearest neighbors search
  263. * \param[out] cloud_covariances covariances matrices for each point in the cloud
  264. */
  265. template<typename PointT>
  266. void computeCovariances(typename pcl::PointCloud<PointT>::ConstPtr cloud,
  267. const typename pcl::search::KdTree<PointT>::ConstPtr tree,
  268. MatricesVector& cloud_covariances);
  269. /** \return trace of mat1^t . mat2
  270. * \param mat1 matrix of dimension nxm
  271. * \param mat2 matrix of dimension nxp
  272. */
  273. inline double
  274. matricesInnerProd(const Eigen::MatrixXd& mat1, const Eigen::MatrixXd& mat2) const
  275. {
  276. double r = 0.;
  277. size_t n = mat1.rows();
  278. // tr(mat1^t.mat2)
  279. for(size_t i = 0; i < n; i++)
  280. for(size_t j = 0; j < n; j++)
  281. r += mat1 (j, i) * mat2 (i,j);
  282. return r;
  283. }
  284. /** \brief Rigid transformation computation method with initial guess.
  285. * \param output the transformed input point cloud dataset using the rigid transformation found
  286. * \param guess the initial guess of the transformation to compute
  287. */
  288. void
  289. computeTransformation (PointCloudSource &output, const Eigen::Matrix4f &guess);
  290. /** \brief Search for the closest nearest neighbor of a given point.
  291. * \param query the point to search a nearest neighbour for
  292. * \param index vector of size 1 to store the index of the nearest neighbour found
  293. * \param distance vector of size 1 to store the distance to nearest neighbour found
  294. */
  295. inline bool
  296. searchForNeighbors (const PointSource &query, std::vector<int>& index, std::vector<float>& distance) const
  297. {
  298. int k = tree_->nearestKSearch (query, 1, index, distance);
  299. if (k == 0)
  300. return (false);
  301. return (true);
  302. }
  303. /// \brief compute transformation matrix from transformation matrix
  304. void applyState(Eigen::Matrix4f &t, const Vector6d& x) const;
  305. /// \brief optimization functor structure
  306. struct OptimizationFunctorWithIndices : public BFGSDummyFunctor<double,6>
  307. {
  308. OptimizationFunctorWithIndices (const GeneralizedIterativeClosestPoint* gicp)
  309. : BFGSDummyFunctor<double,6> (), gicp_(gicp) {}
  310. double operator() (const Vector6d& x);
  311. void df(const Vector6d &x, Vector6d &df);
  312. void fdf(const Vector6d &x, double &f, Vector6d &df);
  313. const GeneralizedIterativeClosestPoint *gicp_;
  314. };
  315. boost::function<void(const pcl::PointCloud<PointSource> &cloud_src,
  316. const std::vector<int> &src_indices,
  317. const pcl::PointCloud<PointTarget> &cloud_tgt,
  318. const std::vector<int> &tgt_indices,
  319. Eigen::Matrix4f &transformation_matrix)> rigid_transformation_estimation_;
  320. };
  321. }
  322. #endif //#ifndef PCL_GICP_H_