icp_svd_registration.cpp 7.9 KB

123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384858687888990919293949596979899100101102103104105106107108109110111112113114115116117118119120121122123124125126127128129130131132133134135136137138139140141142143144145146147148149150151152153154155156157158159160161162163164165166167168169170171172173174175176177178179180181182183184185186187188189190191192193194195196197198199200201202203204205206207208209210211212213214215216217218219220221222223224225226227228229230231232233234235236237238239240241242243244245246247248249250251252253254
  1. /*
  2. * @Description: ICP SVD lidar odometry
  3. * @Author: Ge Yao
  4. * @Date: 2020-10-24 21:46:45
  5. */
  6. #include <pcl/common/transforms.h>
  7. #include <cmath>
  8. #include <vector>
  9. #include <Eigen/Dense>
  10. #include <Eigen/SVD>
  11. #include "glog/logging.h"
  12. #include "icp_svd_registration.hpp"
  13. ICPSVDRegistration::ICPSVDRegistration(
  14. const YAML::Node& node
  15. ) : input_target_kdtree_(new pcl::KdTreeFLANN<pcl::PointXYZ>()) {
  16. // parse params:
  17. float max_corr_dist = node["max_corr_dist"].as<float>();
  18. float trans_eps = node["trans_eps"].as<float>();
  19. float euc_fitness_eps = node["euc_fitness_eps"].as<float>();
  20. int max_iter = node["max_iter"].as<int>();
  21. SetRegistrationParam(max_corr_dist, trans_eps, euc_fitness_eps, max_iter);
  22. }
  23. ICPSVDRegistration::ICPSVDRegistration(
  24. float max_corr_dist,
  25. float trans_eps,
  26. float euc_fitness_eps,
  27. int max_iter
  28. ) : input_target_kdtree_(new pcl::KdTreeFLANN<pcl::PointXYZ>()) {
  29. SetRegistrationParam(max_corr_dist, trans_eps, euc_fitness_eps, max_iter);
  30. }
  31. bool ICPSVDRegistration::SetRegistrationParam(
  32. float max_corr_dist,
  33. float trans_eps,
  34. float euc_fitness_eps,
  35. int max_iter
  36. ) {
  37. // set params:
  38. max_corr_dist_ = max_corr_dist;
  39. trans_eps_ = trans_eps;
  40. euc_fitness_eps_ = euc_fitness_eps;
  41. max_iter_ = max_iter;
  42. // LOG(INFO) << "ICP SVD params:" << std::endl
  43. // << "max_corr_dist: " << max_corr_dist_ << ", "
  44. // << "trans_eps: " << trans_eps_ << ", "
  45. // << "euc_fitness_eps: " << euc_fitness_eps_ << ", "
  46. // << "max_iter: " << max_iter_
  47. // << std::endl << std::endl;
  48. return true;
  49. }
  50. bool ICPSVDRegistration::SetInputTarget(const pcl::PointCloud<pcl::PointXYZ>::Ptr& input_target) {
  51. input_target_ = input_target;
  52. input_target_kdtree_->setInputCloud(input_target_);
  53. return true;
  54. }
  55. bool ICPSVDRegistration::ScanMatch(
  56. const pcl::PointCloud<pcl::PointXYZ>::Ptr& input_source,
  57. const Eigen::Matrix4f& predict_pose,
  58. pcl::PointCloud<pcl::PointXYZ>::Ptr& result_cloud_ptr,
  59. Eigen::Matrix4f& result_pose
  60. ) {
  61. input_source_ = input_source;
  62. // pre-process input source:
  63. pcl::PointCloud<pcl::PointXYZ>::Ptr transformed_input_source(new pcl::PointCloud<pcl::PointXYZ>());
  64. pcl::transformPointCloud(*input_source_, *transformed_input_source, predict_pose);
  65. // init estimation:
  66. transformation_.setIdentity();
  67. //
  68. // TODO: first option -- implement all computing logic on your own
  69. //
  70. // do estimation:
  71. int curr_iter = 0;
  72. while (curr_iter < max_iter_) {
  73. // TODO: apply current estimation:
  74. Eigen::Matrix4f t_current_pose = transformation_ * predict_pose;
  75. pcl::transformPointCloud(*input_source_, *transformed_input_source, t_current_pose);
  76. // TODO: get correspondence:
  77. std::vector<Eigen::Vector3f> xs, ys;
  78. size_t t_correspondence = GetCorrespondence(transformed_input_source, xs, ys);
  79. // TODO: do not have enough correspondence -- break:
  80. if(t_correspondence < 4 || xs.size() != ys.size() || xs.size()<=0)
  81. {
  82. // std::cout<<"icp_svd not enough correspondence "<<std::endl;
  83. return false;
  84. }
  85. // TODO: update current transform:
  86. Eigen::Matrix4f t_iter_transform;
  87. GetTransform(xs, ys, t_iter_transform);
  88. // calculate whether match fitness epsilon
  89. float t_avg_correspond_dist_sq = 0.0f;
  90. for (int i = 0; i < xs.size(); i++)
  91. {
  92. float t_correspond_dist_sq = pow(xs[i].x()-ys[i].x(), 2) +
  93. pow(xs[i].y()-ys[i].y(), 2) +
  94. pow(xs[i].z()-ys[i].z(), 2);
  95. t_avg_correspond_dist_sq += t_correspond_dist_sq;
  96. }
  97. t_avg_correspond_dist_sq /= xs.size();
  98. if(t_avg_correspond_dist_sq > euc_fitness_eps_)
  99. {
  100. // std::cout<<"correspond avg dist sq too large: " << t_avg_correspond_dist_sq <<std::endl;
  101. return false;
  102. }
  103. // TODO: whether the transformation update is significant:
  104. // break if convergent
  105. if (!IsSignificant(t_iter_transform, trans_eps_)) {
  106. // transformation_ = t_iter_transform * transformation_;
  107. break;
  108. }
  109. // TODO: update transformation:
  110. transformation_ = t_iter_transform * transformation_;
  111. ++curr_iter;
  112. }
  113. if(curr_iter>=max_iter_)
  114. {
  115. transformation_.setIdentity();
  116. return false;
  117. }
  118. // set output:
  119. result_pose = transformation_ * predict_pose;
  120. pcl::transformPointCloud(*input_source_, *result_cloud_ptr, result_pose);
  121. // std::cout<<"quat: "<<Eigen::Quaternionf(transformation_.block<3,3>(0,0)).coeffs().transpose()<<std::endl;
  122. // std::cout << "iter count:" << curr_iter << std::endl;
  123. return true;
  124. }
  125. size_t ICPSVDRegistration::GetCorrespondence(
  126. const pcl::PointCloud<pcl::PointXYZ>::Ptr &input_source,
  127. std::vector<Eigen::Vector3f> &xs,
  128. std::vector<Eigen::Vector3f> &ys
  129. ) {
  130. const float MAX_CORR_DIST_SQR = max_corr_dist_ * max_corr_dist_;
  131. size_t num_corr = 0;
  132. // TODO: set up point correspondence
  133. xs.clear();
  134. ys.clear();
  135. std::vector<int> t_indices;
  136. std::vector<float> t_sqr_dists;
  137. for (int i = 0; i < input_source->size(); i++)
  138. {
  139. int neighbors = input_target_kdtree_->nearestKSearch(input_source->points[i], 1, t_indices, t_sqr_dists);
  140. if(neighbors>0 && t_sqr_dists[0] < MAX_CORR_DIST_SQR)
  141. {
  142. xs.push_back(Eigen::Vector3f(input_target_->points[t_indices[0]].x,
  143. input_target_->points[t_indices[0]].y,
  144. input_target_->points[t_indices[0]].z));
  145. ys.push_back(Eigen::Vector3f(input_source->points[i].x,
  146. input_source->points[i].y,
  147. input_source->points[i].z));
  148. num_corr++;
  149. }
  150. }
  151. return num_corr;
  152. }
  153. void ICPSVDRegistration::GetTransform(
  154. const std::vector<Eigen::Vector3f> &xs,
  155. const std::vector<Eigen::Vector3f> &ys,
  156. Eigen::Matrix4f &transformation
  157. ) {
  158. const size_t N = xs.size();
  159. // TODO: find centroids of mu_x and mu_y:
  160. Eigen::Vector3f ux=Eigen::Vector3f::Zero(), uy=Eigen::Vector3f::Zero();
  161. for (size_t i = 0; i < N; i++)
  162. {
  163. ux += xs[i];
  164. uy += ys[i];
  165. }
  166. ux /= N;
  167. uy /= N;
  168. // TODO: build H:
  169. // H = sum((yi-uy) * (xi-ux)_t)
  170. Eigen::Matrix3f H = Eigen::Matrix3f::Zero();
  171. for (size_t i = 0; i < N; i++)
  172. {
  173. H += (ys[i]-uy) * (xs[i]-ux).transpose();
  174. }
  175. // TODO: solve R:
  176. // H = U * S * V_t
  177. // R = V * U_t
  178. Eigen::JacobiSVD<Eigen::MatrixXf> svd_h(H, Eigen::ComputeFullU | Eigen::ComputeFullV);
  179. Eigen::Matrix3f u = svd_h.matrixU();
  180. Eigen::Matrix3f v = svd_h.matrixV();
  181. if(u.determinant() * v.determinant() <0)
  182. {
  183. for (size_t i = 0; i < 3; i++)
  184. {
  185. v(i, 2) *= -1;
  186. }
  187. }
  188. Eigen::Matrix3f R = v * u.transpose();
  189. Eigen::Quaternionf t_quat(R);
  190. t_quat.normalize();
  191. // TODO: solve t:
  192. // e2 = || ux - R * uy -t ||^2
  193. // t = ux - R * uy
  194. Eigen::Vector3f t = ux - t_quat.toRotationMatrix() * uy;
  195. // TODO: set output:
  196. transformation << t_quat.toRotationMatrix(), t, 0.0f, 0.0f, 0.0f, 1.0f;
  197. }
  198. bool ICPSVDRegistration::IsSignificant(
  199. const Eigen::Matrix4f &transformation,
  200. const float trans_eps
  201. ) {
  202. // a. translation magnitude -- norm:
  203. float translation_magnitude = transformation.block<3, 1>(0, 3).norm();
  204. // b. rotation magnitude -- angle:
  205. float rotation_magnitude = fabs(
  206. acos(
  207. (std::min(transformation.block<3, 3>(0, 0).trace(), 2.999999f) - 1.0f) / 2.0f
  208. )
  209. );
  210. // std::cout << "two mag: " << translation_magnitude << ", " << rotation_magnitude << std::endl;
  211. return (
  212. (translation_magnitude > trans_eps) ||
  213. (rotation_magnitude > trans_eps)
  214. );
  215. }