LidarPoseFactor.h 5.2 KB

123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384858687888990919293949596979899100101102103104105106107108109110111112113114115116117118119120121122123124125126127128129130131132133134135136137138139140141142143144145146147148149150
  1. #pragma once
  2. #include <ros/assert.h>
  3. #include <iostream>
  4. #include <eigen3/Eigen/Dense>
  5. #include "utils/math_tools.h"
  6. #include <ceres/ceres.h>
  7. struct LidarPoseFactorAutoDiff
  8. {
  9. public:
  10. EIGEN_MAKE_ALIGNED_OPERATOR_NEW
  11. LidarPoseFactorAutoDiff(Eigen::Quaterniond delta_q_, Eigen::Vector3d delta_p_): delta_q(delta_q_), delta_p(delta_p_)
  12. {}
  13. template <typename T>
  14. bool operator()(const T *p1, const T *p2, const T *p3, const T *p4, T *residuals) const
  15. {
  16. Eigen::Matrix<T, 3, 1> P1(p1[0], p1[1], p1[2]);
  17. Eigen::Quaternion<T> Q1(p2[0], p2[1], p2[2], p2[3]);
  18. Eigen::Matrix<T, 3, 1> P2(p3[0], p3[1], p3[2]);
  19. Eigen::Quaternion<T> Q2(p4[0], p4[1], p4[2], p4[3]);
  20. Eigen::Quaternion<T> tmp_delta_q(T(delta_q.w()), T(delta_q.x()), T(delta_q.y()), T(delta_q.z()));
  21. Eigen::Matrix<T, 3, 1> tmp_delta_p(T(delta_p.x()), T(delta_p.y()), T(delta_p.z()));
  22. Eigen::Matrix<T, 3, 1> residual1 = T(2.0) * (tmp_delta_q.inverse() * Q1.inverse() * Q2).vec();
  23. Eigen::Matrix<T, 3, 1> residual2 = Q1.inverse() * (P2 - P1) - tmp_delta_p;
  24. residuals[0] = T(0.2) * residual1[0];
  25. residuals[1] = T(0.2) * residual1[1];
  26. residuals[2] = T(0.2) * residual1[2];
  27. residuals[3] = T(0.2) * residual2[0];
  28. residuals[4] = T(0.2) * residual2[1];
  29. residuals[5] = T(0.2) * residual2[2];
  30. return true;
  31. }
  32. static ceres::CostFunction *Create(Eigen::Quaterniond delta_q_, Eigen::Vector3d delta_p_)
  33. {
  34. return (new ceres::AutoDiffCostFunction<LidarPoseFactorAutoDiff, 6, 3, 4, 3, 4>(
  35. new LidarPoseFactorAutoDiff(delta_q_, delta_p_)));
  36. }
  37. private:
  38. Eigen::Quaterniond delta_q;
  39. Eigen::Vector3d delta_p;
  40. };
  41. struct LidarPoseLeftFactorAutoDiff
  42. {
  43. public:
  44. EIGEN_MAKE_ALIGNED_OPERATOR_NEW
  45. LidarPoseLeftFactorAutoDiff(Eigen::Quaterniond delta_q_, Eigen::Vector3d delta_p_, Eigen::Quaterniond ql_, Eigen::Vector3d pl_): delta_q(delta_q_), delta_p(delta_p_), ql(ql_), pl(pl_)
  46. {}
  47. template <typename T>
  48. bool operator()(const T *p1, const T *p2, T *residuals) const
  49. {
  50. Eigen::Matrix<T, 3, 1> P1(T(pl.x()), T(pl.y()), T(pl.z()));
  51. Eigen::Quaternion<T> Q1(T(ql.w()), T(ql.x()), T(ql.y()), T(ql.z()));
  52. Eigen::Matrix<T, 3, 1> P2(p1[0], p1[1], p1[2]);
  53. Eigen::Quaternion<T> Q2(p2[0], p2[1], p2[2], p2[3]);
  54. Eigen::Quaternion<T> tmp_delta_q(T(delta_q.w()), T(delta_q.x()), T(delta_q.y()), T(delta_q.z()));
  55. Eigen::Matrix<T, 3, 1> tmp_delta_p(T(delta_p.x()), T(delta_p.y()), T(delta_p.z()));
  56. Eigen::Matrix<T, 3, 1> residual1 = T(2.0) * (tmp_delta_q.inverse() * Q1.inverse() * Q2).vec();
  57. Eigen::Matrix<T, 3, 1> residual2 = Q1.inverse() * (P2 - P1) - tmp_delta_p;
  58. residuals[0] = T(0.2) * residual1[0];
  59. residuals[1] = T(0.2) * residual1[1];
  60. residuals[2] = T(0.2) * residual1[2];
  61. residuals[3] = T(0.2) * residual2[0];
  62. residuals[4] = T(0.2) * residual2[1];
  63. residuals[5] = T(0.2) * residual2[2];
  64. return true;
  65. }
  66. static ceres::CostFunction *Create(Eigen::Quaterniond delta_q_, Eigen::Vector3d delta_p_, Eigen::Quaterniond ql_, Eigen::Vector3d pl_)
  67. {
  68. return (new ceres::AutoDiffCostFunction<LidarPoseLeftFactorAutoDiff, 6, 3, 4>(
  69. new LidarPoseLeftFactorAutoDiff(delta_q_, delta_p_, ql_, pl_)));
  70. }
  71. private:
  72. Eigen::Quaterniond delta_q;
  73. Eigen::Vector3d delta_p;
  74. Eigen::Quaterniond ql;
  75. Eigen::Vector3d pl;
  76. };
  77. struct LidarPoseRightFactorAutoDiff
  78. {
  79. public:
  80. EIGEN_MAKE_ALIGNED_OPERATOR_NEW
  81. LidarPoseRightFactorAutoDiff(Eigen::Quaterniond delta_q_, Eigen::Vector3d delta_p_, Eigen::Quaterniond qr_, Eigen::Vector3d pr_): delta_q(delta_q_), delta_p(delta_p_), qr(qr_), pr(pr_)
  82. {}
  83. template <typename T>
  84. bool operator()(const T *p1, const T *p2, T *residuals) const
  85. {
  86. Eigen::Matrix<T, 3, 1> P2(T(pr.x()), T(pr.y()), T(pr.z()));
  87. Eigen::Quaternion<T> Q2(T(qr.w()), T(qr.x()), T(qr.y()), T(qr.z()));
  88. Eigen::Matrix<T, 3, 1> P1(p1[0], p1[1], p1[2]);
  89. Eigen::Quaternion<T> Q1(p2[0], p2[1], p2[2], p2[3]);
  90. Eigen::Quaternion<T> tmp_delta_q(T(delta_q.w()), T(delta_q.x()), T(delta_q.y()), T(delta_q.z()));
  91. Eigen::Matrix<T, 3, 1> tmp_delta_p(T(delta_p.x()), T(delta_p.y()), T(delta_p.z()));
  92. Eigen::Matrix<T, 3, 1> residual1 = T(2.0) * (tmp_delta_q.inverse() * Q1.inverse() * Q2).vec();
  93. Eigen::Matrix<T, 3, 1> residual2 = Q1.inverse() * (P2 - P1) - tmp_delta_p;
  94. residuals[0] = T(0.2) * residual1[0];
  95. residuals[1] = T(0.2) * residual1[1];
  96. residuals[2] = T(0.2) * residual1[2];
  97. residuals[3] = T(0.2) * residual2[0];
  98. residuals[4] = T(0.2) * residual2[1];
  99. residuals[5] = T(0.2) * residual2[2];
  100. return true;
  101. }
  102. static ceres::CostFunction *Create(Eigen::Quaterniond delta_q_, Eigen::Vector3d delta_p_, Eigen::Quaterniond qr_, Eigen::Vector3d pr_)
  103. {
  104. return (new ceres::AutoDiffCostFunction<LidarPoseRightFactorAutoDiff, 6, 3, 4>(
  105. new LidarPoseRightFactorAutoDiff(delta_q_, delta_p_, qr_, pr_)));
  106. }
  107. private:
  108. Eigen::Quaterniond delta_q;
  109. Eigen::Vector3d delta_p;
  110. Eigen::Quaterniond qr;
  111. Eigen::Vector3d pr;
  112. };