LidarPoseFactor.h 5.0 KB

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