gicp_omp_impl.hpp 22 KB

123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384858687888990919293949596979899100101102103104105106107108109110111112113114115116117118119120121122123124125126127128129130131132133134135136137138139140141142143144145146147148149150151152153154155156157158159160161162163164165166167168169170171172173174175176177178179180181182183184185186187188189190191192193194195196197198199200201202203204205206207208209210211212213214215216217218219220221222223224225226227228229230231232233234235236237238239240241242243244245246247248249250251252253254255256257258259260261262263264265266267268269270271272273274275276277278279280281282283284285286287288289290291292293294295296297298299300301302303304305306307308309310311312313314315316317318319320321322323324325326327328329330331332333334335336337338339340341342343344345346347348349350351352353354355356357358359360361362363364365366367368369370371372373374375376377378379380381382383384385386387388389390391392393394395396397398399400401402403404405406407408409410411412413414415416417418419420421422423424425426427428429430431432433434435436437438439440441442443444445446447448449450451452453454455456457458459460461462463464465466467468469470471472473474475476477478479480481482483484485486487488489490491492493494495496497498499500501502503504505506507508509510511512513514515516517518519520521522523524525526527528529530531532533534535
  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_REGISTRATION_IMPL_GICP_OMP_HPP_
  41. #define PCL_REGISTRATION_IMPL_GICP_OMP_HPP_
  42. #include <atomic>
  43. #include <pcl/registration/boost.h>
  44. #include <pcl/registration/exceptions.h>
  45. ////////////////////////////////////////////////////////////////////////////////////////
  46. template <typename PointSource, typename PointTarget>
  47. template<typename PointT> void
  48. pclomp::GeneralizedIterativeClosestPoint<PointSource, PointTarget>::computeCovariances(typename pcl::PointCloud<PointT>::ConstPtr cloud,
  49. const typename pcl::search::KdTree<PointT>::ConstPtr kdtree,
  50. MatricesVector& cloud_covariances)
  51. {
  52. if (k_correspondences_ > int (cloud->size ()))
  53. {
  54. PCL_ERROR ("[pcl::GeneralizedIterativeClosestPoint::computeCovariances] Number of points in cloud (%lu) is less than k_correspondences_ (%lu)!\n", cloud->size (), k_correspondences_);
  55. return;
  56. }
  57. // We should never get there but who knows
  58. if(cloud_covariances.size () < cloud->size ())
  59. cloud_covariances.resize (cloud->size ());
  60. std::vector<std::vector<int>> nn_indices_array(omp_get_max_threads());
  61. std::vector<std::vector<float>> nn_dist_sq_array(omp_get_max_threads());
  62. #pragma omp parallel for
  63. for(std::size_t i=0; i < cloud->size(); i++) {
  64. auto& nn_indices = nn_indices_array[omp_get_thread_num()];
  65. auto& nn_dist_sq = nn_dist_sq_array[omp_get_thread_num()];
  66. const PointT &query_point = cloud->at(i);
  67. Eigen::Vector3d mean = Eigen::Vector3d::Zero();
  68. Eigen::Matrix3d &cov = cloud_covariances[i];
  69. // Zero out the cov and mean
  70. cov.setZero ();
  71. // Search for the K nearest neighbours
  72. kdtree->nearestKSearch(query_point, k_correspondences_, nn_indices, nn_dist_sq);
  73. // Find the covariance matrix
  74. for(int j = 0; j < k_correspondences_; j++) {
  75. const PointT &pt = (*cloud)[nn_indices[j]];
  76. mean[0] += pt.x;
  77. mean[1] += pt.y;
  78. mean[2] += pt.z;
  79. cov(0,0) += pt.x*pt.x;
  80. cov(1,0) += pt.y*pt.x;
  81. cov(1,1) += pt.y*pt.y;
  82. cov(2,0) += pt.z*pt.x;
  83. cov(2,1) += pt.z*pt.y;
  84. cov(2,2) += pt.z*pt.z;
  85. }
  86. mean /= static_cast<double> (k_correspondences_);
  87. // Get the actual covariance
  88. for (int k = 0; k < 3; k++)
  89. for (int l = 0; l <= k; l++)
  90. {
  91. cov(k,l) /= static_cast<double> (k_correspondences_);
  92. cov(k,l) -= mean[k]*mean[l];
  93. cov(l,k) = cov(k,l);
  94. }
  95. // Compute the SVD (covariance matrix is symmetric so U = V')
  96. Eigen::JacobiSVD<Eigen::Matrix3d> svd(cov, Eigen::ComputeFullU);
  97. cov.setZero ();
  98. Eigen::Matrix3d U = svd.matrixU ();
  99. // Reconstitute the covariance matrix with modified singular values using the column // vectors in V.
  100. for(int k = 0; k < 3; k++) {
  101. Eigen::Vector3d col = U.col(k);
  102. double v = 1.; // biggest 2 singular values replaced by 1
  103. if(k == 2) // smallest singular value replaced by gicp_epsilon
  104. v = gicp_epsilon_;
  105. cov+= v * col * col.transpose();
  106. }
  107. }
  108. }
  109. ////////////////////////////////////////////////////////////////////////////////////////
  110. template <typename PointSource, typename PointTarget> void
  111. pclomp::GeneralizedIterativeClosestPoint<PointSource, PointTarget>::computeRDerivative(const Vector6d &x, const Eigen::Matrix3d &R, Vector6d& g) const
  112. {
  113. Eigen::Matrix3d dR_dPhi;
  114. Eigen::Matrix3d dR_dTheta;
  115. Eigen::Matrix3d dR_dPsi;
  116. double phi = x[3], theta = x[4], psi = x[5];
  117. double cphi = std::cos(phi), sphi = sin(phi);
  118. double ctheta = std::cos(theta), stheta = sin(theta);
  119. double cpsi = std::cos(psi), spsi = sin(psi);
  120. dR_dPhi(0,0) = 0.;
  121. dR_dPhi(1,0) = 0.;
  122. dR_dPhi(2,0) = 0.;
  123. dR_dPhi(0,1) = sphi*spsi + cphi*cpsi*stheta;
  124. dR_dPhi(1,1) = -cpsi*sphi + cphi*spsi*stheta;
  125. dR_dPhi(2,1) = cphi*ctheta;
  126. dR_dPhi(0,2) = cphi*spsi - cpsi*sphi*stheta;
  127. dR_dPhi(1,2) = -cphi*cpsi - sphi*spsi*stheta;
  128. dR_dPhi(2,2) = -ctheta*sphi;
  129. dR_dTheta(0,0) = -cpsi*stheta;
  130. dR_dTheta(1,0) = -spsi*stheta;
  131. dR_dTheta(2,0) = -ctheta;
  132. dR_dTheta(0,1) = cpsi*ctheta*sphi;
  133. dR_dTheta(1,1) = ctheta*sphi*spsi;
  134. dR_dTheta(2,1) = -sphi*stheta;
  135. dR_dTheta(0,2) = cphi*cpsi*ctheta;
  136. dR_dTheta(1,2) = cphi*ctheta*spsi;
  137. dR_dTheta(2,2) = -cphi*stheta;
  138. dR_dPsi(0,0) = -ctheta*spsi;
  139. dR_dPsi(1,0) = cpsi*ctheta;
  140. dR_dPsi(2,0) = 0.;
  141. dR_dPsi(0,1) = -cphi*cpsi - sphi*spsi*stheta;
  142. dR_dPsi(1,1) = -cphi*spsi + cpsi*sphi*stheta;
  143. dR_dPsi(2,1) = 0.;
  144. dR_dPsi(0,2) = cpsi*sphi - cphi*spsi*stheta;
  145. dR_dPsi(1,2) = sphi*spsi + cphi*cpsi*stheta;
  146. dR_dPsi(2,2) = 0.;
  147. g[3] = matricesInnerProd(dR_dPhi, R);
  148. g[4] = matricesInnerProd(dR_dTheta, R);
  149. g[5] = matricesInnerProd(dR_dPsi, R);
  150. }
  151. ////////////////////////////////////////////////////////////////////////////////////////
  152. template <typename PointSource, typename PointTarget> void
  153. pclomp::GeneralizedIterativeClosestPoint<PointSource, PointTarget>::estimateRigidTransformationBFGS (const PointCloudSource &cloud_src,
  154. const std::vector<int> &indices_src,
  155. const PointCloudTarget &cloud_tgt,
  156. const std::vector<int> &indices_tgt,
  157. Eigen::Matrix4f &transformation_matrix)
  158. {
  159. if (indices_src.size () < 4) // need at least 4 samples
  160. {
  161. PCL_THROW_EXCEPTION (pcl::NotEnoughPointsException,
  162. "[pcl::GeneralizedIterativeClosestPoint::estimateRigidTransformationBFGS] Need at least 4 points to estimate a transform! Source and target have " << indices_src.size () << " points!");
  163. return;
  164. }
  165. // Set the initial solution
  166. Vector6d x = Vector6d::Zero ();
  167. x[0] = transformation_matrix (0,3);
  168. x[1] = transformation_matrix (1,3);
  169. x[2] = transformation_matrix (2,3);
  170. x[3] = std::atan2 (transformation_matrix (2,1), transformation_matrix (2,2));
  171. x[4] = asin (-transformation_matrix (2,0));
  172. x[5] = std::atan2 (transformation_matrix (1,0), transformation_matrix (0,0));
  173. // Set temporary pointers
  174. tmp_src_ = &cloud_src;
  175. tmp_tgt_ = &cloud_tgt;
  176. tmp_idx_src_ = &indices_src;
  177. tmp_idx_tgt_ = &indices_tgt;
  178. // Optimize using forward-difference approximation LM
  179. const double gradient_tol = 1e-2;
  180. OptimizationFunctorWithIndices functor(this);
  181. BFGS<OptimizationFunctorWithIndices> bfgs (functor);
  182. bfgs.parameters.sigma = 0.01;
  183. bfgs.parameters.rho = 0.01;
  184. bfgs.parameters.tau1 = 9;
  185. bfgs.parameters.tau2 = 0.05;
  186. bfgs.parameters.tau3 = 0.5;
  187. bfgs.parameters.order = 3;
  188. int inner_iterations_ = 0;
  189. int result = bfgs.minimizeInit (x);
  190. result = BFGSSpace::Running;
  191. do
  192. {
  193. inner_iterations_++;
  194. result = bfgs.minimizeOneStep (x);
  195. if(result)
  196. {
  197. break;
  198. }
  199. #if PCL_VERSION_COMPARE(<, 1, 11, 0)
  200. result = bfgs.testGradient(gradient_tol);
  201. #else
  202. result = bfgs.testGradient();
  203. #endif
  204. } while(result == BFGSSpace::Running && inner_iterations_ < max_inner_iterations_);
  205. if(result == BFGSSpace::NoProgress || result == BFGSSpace::Success || inner_iterations_ == max_inner_iterations_)
  206. {
  207. PCL_DEBUG ("[pcl::registration::TransformationEstimationBFGS::estimateRigidTransformation]");
  208. PCL_DEBUG ("BFGS solver finished with exit code %i \n", result);
  209. transformation_matrix.setIdentity();
  210. applyState(transformation_matrix, x);
  211. }
  212. else
  213. PCL_THROW_EXCEPTION(pcl::SolverDidntConvergeException,
  214. "[pcl::" << getClassName () << "::TransformationEstimationBFGS::estimateRigidTransformation] BFGS solver didn't converge!");
  215. }
  216. ////////////////////////////////////////////////////////////////////////////////////////
  217. template <typename PointSource, typename PointTarget> inline double
  218. pclomp::GeneralizedIterativeClosestPoint<PointSource, PointTarget>::OptimizationFunctorWithIndices::operator() (const Vector6d& x)
  219. {
  220. Eigen::Matrix4f transformation_matrix = gicp_->base_transformation_;
  221. gicp_->applyState(transformation_matrix, x);
  222. double f = 0;
  223. std::vector<double> f_array(omp_get_max_threads(), 0.0);
  224. int m = static_cast<int> (gicp_->tmp_idx_src_->size ());
  225. #pragma omp parallel for
  226. for(int i = 0; i < m; ++i)
  227. {
  228. // The last coordinate, p_src[3] is guaranteed to be set to 1.0 in registration.hpp
  229. pcl::Vector4fMapConst p_src = gicp_->tmp_src_->points[(*gicp_->tmp_idx_src_)[i]].getVector4fMap();
  230. // The last coordinate, p_tgt[3] is guaranteed to be set to 1.0 in registration.hpp
  231. pcl::Vector4fMapConst p_tgt = gicp_->tmp_tgt_->points[(*gicp_->tmp_idx_tgt_)[i]].getVector4fMap();
  232. // Estimate the distance (cost function)
  233. // The last coordinate is still guaranteed to be set to 1.0
  234. // Eigen::AlignedVector3<double> res(pp[0] - p_tgt[0], pp[1] - p_tgt[1], pp[2] - p_tgt[2]);
  235. // Eigen::AlignedVector3<double> temp(gicp_->mahalanobis((*gicp_->tmp_idx_src_)[i]) * res);
  236. Eigen::Vector4f res = transformation_matrix * p_src - p_tgt;
  237. Eigen::Matrix4f maha = gicp_->mahalanobis((*gicp_->tmp_idx_src_)[i]);
  238. // Eigen::Vector4d temp(maha * res);
  239. // increment= res'*temp/num_matches = temp'*M*temp/num_matches (we postpone 1/num_matches after the loop closes)
  240. // double ret = double(res.transpose() * temp);
  241. double ret = res.dot(maha*res);
  242. f_array[omp_get_thread_num()] += ret;
  243. }
  244. f = std::accumulate(f_array.begin(), f_array.end(), 0.0);
  245. return f/m;
  246. }
  247. ////////////////////////////////////////////////////////////////////////////////////////
  248. template <typename PointSource, typename PointTarget> inline void
  249. pclomp::GeneralizedIterativeClosestPoint<PointSource, PointTarget>::OptimizationFunctorWithIndices::df (const Vector6d& x, Vector6d& g)
  250. {
  251. Eigen::Matrix4f transformation_matrix = gicp_->base_transformation_;
  252. gicp_->applyState(transformation_matrix, x);
  253. //Eigen::Vector3d g_t = g.head<3> ();
  254. std::vector<Eigen::Matrix4d, Eigen::aligned_allocator<Eigen::Matrix4d>> R_array(omp_get_max_threads());
  255. std::vector<Eigen::Vector4d, Eigen::aligned_allocator<Eigen::Vector4d>> g_array(omp_get_max_threads());
  256. for (std::size_t i = 0; i < R_array.size(); i++) {
  257. R_array[i].setZero();
  258. g_array[i].setZero();
  259. }
  260. int m = static_cast<int> (gicp_->tmp_idx_src_->size ());
  261. #pragma omp parallel for
  262. for(int i = 0; i < m; ++i)
  263. {
  264. // The last coordinate, p_src[3] is guaranteed to be set to 1.0 in registration.hpp
  265. pcl::Vector4fMapConst p_src = gicp_->tmp_src_->points[(*gicp_->tmp_idx_src_)[i]].getVector4fMap();
  266. // The last coordinate, p_tgt[3] is guaranteed to be set to 1.0 in registration.hpp
  267. pcl::Vector4fMapConst p_tgt = gicp_->tmp_tgt_->points[(*gicp_->tmp_idx_tgt_)[i]].getVector4fMap();
  268. Eigen::Vector4f pp(transformation_matrix * p_src);
  269. // The last coordinate is still guaranteed to be set to 1.0
  270. Eigen::Vector4d res(pp[0] - p_tgt[0], pp[1] - p_tgt[1], pp[2] - p_tgt[2], 0.0);
  271. // temp = M*res
  272. Eigen::Matrix4d maha = gicp_->mahalanobis((*gicp_->tmp_idx_src_)[i]).template cast<double>();
  273. Eigen::Vector4d temp(maha * res);
  274. // Increment translation gradient
  275. // g.head<3> ()+= 2*M*res/num_matches (we postpone 2/num_matches after the loop closes)
  276. // Increment rotation gradient
  277. pp = gicp_->base_transformation_ * p_src;
  278. Eigen::Vector4d p_src3(pp[0], pp[1], pp[2], 0.0);
  279. g_array[omp_get_thread_num()] += temp;
  280. R_array[omp_get_thread_num()] += p_src3 * temp.transpose();
  281. }
  282. g.setZero();
  283. Eigen::Matrix4d R = Eigen::Matrix4d::Zero();
  284. for (std::size_t i = 0; i < R_array.size(); i++) {
  285. R += R_array[i];
  286. g.head<3>() += g_array[i].head<3>();
  287. }
  288. g.head<3>() *= 2.0 / m;
  289. R *= 2.0 / m;
  290. gicp_->computeRDerivative(x, R.block<3, 3>(0, 0), g);
  291. }
  292. ////////////////////////////////////////////////////////////////////////////////////////
  293. template <typename PointSource, typename PointTarget> inline void
  294. pclomp::GeneralizedIterativeClosestPoint<PointSource, PointTarget>::OptimizationFunctorWithIndices::fdf (const Vector6d& x, double& f, Vector6d& g)
  295. {
  296. Eigen::Matrix4f transformation_matrix = gicp_->base_transformation_;
  297. gicp_->applyState(transformation_matrix, x);
  298. f = 0;
  299. g.setZero ();
  300. Eigen::Matrix3d R = Eigen::Matrix3d::Zero ();
  301. const auto m = static_cast<int> (gicp_->tmp_idx_src_->size ());
  302. for (int i = 0; i < m; ++i)
  303. {
  304. // The last coordinate, p_src[3] is guaranteed to be set to 1.0 in registration.hpp
  305. pcl::Vector4fMapConst p_src = gicp_->tmp_src_->points[(*gicp_->tmp_idx_src_)[i]].getVector4fMap ();
  306. // The last coordinate, p_tgt[3] is guaranteed to be set to 1.0 in registration.hpp
  307. pcl::Vector4fMapConst p_tgt = gicp_->tmp_tgt_->points[(*gicp_->tmp_idx_tgt_)[i]].getVector4fMap ();
  308. Eigen::Vector4f pp (transformation_matrix * p_src);
  309. // The last coordinate is still guaranteed to be set to 1.0
  310. Eigen::Vector3d res (pp[0] - p_tgt[0], pp[1] - p_tgt[1], pp[2] - p_tgt[2]);
  311. // temp = M*res
  312. Eigen::Vector3d temp (gicp_->mahalanobis((*gicp_->tmp_idx_src_)[i]).template block<3, 3>(0, 0).template cast<double>() * res);
  313. // Increment total error
  314. f+= double(res.transpose() * temp);
  315. // Increment translation gradient
  316. // g.head<3> ()+= 2*M*res/num_matches (we postpone 2/num_matches after the loop closes)
  317. g.head<3> ()+= temp;
  318. pp = gicp_->base_transformation_ * p_src;
  319. Eigen::Vector3d p_src3 (pp[0], pp[1], pp[2]);
  320. // Increment rotation gradient
  321. R+= p_src3 * temp.transpose();
  322. }
  323. f/= double(m);
  324. g.head<3> ()*= double(2.0/m);
  325. R*= 2.0/m;
  326. gicp_->computeRDerivative(x, R, g);
  327. }
  328. ////////////////////////////////////////////////////////////////////////////////////////
  329. template <typename PointSource, typename PointTarget> inline void
  330. pclomp::GeneralizedIterativeClosestPoint<PointSource, PointTarget>::computeTransformation (PointCloudSource &output, const Eigen::Matrix4f& guess)
  331. {
  332. pcl::IterativeClosestPoint<PointSource, PointTarget>::initComputeReciprocal ();
  333. using namespace std;
  334. // Difference between consecutive transforms
  335. double delta = 0;
  336. // Get the size of the target
  337. const size_t N = indices_->size ();
  338. // Set the mahalanobis matrices to identity
  339. mahalanobis_.resize (N, Eigen::Matrix4f::Identity ());
  340. // Compute target cloud covariance matrices
  341. if ((!target_covariances_) || (target_covariances_->empty ()))
  342. {
  343. target_covariances_.reset (new MatricesVector);
  344. computeCovariances<PointTarget> (target_, tree_, *target_covariances_);
  345. }
  346. // Compute input cloud covariance matrices
  347. if ((!input_covariances_) || (input_covariances_->empty ()))
  348. {
  349. input_covariances_.reset (new MatricesVector);
  350. computeCovariances<PointSource> (input_, tree_reciprocal_, *input_covariances_);
  351. }
  352. base_transformation_ = Eigen::Matrix4f::Identity();
  353. nr_iterations_ = 0;
  354. converged_ = false;
  355. double dist_threshold = corr_dist_threshold_ * corr_dist_threshold_;
  356. pcl::transformPointCloud(output, output, guess);
  357. std::vector<std::vector<int>> nn_indices_array(omp_get_max_threads());
  358. std::vector<std::vector<float>> nn_dists_array(omp_get_max_threads());
  359. for (auto& nn_indices : nn_indices_array) { nn_indices.resize(1); }
  360. for (auto& nn_dists : nn_dists_array) { nn_dists.resize(1); }
  361. while(!converged_)
  362. {
  363. std::atomic<size_t> cnt;
  364. cnt = 0;
  365. std::vector<int> source_indices (indices_->size ());
  366. std::vector<int> target_indices (indices_->size ());
  367. // guess corresponds to base_t and transformation_ to t
  368. Eigen::Matrix4d transform_R = Eigen::Matrix4d::Zero ();
  369. for(size_t i = 0; i < 4; i++)
  370. for(size_t j = 0; j < 4; j++)
  371. for(size_t k = 0; k < 4; k++)
  372. transform_R(i,j)+= double(transformation_(i,k)) * double(guess(k,j));
  373. const Eigen::Matrix3d R = transform_R.topLeftCorner<3,3> ();
  374. #pragma omp parallel for
  375. for (std::size_t i = 0; i < N; i++)
  376. {
  377. auto& nn_indices = nn_indices_array[omp_get_thread_num()];
  378. auto& nn_dists = nn_dists_array[omp_get_thread_num()];
  379. PointSource query = output[i];
  380. query.getVector4fMap () = transformation_ * query.getVector4fMap ();
  381. if (!searchForNeighbors (query, nn_indices, nn_dists))
  382. {
  383. PCL_ERROR ("[pcl::%s::computeTransformation] Unable to find a nearest neighbor in the target dataset for point %d in the source!\n", getClassName ().c_str (), (*indices_)[i]);
  384. continue;
  385. }
  386. // Check if the distance to the nearest neighbor is smaller than the user imposed threshold
  387. if (nn_dists[0] < dist_threshold)
  388. {
  389. const Eigen::Matrix3d &C1 = (*input_covariances_)[i];
  390. const Eigen::Matrix3d &C2 = (*target_covariances_)[nn_indices[0]];
  391. Eigen::Matrix4f& M_ = mahalanobis_[i];
  392. M_.setZero();
  393. Eigen::Matrix3d M = M_.block<3, 3>(0, 0).cast<double>();
  394. // M = R*C1
  395. M = R * C1;
  396. // temp = M*R' + C2 = R*C1*R' + C2
  397. Eigen::Matrix3d temp = M * R.transpose();
  398. temp+= C2;
  399. // M = temp^-1
  400. M = temp.inverse ();
  401. M_.block<3, 3>(0, 0) = M.cast<float>();
  402. int c = cnt++;
  403. source_indices[c] = static_cast<int> (i);
  404. target_indices[c] = nn_indices[0];
  405. }
  406. }
  407. // Resize to the actual number of valid correspondences
  408. source_indices.resize(cnt); target_indices.resize(cnt);
  409. std::vector<std::pair<int, int>> indices(source_indices.size());
  410. for(std::size_t i = 0; i<source_indices.size(); i++) {
  411. indices[i].first = source_indices[i];
  412. indices[i].second = target_indices[i];
  413. }
  414. std::sort(indices.begin(), indices.end(), [=](const std::pair<int, int>& lhs, const std::pair<int, int>& rhs) { return lhs.first < rhs.first; });
  415. for(std::size_t i = 0; i < source_indices.size(); i++) {
  416. source_indices[i] = indices[i].first;
  417. target_indices[i] = indices[i].second;
  418. }
  419. /* optimize transformation using the current assignment and Mahalanobis metrics*/
  420. previous_transformation_ = transformation_;
  421. //optimization right here
  422. try
  423. {
  424. rigid_transformation_estimation_(output, source_indices, *target_, target_indices, transformation_);
  425. /* compute the delta from this iteration */
  426. delta = 0.;
  427. for(int k = 0; k < 4; k++) {
  428. for(int l = 0; l < 4; l++) {
  429. double ratio = 1;
  430. if(k < 3 && l < 3) // rotation part of the transform
  431. ratio = 1./rotation_epsilon_;
  432. else
  433. ratio = 1./transformation_epsilon_;
  434. double c_delta = ratio*std::abs(previous_transformation_(k,l) - transformation_(k,l));
  435. if(c_delta > delta)
  436. delta = c_delta;
  437. }
  438. }
  439. }
  440. catch (pcl::PCLException &e)
  441. {
  442. PCL_DEBUG ("[pcl::%s::computeTransformation] Optimization issue %s\n", getClassName ().c_str (), e.what ());
  443. break;
  444. }
  445. nr_iterations_++;
  446. // Check for convergence
  447. if (nr_iterations_ >= max_iterations_ || delta < 1)
  448. {
  449. converged_ = true;
  450. previous_transformation_ = transformation_;
  451. PCL_DEBUG ("[pcl::%s::computeTransformation] Convergence reached. Number of iterations: %d out of %d. Transformation difference: %f\n",
  452. getClassName ().c_str (), nr_iterations_, max_iterations_, (transformation_ - previous_transformation_).array ().abs ().sum ());
  453. }
  454. else
  455. PCL_DEBUG ("[pcl::%s::computeTransformation] Convergence failed\n", getClassName ().c_str ());
  456. }
  457. final_transformation_ = previous_transformation_ * guess;
  458. // Transform the point cloud
  459. pcl::transformPointCloud (*input_, output, final_transformation_);
  460. }
  461. template <typename PointSource, typename PointTarget> void
  462. pclomp::GeneralizedIterativeClosestPoint<PointSource, PointTarget>::applyState(Eigen::Matrix4f &t, const Vector6d& x) const
  463. {
  464. // !!! CAUTION Stanford GICP uses the Z Y X euler angles convention
  465. Eigen::Matrix3f R;
  466. R = Eigen::AngleAxisf (static_cast<float> (x[5]), Eigen::Vector3f::UnitZ ())
  467. * Eigen::AngleAxisf (static_cast<float> (x[4]), Eigen::Vector3f::UnitY ())
  468. * Eigen::AngleAxisf (static_cast<float> (x[3]), Eigen::Vector3f::UnitX ());
  469. t.topLeftCorner<3,3> ().matrix () = R * t.topLeftCorner<3,3> ().matrix ();
  470. Eigen::Vector4f T (static_cast<float> (x[0]), static_cast<float> (x[1]), static_cast<float> (x[2]), 0.0f);
  471. t.col (3) += T;
  472. }
  473. #endif //PCL_REGISTRATION_IMPL_GICP_HPP_