pose_graph.cpp 4.6 KB

123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384858687888990919293949596979899100101102103104105106107108109110111112113114115116117118119120121122123124125126127128129130131132133134135136137138139140141142143144145146147148
  1. #include <pose_graph/pose_graph.h>
  2. namespace hlzn_slam {
  3. namespace pose_graph {
  4. template <typename Derived>
  5. static Eigen::Matrix<typename Derived::Scalar, 3, 3> skewSymmetric(const Eigen::MatrixBase<Derived> &q)
  6. {
  7. Eigen::Matrix<typename Derived::Scalar, 3, 3> ans;
  8. ans << typename Derived::Scalar(0), -q(2), q(1),
  9. q(2), typename Derived::Scalar(0), -q(0),
  10. -q(1), q(0), typename Derived::Scalar(0);
  11. return ans;
  12. }
  13. template <typename Derived>
  14. static Eigen::Quaternion<typename Derived::Scalar> deltaQ(const Eigen::MatrixBase<Derived> &theta)
  15. {
  16. typedef typename Derived::Scalar Scalar_t;
  17. Eigen::Quaternion<Scalar_t> dq;
  18. Eigen::Matrix<Scalar_t, 3, 1> half_theta = theta;
  19. half_theta /= static_cast<Scalar_t>(2.0);
  20. dq.w() = static_cast<Scalar_t>(1.0);
  21. dq.x() = 0; // half_theta.x();
  22. dq.y() = 0; // half_theta.y();
  23. dq.z() = half_theta.z();
  24. return dq;
  25. }
  26. bool TranslationLocalParameterization::Plus(const double *x, const double *delta, double *x_plus_delta) const
  27. {
  28. Eigen::Map<const Eigen::Vector3d> _p(x);
  29. Eigen::Map<const Eigen::Vector3d> dp(delta);
  30. Eigen::Map<Eigen::Vector3d> p(x_plus_delta);
  31. p = _p + dp;
  32. return true;
  33. }
  34. bool TranslationLocalParameterization::ComputeJacobian(const double *x, double *jacobian) const
  35. {
  36. Eigen::Map<Eigen::Matrix<double, 3, 3, Eigen::RowMajor>> j(jacobian);
  37. j.setIdentity();
  38. return true;
  39. }
  40. bool QuaternionLocalParameterization::Plus(const double *x, const double *delta, double *x_plus_delta) const
  41. {
  42. Eigen::Map<const Eigen::Quaterniond> _q(x);
  43. Eigen::Quaterniond dq = deltaQ(Eigen::Map<const Eigen::Vector3d>(delta));
  44. Eigen::Map<Eigen::Quaterniond> q(x_plus_delta);
  45. q = (_q * dq).normalized();
  46. return true;
  47. }
  48. bool QuaternionLocalParameterization::ComputeJacobian(const double *x, double *jacobian) const
  49. {
  50. Eigen::Map<Eigen::Matrix<double, 3, 4, Eigen::RowMajor>> j(jacobian);
  51. j.topRows<3>().setIdentity();
  52. j.bottomRows<1>().setZero();
  53. return true;
  54. }
  55. PoseGraphFunction::PoseGraphFunction()
  56. {}
  57. bool PoseGraphFunction::Evaluate(double const *const *parameters, double *residuals, double **jacobians) const
  58. {
  59. Eigen::Vector3d T1(parameters[0][0], parameters[0][1], parameters[0][2]);
  60. Eigen::Quaterniond Q1(parameters[1][3], parameters[1][0], parameters[1][1], parameters[1][2]);
  61. Eigen::Vector3d T2(parameters[2][0], parameters[2][1], parameters[2][2]);
  62. Eigen::Quaterniond Q2(parameters[3][3], parameters[3][0], parameters[3][1], parameters[3][2]);
  63. Eigen::Vector3d T12(parameters[4][0], parameters[4][1], parameters[4][2]);
  64. Eigen::Quaterniond Q12(parameters[5][3], parameters[5][0], parameters[5][1], parameters[5][2]);
  65. Eigen::Map<Eigen::Vector3d> residual(residuals);
  66. Eigen::Matrix3d R1 = Q1.toRotationMatrix();
  67. Eigen::Matrix3d R2 = Q2.toRotationMatrix();
  68. Eigen::Matrix3d R12 = Q12.toRotationMatrix();
  69. residual = -R12 * R1.inverse() * T1 + R2 * T12 + T2;
  70. if (jacobians) {
  71. // 对T1求导
  72. if (jacobians[0]) {
  73. Eigen::Map<Eigen::Matrix<double, 3, 3, Eigen::RowMajor>> jacobian(jacobians[0]);
  74. jacobian = -R12 * R1.inverse();
  75. }
  76. // 对R1求导
  77. if (jacobians[1]) {
  78. Eigen::Map<Eigen::Matrix<double, 3, 4, Eigen::RowMajor>> jacobian(jacobians[1]);
  79. Eigen::Matrix<double, 3, 4> jaco;
  80. jaco.leftCols<3>() = -R12 * skewSymmetric(R1.inverse() * T1);
  81. jaco.rightCols<1>().setZero();
  82. jacobian = jaco;
  83. }
  84. // 对T2求导
  85. if (jacobians[2]) {
  86. Eigen::Map<Eigen::Matrix<double, 3, 3, Eigen::RowMajor>> jacobian(jacobians[2]);
  87. jacobian.setIdentity();
  88. }
  89. // 对R2求导
  90. if (jacobians[3]) {
  91. Eigen::Map<Eigen::Matrix<double, 3, 4, Eigen::RowMajor>> jacobian(jacobians[3]);
  92. Eigen::Matrix<double, 3, 4> jaco;
  93. jaco.leftCols<3>() = -R2 * skewSymmetric(T12);
  94. jaco.rightCols<1>().setZero();
  95. jacobian = jaco;
  96. }
  97. // 对T12求导
  98. if (jacobians[4]) {
  99. Eigen::Map<Eigen::Matrix<double, 3, 3, Eigen::RowMajor>> jacobian(jacobians[4]);
  100. jacobian = R2;
  101. }
  102. // 对R12求导
  103. if (jacobians[5]) {
  104. Eigen::Map<Eigen::Matrix<double, 3, 4, Eigen::RowMajor>> jacobian(jacobians[5]);
  105. Eigen::Matrix<double, 3, 4> jaco;
  106. jaco.leftCols<3>() = R12 * skewSymmetric(R1.inverse() * T1);;
  107. jaco.rightCols<1>().setZero();
  108. jacobian = jaco;
  109. }
  110. }
  111. return true;
  112. }
  113. }
  114. }