LidarKeyframeFactor.h 5.8 KB

123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384858687888990919293949596979899100101102103104105106107108109110111112113114115116117118119120121122123124125126127128129130131132133134135136137138139140141
  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. //To do: LidarKeyframeFactor.h
  11. struct LidarEdgeFactor {
  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_): curr_point(curr_point_), last_point_a(last_point_a_), last_point_b(last_point_b_) {
  19. qlb = qlb_;
  20. tlb = tlb_;
  21. s = s_;
  22. }
  23. template <typename T> bool operator()(const T *t, const T *q, T *residual) const {
  24. Eigen::Matrix<T, 3, 1> cp{T(curr_point.x()), T(curr_point.y()), T(curr_point.z())};
  25. Eigen::Matrix<T, 3, 1> lpa{T(last_point_a.x()), T(last_point_a.y()), T(last_point_a.z())};
  26. Eigen::Matrix<T, 3, 1> lpb{T(last_point_b.x()), T(last_point_b.y()), T(last_point_b.z())};
  27. Eigen::Quaternion<T> q_last_curr{q[0], q[1], q[2], q[3]};
  28. Eigen::Matrix<T, 3, 1> t_last_curr{t[0], t[1], t[2]};
  29. Eigen::Quaternion<T> q_l_b{T(qlb.w()), T(qlb.x()), T(qlb.y()), T(qlb.z())};
  30. Eigen::Matrix<T, 3, 1> t_l_b{T(tlb.x()), T(tlb.y()), T(tlb.z())};
  31. Eigen::Matrix<T, 3, 1> lp;
  32. lp = q_last_curr * cp + t_last_curr;
  33. Eigen::Matrix<T, 3, 1> nu = (lp - lpa).cross(lp - lpb);
  34. Eigen::Matrix<T, 3, 1> de = lpa - lpb;
  35. residual[0] = nu.norm() / de.norm();
  36. residual[0] *= T(s);
  37. return true;
  38. }
  39. static ceres::CostFunction *Create(const Eigen::Vector3d curr_point_,
  40. const Eigen::Vector3d last_point_a_,
  41. const Eigen::Vector3d last_point_b_,
  42. Eigen::Quaterniond qlb_,
  43. Eigen::Vector3d tlb_,
  44. double s_) {
  45. return (new ceres::AutoDiffCostFunction<LidarEdgeFactor, 1, 3, 4>(new LidarEdgeFactor(curr_point_, last_point_a_, last_point_b_, qlb_, tlb_, s_)));
  46. }
  47. Eigen::Vector3d curr_point, last_point_a, last_point_b;
  48. Eigen::Quaterniond qlb;
  49. Eigen::Vector3d tlb;
  50. double s;
  51. };
  52. struct LidarPlaneNormFactor {
  53. LidarPlaneNormFactor(Eigen::Vector3d curr_point_,
  54. Eigen::Vector3d plane_unit_norm_,
  55. Eigen::Quaterniond qlb_,
  56. Eigen::Vector3d tlb_,
  57. double negative_OA_dot_norm_,
  58. double score_): curr_point(curr_point_),
  59. plane_unit_norm(plane_unit_norm_),
  60. qlb(qlb_),
  61. tlb(tlb_),
  62. negative_OA_dot_norm(negative_OA_dot_norm_),
  63. score(score_) {}
  64. template <typename T> bool operator()(const T *t, const T *q, T *residual) const {
  65. Eigen::Quaternion<T> q_w_curr{q[0], q[1], q[2], q[3]};
  66. Eigen::Matrix<T, 3, 1> t_w_curr{t[0], t[1], t[2]};
  67. Eigen::Matrix<T, 3, 1> cp{T(curr_point.x()), T(curr_point.y()), T(curr_point.z())};
  68. Eigen::Matrix<T, 3, 1> point_w;
  69. Eigen::Quaternion<T> q_l_b{T(qlb.w()), T(qlb.x()), T(qlb.y()), T(qlb.z())};
  70. Eigen::Matrix<T, 3, 1> t_l_b{T(tlb.x()), T(tlb.y()), T(tlb.z())};
  71. point_w = q_l_b.inverse() * (cp - t_l_b);
  72. point_w = q_w_curr * point_w + t_w_curr;
  73. Eigen::Matrix<T, 3, 1> norm(T(plane_unit_norm.x()), T(plane_unit_norm.y()), T(plane_unit_norm.z()));
  74. residual[0] = T(score) * (norm.dot(point_w) + T(negative_OA_dot_norm));
  75. return true;
  76. }
  77. static ceres::CostFunction *Create(const Eigen::Vector3d curr_point_,
  78. const Eigen::Vector3d plane_unit_norm_,
  79. const Eigen::Quaterniond qlb_,
  80. const Eigen::Vector3d tlb_,
  81. const double negative_OA_dot_norm_,
  82. const double score_) {
  83. return (new ceres::AutoDiffCostFunction<LidarPlaneNormFactor, 1, 3, 4>(new LidarPlaneNormFactor(curr_point_, plane_unit_norm_, qlb_, tlb_, negative_OA_dot_norm_, score_)));
  84. }
  85. Eigen::Vector3d curr_point;
  86. Eigen::Vector3d plane_unit_norm;
  87. Eigen::Quaterniond qlb;
  88. Eigen::Vector3d tlb;
  89. double negative_OA_dot_norm, score;
  90. };
  91. struct LidarPlaneNormIncreFactor {
  92. LidarPlaneNormIncreFactor(Eigen::Vector3d curr_point_,
  93. Eigen::Vector3d plane_unit_norm_,
  94. double negative_OA_dot_norm_): curr_point(curr_point_),
  95. plane_unit_norm(plane_unit_norm_),
  96. negative_OA_dot_norm(negative_OA_dot_norm_) {}
  97. template <typename T> bool operator()(const T *q, const T *t, T *residual) const {
  98. Eigen::Quaternion<T> q_inc{q[0], q[1], q[2], q[3]};
  99. Eigen::Matrix<T, 3, 1> t_inc{t[0], t[1], t[2]};
  100. Eigen::Matrix<T, 3, 1> cp{T(curr_point.x()), T(curr_point.y()), T(curr_point.z())};
  101. Eigen::Matrix<T, 3, 1> point_w;
  102. point_w = q_inc * cp + t_inc;
  103. Eigen::Matrix<T, 3, 1> norm(T(plane_unit_norm.x()), T(plane_unit_norm.y()), T(plane_unit_norm.z()));
  104. residual[0] = norm.dot(point_w) + T(negative_OA_dot_norm);
  105. return true;
  106. }
  107. static ceres::CostFunction *Create(const Eigen::Vector3d curr_point_,
  108. const Eigen::Vector3d plane_unit_norm_,
  109. const double negative_OA_dot_norm_) {
  110. return (new ceres::AutoDiffCostFunction<LidarPlaneNormIncreFactor, 1, 4, 3>(new LidarPlaneNormIncreFactor(curr_point_, plane_unit_norm_, negative_OA_dot_norm_)));
  111. }
  112. Eigen::Vector3d curr_point;
  113. Eigen::Vector3d plane_unit_norm;
  114. double negative_OA_dot_norm;
  115. };
  116. #endif // LIDARFACTOR_H