LidarKeyframeFactor.h 5.9 KB

123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384858687888990919293949596979899100101102103104105106107108109110111112113114115116117118119120121122123124125126127128129130131132133134135136137138139140141142143144145146147148149150151152153154155156157158159160161
  1. #ifndef LIDARFACTOR_H
  2. #define LIDARFACTOR_H
  3. #include <iostream>
  4. #include <ceres/ceres.h>
  5. #include <ceres/rotation.h>
  6. #include <Eigen/Dense>
  7. #include <assert.h>
  8. #include <cmath>
  9. #include "utils/math_tools.h"
  10. struct LidarEdgeFactor
  11. {
  12. EIGEN_MAKE_ALIGNED_OPERATOR_NEW
  13. LidarEdgeFactor(Eigen::Vector3d curr_point_,
  14. Eigen::Vector3d last_point_a_,
  15. Eigen::Vector3d last_point_b_,
  16. Eigen::Quaterniond qlb_,
  17. Eigen::Vector3d tlb_,
  18. double s_)
  19. : curr_point(curr_point_), last_point_a(last_point_a_), last_point_b(last_point_b_) {
  20. qlb = qlb_;
  21. tlb = tlb_;
  22. s = s_;
  23. }
  24. template <typename T>
  25. bool operator()(const T *t, const T *q, T *residual) const
  26. {
  27. Eigen::Matrix<T, 3, 1> cp{T(curr_point.x()), T(curr_point.y()), T(curr_point.z())};
  28. Eigen::Matrix<T, 3, 1> lpa{T(last_point_a.x()), T(last_point_a.y()), T(last_point_a.z())};
  29. Eigen::Matrix<T, 3, 1> lpb{T(last_point_b.x()), T(last_point_b.y()), T(last_point_b.z())};
  30. Eigen::Quaternion<T> q_last_curr{q[0], q[1], q[2], q[3]};
  31. Eigen::Matrix<T, 3, 1> t_last_curr{t[0], t[1], t[2]};
  32. Eigen::Quaternion<T> q_l_b{T(qlb.w()), T(qlb.x()), T(qlb.y()), T(qlb.z())};
  33. Eigen::Matrix<T, 3, 1> t_l_b{T(tlb.x()), T(tlb.y()), T(tlb.z())};
  34. Eigen::Matrix<T, 3, 1> lp;
  35. lp = q_last_curr * cp + t_last_curr;
  36. Eigen::Matrix<T, 3, 1> nu = (lp - lpa).cross(lp - lpb);
  37. Eigen::Matrix<T, 3, 1> de = lpa - lpb;
  38. residual[0] = nu.norm() / de.norm();
  39. residual[0] *= T(s);
  40. return true;
  41. }
  42. static ceres::CostFunction *Create(const Eigen::Vector3d curr_point_,
  43. const Eigen::Vector3d last_point_a_,
  44. const Eigen::Vector3d last_point_b_,
  45. Eigen::Quaterniond qlb_,
  46. Eigen::Vector3d tlb_,
  47. double s_)
  48. {
  49. return (new ceres::AutoDiffCostFunction<LidarEdgeFactor, 1, 3, 4>(
  50. new LidarEdgeFactor(curr_point_, last_point_a_, last_point_b_, qlb_, tlb_, s_)));
  51. }
  52. Eigen::Vector3d curr_point, last_point_a, last_point_b;
  53. Eigen::Quaterniond qlb;
  54. Eigen::Vector3d tlb;
  55. double s;
  56. };
  57. struct LidarPlaneNormFactor
  58. {
  59. LidarPlaneNormFactor(Eigen::Vector3d curr_point_,
  60. Eigen::Vector3d plane_unit_norm_,
  61. Eigen::Quaterniond qlb_,
  62. Eigen::Vector3d tlb_,
  63. double negative_OA_dot_norm_,
  64. double score_) : curr_point(curr_point_),
  65. plane_unit_norm(plane_unit_norm_),
  66. qlb(qlb_),
  67. tlb(tlb_),
  68. negative_OA_dot_norm(negative_OA_dot_norm_),
  69. score(score_) {}
  70. template <typename T>
  71. bool operator()(const T *t, const T *q, T *residual) const
  72. {
  73. Eigen::Quaternion<T> q_w_curr{q[0], q[1], q[2], q[3]};
  74. Eigen::Matrix<T, 3, 1> t_w_curr{t[0], t[1], t[2]};
  75. Eigen::Matrix<T, 3, 1> cp{T(curr_point.x()), T(curr_point.y()), T(curr_point.z())};
  76. Eigen::Matrix<T, 3, 1> point_w;
  77. Eigen::Quaternion<T> q_l_b{T(qlb.w()), T(qlb.x()), T(qlb.y()), T(qlb.z())};
  78. Eigen::Matrix<T, 3, 1> t_l_b{T(tlb.x()), T(tlb.y()), T(tlb.z())};
  79. point_w = q_l_b.inverse() * (cp - t_l_b);
  80. point_w = q_w_curr * point_w + t_w_curr;
  81. Eigen::Matrix<T, 3, 1> norm(T(plane_unit_norm.x()), T(plane_unit_norm.y()), T(plane_unit_norm.z()));
  82. residual[0] = T(score) * (norm.dot(point_w) + T(negative_OA_dot_norm));
  83. return true;
  84. }
  85. static ceres::CostFunction *Create(const Eigen::Vector3d curr_point_,
  86. const Eigen::Vector3d plane_unit_norm_,
  87. const Eigen::Quaterniond qlb_,
  88. const Eigen::Vector3d tlb_,
  89. const double negative_OA_dot_norm_,
  90. const double score_)
  91. {
  92. return (new ceres::AutoDiffCostFunction<
  93. LidarPlaneNormFactor, 1, 3, 4>(
  94. new LidarPlaneNormFactor(curr_point_, plane_unit_norm_, qlb_, tlb_, negative_OA_dot_norm_, score_)));
  95. }
  96. Eigen::Vector3d curr_point;
  97. Eigen::Vector3d plane_unit_norm;
  98. Eigen::Quaterniond qlb;
  99. Eigen::Vector3d tlb;
  100. double negative_OA_dot_norm, score;
  101. };
  102. struct LidarPlaneNormIncreFactor
  103. {
  104. LidarPlaneNormIncreFactor(Eigen::Vector3d curr_point_,
  105. Eigen::Vector3d plane_unit_norm_,
  106. double negative_OA_dot_norm_)
  107. : curr_point(curr_point_),
  108. plane_unit_norm(plane_unit_norm_),
  109. negative_OA_dot_norm(negative_OA_dot_norm_) {}
  110. template <typename T>
  111. bool operator()(const T *q, const T *t, T *residual) const
  112. {
  113. Eigen::Quaternion<T> q_inc{q[0], q[1], q[2], q[3]};
  114. Eigen::Matrix<T, 3, 1> t_inc{t[0], t[1], t[2]};
  115. Eigen::Matrix<T, 3, 1> cp{T(curr_point.x()), T(curr_point.y()), T(curr_point.z())};
  116. Eigen::Matrix<T, 3, 1> point_w;
  117. point_w = q_inc * cp + t_inc;
  118. Eigen::Matrix<T, 3, 1> norm(T(plane_unit_norm.x()), T(plane_unit_norm.y()), T(plane_unit_norm.z()));
  119. residual[0] = norm.dot(point_w) + T(negative_OA_dot_norm);
  120. return true;
  121. }
  122. static ceres::CostFunction *Create(const Eigen::Vector3d curr_point_,
  123. const Eigen::Vector3d plane_unit_norm_,
  124. const double negative_OA_dot_norm_)
  125. {
  126. return (new ceres::AutoDiffCostFunction<LidarPlaneNormIncreFactor, 1, 4, 3>(
  127. new LidarPlaneNormIncreFactor(curr_point_, plane_unit_norm_, negative_OA_dot_norm_)));
  128. }
  129. Eigen::Vector3d curr_point;
  130. Eigen::Vector3d plane_unit_norm;
  131. double negative_OA_dot_norm;
  132. };
  133. #endif // LIDARFACTOR_H