fast_gicp_st_impl.hpp 4.1 KB

123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384858687888990919293949596979899100101102103104105106107108109110111112113114115116117118119120121122123124125126127128129
  1. #ifndef FAST_GICP_FAST_GICP_ST_IMPL_HPP
  2. #define FAST_GICP_FAST_GICP_ST_IMPL_HPP
  3. #include <fast_gicp/so3/so3.hpp>
  4. #include <fast_gicp/gicp/fast_gicp_st.hpp>
  5. namespace fast_gicp {
  6. template <typename PointSource, typename PointTarget>
  7. FastGICPSingleThread<PointSource, PointTarget>::FastGICPSingleThread() : FastGICP<PointSource, PointTarget>() {
  8. this->reg_name_ = "FastGICPSingleThread";
  9. this->num_threads_ = 1;
  10. }
  11. template <typename PointSource, typename PointTarget>
  12. FastGICPSingleThread<PointSource, PointTarget>::~FastGICPSingleThread() {}
  13. template <typename PointSource, typename PointTarget>
  14. void FastGICPSingleThread<PointSource, PointTarget>::computeTransformation(PointCloudSource& output, const Matrix4& guess) {
  15. anchors_.clear();
  16. FastGICP<PointSource, PointTarget>::computeTransformation(output, guess);
  17. }
  18. template <typename PointSource, typename PointTarget>
  19. void FastGICPSingleThread<PointSource, PointTarget>::update_correspondences(const Eigen::Isometry3d& x) {
  20. assert(source_covs_.size() == input_->size());
  21. assert(target_covs_.size() == target_->size());
  22. Eigen::Isometry3f trans = x.template cast<float>();
  23. bool is_first = anchors_.empty();
  24. correspondences_.resize(input_->size());
  25. sq_distances_.resize(input_->size());
  26. second_sq_distances_.resize(input_->size());
  27. anchors_.resize(input_->size());
  28. mahalanobis_.resize(input_->size());
  29. std::vector<int> k_indices;
  30. std::vector<float> k_sq_dists;
  31. for (int i = 0; i < input_->size(); i++) {
  32. PointTarget pt;
  33. pt.getVector4fMap() = trans * input_->at(i).getVector4fMap();
  34. if (!is_first) {
  35. double d = (pt.getVector4fMap() - anchors_[i]).norm();
  36. double max_first = std::sqrt(sq_distances_[i]) + d;
  37. double min_second = std::sqrt(second_sq_distances_[i]) - d;
  38. if (max_first < min_second) {
  39. continue;
  40. }
  41. }
  42. target_kdtree_->nearestKSearch(pt, 2, k_indices, k_sq_dists);
  43. correspondences_[i] = k_sq_dists[0] < this->corr_dist_threshold_ * this->corr_dist_threshold_ ? k_indices[0] : -1;
  44. sq_distances_[i] = k_sq_dists[0];
  45. second_sq_distances_[i] = k_sq_dists[1];
  46. anchors_[i] = pt.getVector4fMap();
  47. if (correspondences_[i] < 0) {
  48. continue;
  49. }
  50. const int target_index = correspondences_[i];
  51. const auto& cov_A = source_covs_[i];
  52. const auto& cov_B = target_covs_[target_index];
  53. Eigen::Matrix4d RCR = cov_B + x.matrix() * cov_A * x.matrix().transpose();
  54. RCR(3, 3) = 1.0;
  55. mahalanobis_[i] = RCR.inverse();
  56. mahalanobis_[i](3, 3) = 0.0;
  57. }
  58. }
  59. template <typename PointSource, typename PointTarget>
  60. double FastGICPSingleThread<PointSource, PointTarget>::linearize(const Eigen::Isometry3d& trans, Eigen::Matrix<double, 6, 6>* H, Eigen::Matrix<double, 6, 1>* b) {
  61. if (H && b) {
  62. update_correspondences(trans);
  63. H->setZero();
  64. b->setZero();
  65. }
  66. double sum_errors = 0.0;
  67. for (int i = 0; i < input_->size(); i++) {
  68. int target_index = correspondences_[i];
  69. if (target_index < 0) {
  70. continue;
  71. }
  72. const Eigen::Vector4d mean_A = input_->at(i).getVector4fMap().template cast<double>();
  73. const auto& cov_A = source_covs_[i];
  74. const Eigen::Vector4d mean_B = target_->at(target_index).getVector4fMap().template cast<double>();
  75. const auto& cov_B = target_covs_[target_index];
  76. const Eigen::Vector4d transed_mean_A = trans * mean_A;
  77. const Eigen::Vector4d error = mean_B - transed_mean_A;
  78. sum_errors += error.transpose() * mahalanobis_[i] * error;
  79. if (H == nullptr || b == nullptr) {
  80. continue;
  81. }
  82. Eigen::Matrix<double, 4, 6> dtdx0 = Eigen::Matrix<double, 4, 6>::Zero();
  83. dtdx0.block<3, 3>(0, 0) = skewd(transed_mean_A.head<3>());
  84. dtdx0.block<3, 3>(0, 3) = -Eigen::Matrix3d::Identity();
  85. Eigen::Matrix<double, 4, 6> jlossexp = dtdx0;
  86. (*H) += jlossexp.transpose() * mahalanobis_[i] * jlossexp;
  87. (*b) += jlossexp.transpose() * mahalanobis_[i] * error;
  88. }
  89. return sum_errors;
  90. }
  91. template <typename PointSource, typename PointTarget>
  92. double FastGICPSingleThread<PointSource, PointTarget>::compute_error(const Eigen::Isometry3d& trans) {
  93. return linearize(trans, nullptr, nullptr);
  94. }
  95. } // namespace fast_gicp
  96. #endif