pose_cost_function.cpp 5.8 KB

123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384858687888990919293949596979899100101102103104105106107108109110111112113114115116117118119120121122123124125126127128129130131132133134135136137138139140141142143144145146147148149150151152153154155156157158159160161162163
  1. #include <pose_graph/pose_cost_function.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 PoseLocalParameterization::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::Quaterniond> _q(x + 3);
  30. Eigen::Map<const Eigen::Vector3d> dp(delta);
  31. Eigen::Quaterniond dq = deltaQ(Eigen::Map<const Eigen::Vector3d>(delta + 3));
  32. Eigen::Map<Eigen::Vector3d> p(x_plus_delta);
  33. Eigen::Map<Eigen::Quaterniond> q(x_plus_delta + 3);
  34. p = _p + dp;
  35. q = (_q * dq).normalized();
  36. return true;
  37. }
  38. bool PoseLocalParameterization::ComputeJacobian(const double *x, double *jacobian) const
  39. {
  40. Eigen::Map<Eigen::Matrix<double, 7, 6, Eigen::RowMajor>> j(jacobian);
  41. j.topRows<6>().setIdentity();
  42. j.bottomRows<1>().setZero();
  43. return true;
  44. }
  45. PoseCostFunction::PoseCostFunction()
  46. {
  47. }
  48. bool PoseCostFunction::Evaluate(double const *const *parameters, double *residuals, double **jacobians) const
  49. {
  50. Eigen::Vector3d T1(parameters[0][0], parameters[0][1], parameters[0][2]);
  51. Eigen::Quaterniond Q1(parameters[0][6], parameters[0][3], parameters[0][4], parameters[0][5]);
  52. Eigen::Vector3d T2(parameters[1][0], parameters[1][1], parameters[1][2]);
  53. Eigen::Quaterniond Q2(parameters[1][6], parameters[1][3], parameters[1][4], parameters[1][5]);
  54. Eigen::Vector3d T12(parameters[2][0], parameters[2][1], parameters[2][2]);
  55. Eigen::Quaterniond Q12(parameters[2][6], parameters[2][3], parameters[2][4], parameters[2][5]);
  56. Eigen::Map<Eigen::Vector3d> residual(residuals);
  57. Eigen::Matrix3d R1 = Q1.toRotationMatrix();
  58. Eigen::Matrix3d R2 = Q2.toRotationMatrix();
  59. Eigen::Matrix3d R12 = Q12.toRotationMatrix();
  60. // residual = -R1 * R12 * R2.inverse() * T2 + R1 * T12 + T1;
  61. // LOG(INFO)<<"residual: \r\n"<<residual;
  62. // if (jacobians) {
  63. // // 对R1和T1求导
  64. // if (jacobians[0]) {
  65. // Eigen::Map<Eigen::Matrix<double, 3, 7, Eigen::RowMajor>> jacobian(jacobians[0]);
  66. // Eigen::Matrix<double, 3, 6> jaco;
  67. // jaco.leftCols<3>().setIdentity();
  68. // jaco.rightCols<3>() = R1 * skewSymmetric(R12 * R2.inverse() * T2) - R1 * skewSymmetric(T12);
  69. // jacobian.leftCols<6>() = jaco;
  70. // jacobian.rightCols<1>().setZero();
  71. // }
  72. // // 对R2和T2求导
  73. // if (jacobians[1]) {
  74. // Eigen::Map<Eigen::Matrix<double, 3, 7, Eigen::RowMajor>> jacobian(jacobians[1]);
  75. // Eigen::Matrix<double, 3, 6> jaco;
  76. // jaco.leftCols<3>() = -R1 * R12 * R2.inverse();
  77. // jaco.rightCols<3>() = -R1 * R12 * skewSymmetric(R2.inverse() * T2);
  78. // jacobian.leftCols<6>() = jaco;
  79. // jacobian.rightCols<1>().setZero();
  80. // }
  81. // // 对R12和T12求导
  82. // if (jacobians[2]) {
  83. // Eigen::Map<Eigen::Matrix<double, 3, 7, Eigen::RowMajor>> jacobian(jacobians[2]);
  84. // Eigen::Matrix<double, 3, 6> jaco;
  85. // jaco.leftCols<3>() = R1;
  86. // jaco.rightCols<3>() = R1 * R12 * skewSymmetric(R2.inverse() * T2);
  87. // jacobian.leftCols<6>() = jaco;
  88. // jacobian.rightCols<1>().setZero();
  89. // }
  90. // }
  91. Eigen::Vector3d p(1, 1, 1);
  92. residual = R2.inverse() * R1 * R12 * p + R2.inverse() * R1 * T12 + R2.inverse() * T1 - R2.inverse() * T2 - p;
  93. // LOG(INFO)<<"residual: \r\n"<<residual;
  94. if (jacobians) {
  95. // 对R1和T1求导
  96. if (jacobians[0]) {
  97. Eigen::Map<Eigen::Matrix<double, 3, 7, Eigen::RowMajor>> jacobian(jacobians[0]);
  98. Eigen::Matrix<double, 3, 6> jaco;
  99. jaco.leftCols<3>() = R2.inverse();
  100. jaco.rightCols<3>() = -R2.inverse() * R1 * skewSymmetric(R12 * p) - R2.inverse() * R1 * skewSymmetric(T12);
  101. // R1 * skewSymmetric(R12 * R2.inverse() * T2) - R1 * skewSymmetric(T12);
  102. jacobian.leftCols<6>() = jaco;
  103. jacobian.rightCols<1>().setZero();
  104. }
  105. // 对R2和T2求导
  106. if (jacobians[1]) {
  107. Eigen::Map<Eigen::Matrix<double, 3, 7, Eigen::RowMajor>> jacobian(jacobians[1]);
  108. Eigen::Matrix<double, 3, 6> jaco;
  109. jaco.leftCols<3>() = -R2.inverse();
  110. jaco.rightCols<3>() = skewSymmetric(R2.inverse() * R1 * R12 * p) +
  111. skewSymmetric(R2.inverse() * R1 * T12) + skewSymmetric(R2.inverse() * T1) - skewSymmetric(R2.inverse() * T2);
  112. jacobian.leftCols<6>() = jaco;
  113. jacobian.rightCols<1>().setZero();
  114. }
  115. // 对R12和T12求导
  116. if (jacobians[2]) {
  117. Eigen::Map<Eigen::Matrix<double, 3, 7, Eigen::RowMajor>> jacobian(jacobians[2]);
  118. Eigen::Matrix<double, 3, 6> jaco;
  119. jaco.leftCols<3>() = R2.inverse() * R1;
  120. jaco.rightCols<3>() = -R2.inverse() * R1 * R12 * skewSymmetric(p);
  121. jacobian.leftCols<6>() = jaco;
  122. jacobian.rightCols<1>().setZero();
  123. }
  124. }
  125. return true;
  126. }
  127. }
  128. }