occupied_space_cost_function.cc 3.9 KB

123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384858687888990919293949596979899100101102103104105106107108109110111112113114115116117118119120121122123124
  1. #include "pose_graph/occupied_space_cost_function.h"
  2. #include "ceres/cubic_interpolation.h"
  3. #include "common/common.h"
  4. #include <Eigen/Dense>
  5. #include <Eigen/Cholesky>
  6. #include <Eigen/Geometry>
  7. namespace hlzn_slam {
  8. namespace ceres_matching {
  9. namespace {
  10. template<typename T>
  11. T ROUND(T x) // 四舍五入
  12. {
  13. return (x > 0.0) ? floor(x + 0.5) : ceil(x - 0.5);
  14. }
  15. // Computes a cost for matching the 'point_cloud' to the 'grid' with
  16. // a 'pose'. The cost increases with poorer correspondence of the grid and the
  17. // point observation (e.g. points falling into less occupied space).
  18. class OccupiedSpaceCostFunction {
  19. public:
  20. OccupiedSpaceCostFunction(const double scaling_factor,
  21. const common::PointCloud& point_cloud,
  22. Map& map)
  23. : scaling_factor_(scaling_factor),
  24. point_cloud_(point_cloud),
  25. map_(map)
  26. {
  27. adapter_ = new GridArrayAdapter(map);
  28. interpolator_ = new ceres::BiCubicInterpolator<GridArrayAdapter>(*adapter_);
  29. }
  30. ~OccupiedSpaceCostFunction() {
  31. delete adapter_;
  32. delete interpolator_;
  33. }
  34. template <typename T>
  35. void mapToWorld(const T& x, const T& y, T& world_x, T& world_y) const {
  36. const T& x_origin = T(map_.getXorigin());
  37. const T& y_origin = T(map_.getYorigin());
  38. const T& reciprocal_resolution = T(map_.getReciprocalResolution());
  39. world_x = (T)map_.getRows() - (y + y_origin) * reciprocal_resolution;
  40. world_y = (x + x_origin) * reciprocal_resolution;
  41. }
  42. template <typename T>
  43. bool operator()(const T* const pose, const T* const quaternion, T* residual) const {
  44. Eigen::Matrix<T, 3, 1> translation(pose[0], pose[1], pose[2]);
  45. Eigen::Quaternion<T> Q(quaternion[3], quaternion[0], quaternion[1], quaternion[2]);
  46. Eigen::Matrix<T, 3, 3> R = Q.toRotationMatrix();
  47. for (size_t i = 0; i < point_cloud_.data.size(); ++i) {
  48. // Note that this is a 2D point. The third component is a scaling factor.
  49. const Eigen::Matrix<T, 3, 1> point(T(point_cloud_.data[i](0)),
  50. T(point_cloud_.data[i](1)),
  51. T(1.));
  52. const Eigen::Matrix<T, 3, 1> world = R * point + translation;
  53. T x, y;
  54. mapToWorld(world[0], world[1], x, y);
  55. interpolator_->Evaluate(x, y, &residual[i]);
  56. residual[i] = scaling_factor_ * residual[i];
  57. }
  58. return true;
  59. }
  60. private:
  61. class GridArrayAdapter {
  62. public:
  63. enum { DATA_DIMENSION = 1 };
  64. explicit GridArrayAdapter(Map& map) : map_(map) {}
  65. void GetValue(const int row, const int column, double* const value) const {
  66. if (row < 0 || column < 0 || row >= NumRows() ||
  67. column >= NumCols()) {
  68. *value = 1.;
  69. } else {
  70. float probablity = 1.0 - map_.getPixelProbablity(row, column);
  71. *value = static_cast<double>(probablity);
  72. }
  73. }
  74. int NumRows() const {
  75. return map_.getRows() - 1;
  76. }
  77. int NumCols() const {
  78. return map_.getCols() - 1;
  79. }
  80. private:
  81. Map& map_;
  82. };
  83. OccupiedSpaceCostFunction(const OccupiedSpaceCostFunction&) = delete;
  84. OccupiedSpaceCostFunction& operator=(const OccupiedSpaceCostFunction&) =
  85. delete;
  86. const double scaling_factor_;
  87. const common::PointCloud& point_cloud_;
  88. Map& map_;
  89. GridArrayAdapter* adapter_;
  90. ceres::BiCubicInterpolator<GridArrayAdapter>* interpolator_;
  91. };
  92. } // namespace
  93. ceres::CostFunction* CreateOccupiedSpaceCostFunction(
  94. const double scaling_factor, const common::PointCloud& point_cloud,
  95. Map& map) {
  96. return new ceres::AutoDiffCostFunction<OccupiedSpaceCostFunction,
  97. ceres::DYNAMIC /* residuals */,
  98. 3 /* pose variables */,
  99. 4>(
  100. new OccupiedSpaceCostFunction(scaling_factor, point_cloud, map),
  101. point_cloud.data.size());
  102. }
  103. } // namespace scan_matching
  104. } // namespace cartographer