Preintegration.h 9.8 KB

123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384858687888990919293949596979899100101102103104105106107108109110111112113114115116117118119120121122123124125126127128129130131132133134135136137138139140141142143144145146147148149150151152153154155156157158159160161162163164165166167168169170171172173174175176177178179180181182183184185186187188189190191192193194195196197198199200201202203204205206207208209210211212213214215216217218219220221222223224225226227228229230231232233234235236237238239240241
  1. #ifndef PREINTEGRATION_H_
  2. #define PREINTEGRATION_H_
  3. #include <Eigen/Eigen>
  4. #include "utils/math_tools.h"
  5. using Eigen::Vector3d;
  6. using Eigen::Matrix;
  7. using Eigen::Matrix3d;
  8. using Eigen::MatrixXd;
  9. using Eigen::Quaterniond;
  10. enum StateOrder {
  11. O_P = 0,
  12. O_R = 3,
  13. O_V = 6,
  14. O_BA = 9,
  15. O_BG = 12,
  16. };
  17. class Preintegration {
  18. public:
  19. EIGEN_MAKE_ALIGNED_OPERATOR_NEW
  20. Preintegration() = delete;
  21. Preintegration(const Vector3d &acc0, const Vector3d &gyr0,
  22. const Vector3d &linearized_ba, const Vector3d &linearized_bg)
  23. : acc0_{acc0},
  24. gyr0_{gyr0},
  25. linearized_acc_{acc0},
  26. linearized_gyr_{gyr0},
  27. linearized_ba_{linearized_ba},
  28. linearized_bg_{linearized_bg},
  29. jacobian_{Matrix<double, 15, 15>::Identity()},
  30. sum_dt_{0.0},
  31. delta_p_{Vector3d::Zero()},
  32. delta_q_{Quaterniond::Identity()},
  33. delta_v_{Vector3d::Zero()} {
  34. acc_n = 0.00059;
  35. gyr_n = 0.000061;
  36. acc_w = 0.000011;
  37. gyr_w = 0.000001;
  38. covariance_ = 0.0001 * Matrix<double, 15, 15>::Identity();
  39. g_vec_ = -Eigen::Vector3d(0, 0, 9.805);
  40. noise_ = Matrix<double, 18, 18>::Zero();
  41. noise_.block<3, 3>(0, 0) = (acc_n * acc_n) * Matrix3d::Identity();
  42. noise_.block<3, 3>(3, 3) = (gyr_n * gyr_n) * Matrix3d::Identity();
  43. noise_.block<3, 3>(6, 6) = (acc_n * acc_n) * Matrix3d::Identity();
  44. noise_.block<3, 3>(9, 9) = (gyr_n * gyr_n) * Matrix3d::Identity();
  45. noise_.block<3, 3>(12, 12) = (acc_w * acc_w) * Matrix3d::Identity();
  46. noise_.block<3, 3>(15, 15) = (gyr_w * gyr_w) * Matrix3d::Identity();
  47. }
  48. void push_back(double dt, const Vector3d &acc, const Vector3d &gyr) {
  49. dt_buf_.push_back(dt);
  50. acc_buf_.push_back(acc);
  51. gyr_buf_.push_back(gyr);
  52. Propagate(dt, acc, gyr);
  53. }
  54. void Repropagate(const Vector3d &linearized_ba, const Vector3d &linearized_bg) {
  55. sum_dt_ = 0.0;
  56. acc0_ = linearized_acc_;
  57. gyr0_ = linearized_gyr_;
  58. delta_p_.setZero();
  59. delta_q_.setIdentity();
  60. delta_v_.setZero();
  61. linearized_ba_ = linearized_ba;
  62. linearized_bg_ = linearized_bg;
  63. jacobian_.setIdentity();
  64. covariance_.setZero();
  65. for (size_t i = 0; i < dt_buf_.size(); ++i)
  66. Propagate(dt_buf_[i], acc_buf_[i], gyr_buf_[i]);
  67. }
  68. void MidPointIntegration(double dt,
  69. const Vector3d &acc0, const Vector3d &gyr0,
  70. const Vector3d &acc1, const Vector3d &gyr1,
  71. const Vector3d &delta_p, const Quaterniond &delta_q,
  72. const Vector3d &delta_v, const Vector3d &linearized_ba,
  73. const Vector3d &linearized_bg, Vector3d &result_delta_p,
  74. Quaterniond &result_delta_q, Vector3d &result_delta_v,
  75. Vector3d &result_linearized_ba, Vector3d &result_linearized_bg,
  76. bool update_jacobian) {
  77. Vector3d un_acc_0 = delta_q * (acc0 - linearized_ba);
  78. Vector3d un_gyr = 0.5 * (gyr0 + gyr1) - linearized_bg;
  79. result_delta_q = delta_q * Quaterniond(1, un_gyr(0) * dt / 2, un_gyr(1) * dt / 2, un_gyr(2) * dt / 2);
  80. Vector3d un_acc_1 = result_delta_q * (acc1 - linearized_ba);
  81. Vector3d un_acc = 0.5 * (un_acc_0 + un_acc_1);
  82. result_delta_p = delta_p + delta_v * dt + 0.5 * un_acc * dt * dt;
  83. result_delta_v = delta_v + un_acc * dt;
  84. result_linearized_ba = linearized_ba;
  85. result_linearized_bg = linearized_bg;
  86. if (update_jacobian) {
  87. Vector3d w_x = 0.5 * (gyr0 + gyr1) - linearized_bg;
  88. Vector3d a_0_x = acc0 - linearized_ba;
  89. Vector3d a_1_x = acc1 - linearized_ba;
  90. Matrix3d R_w_x, R_a_0_x, R_a_1_x;
  91. R_w_x << 0, -w_x(2), w_x(1),
  92. w_x(2), 0, -w_x(0),
  93. -w_x(1), w_x(0), 0;
  94. R_a_0_x << 0, -a_0_x(2), a_0_x(1),
  95. a_0_x(2), 0, -a_0_x(0),
  96. -a_0_x(1), a_0_x(0), 0;
  97. R_a_1_x << 0, -a_1_x(2), a_1_x(1),
  98. a_1_x(2), 0, -a_1_x(0),
  99. -a_1_x(1), a_1_x(0), 0;
  100. MatrixXd F = MatrixXd::Zero(15, 15);
  101. F.block<3, 3>(0, 0) = Matrix3d::Identity();
  102. F.block<3, 3>(0, 3) = -0.25*delta_q.toRotationMatrix() * R_a_0_x * dt * dt +
  103. -0.25 * result_delta_q.toRotationMatrix() * R_a_1_x * (Matrix3d::Identity() - R_w_x * dt) * dt * dt;
  104. F.block<3, 3>(0, 6) = MatrixXd::Identity(3, 3) * dt;
  105. F.block<3, 3>(0, 9) = -0.25*(delta_q.toRotationMatrix() + result_delta_q.toRotationMatrix()) * dt * dt;
  106. F.block<3, 3>(0, 12) = -0.1667*result_delta_q.toRotationMatrix() * R_a_1_x * dt * dt * -dt;
  107. F.block<3, 3>(3, 3) = Matrix3d::Identity() - R_w_x * dt;
  108. F.block<3, 3>(3, 12) = -MatrixXd::Identity(3, 3) * dt;
  109. F.block<3, 3>(6, 3) = -0.5*delta_q.toRotationMatrix() * R_a_0_x * dt +
  110. -0.5 * result_delta_q.toRotationMatrix() * R_a_1_x * (Matrix3d::Identity() - R_w_x * dt) * dt;
  111. F.block<3, 3>(6, 6) = Matrix3d::Identity();
  112. F.block<3, 3>(6, 9) = -0.5*(delta_q.toRotationMatrix() + result_delta_q.toRotationMatrix()) * dt;
  113. F.block<3, 3>(6, 12) = -0.5*result_delta_q.toRotationMatrix() * R_a_1_x * dt * -dt;
  114. F.block<3, 3>(9, 9) = Matrix3d::Identity();
  115. F.block<3, 3>(12, 12) = Matrix3d::Identity();
  116. MatrixXd V = MatrixXd::Zero(15, 18);
  117. V.block<3, 3>(0, 0) = 0.5 * delta_q.toRotationMatrix() * dt * dt;
  118. V.block<3, 3>(0, 3) = -0.25*result_delta_q.toRotationMatrix() * R_a_1_x * dt * dt * 0.5 * dt;
  119. V.block<3, 3>(0, 6) = 0.5 * result_delta_q.toRotationMatrix() * dt * dt;
  120. V.block<3, 3>(0, 9) = V.block<3, 3>(0, 3);
  121. V.block<3, 3>(3, 3) = 0.5*MatrixXd::Identity(3, 3) * dt;
  122. V.block<3, 3>(3, 9) = 0.5*MatrixXd::Identity(3, 3) * dt;
  123. V.block<3, 3>(6, 0) = 0.5*delta_q.toRotationMatrix() * dt;
  124. V.block<3, 3>(6, 3) = 0.5*-result_delta_q.toRotationMatrix() * R_a_1_x * dt * 0.5 * dt;
  125. V.block<3, 3>(6, 6) = 0.5*result_delta_q.toRotationMatrix() * dt;
  126. V.block<3, 3>(6, 9) = V.block<3, 3>(6, 3);
  127. V.block<3, 3>(9, 12) = MatrixXd::Identity(3, 3) * dt;
  128. V.block<3, 3>(12, 15) = MatrixXd::Identity(3, 3) * dt;
  129. jacobian_ = F * jacobian_;
  130. covariance_ = F * covariance_ * F.transpose() + V * noise_ * V.transpose();
  131. }
  132. }
  133. void Propagate(double dt, const Vector3d &acc1, const Vector3d &gyr1) {
  134. dt_ = dt;
  135. acc1_ = acc1;
  136. gyr1_ = gyr1;
  137. Vector3d result_delta_p;
  138. Quaterniond result_delta_q;
  139. Vector3d result_delta_v;
  140. Vector3d result_linearized_ba;
  141. Vector3d result_linearized_bg;
  142. MidPointIntegration(dt, acc0_, gyr0_, acc1, gyr1, delta_p_, delta_q_, delta_v_,
  143. linearized_ba_, linearized_bg_,
  144. result_delta_p, result_delta_q, result_delta_v,
  145. result_linearized_ba, result_linearized_bg, true);
  146. delta_p_ = result_delta_p;
  147. delta_q_ = result_delta_q;
  148. delta_v_ = result_delta_v;
  149. linearized_ba_ = result_linearized_ba;
  150. linearized_bg_ = result_linearized_bg;
  151. delta_q_.normalize();
  152. sum_dt_ += dt_;
  153. acc0_ = acc1_;
  154. gyr0_ = gyr1_;
  155. }
  156. Matrix<double, 15, 1> evaluate(const Vector3d &Pi,
  157. const Quaterniond &Qi,
  158. const Vector3d &Vi,
  159. const Vector3d &Bai,
  160. const Vector3d &Bgi,
  161. const Vector3d &Pj,
  162. const Quaterniond &Qj,
  163. const Vector3d &Vj,
  164. const Vector3d &Baj,
  165. const Vector3d &Bgj) {
  166. Matrix<double, 15, 1> residuals;
  167. residuals.setZero();
  168. Matrix3d dp_dba = jacobian_.block<3, 3>(O_P, O_BA);
  169. Matrix3d dp_dbg = jacobian_.block<3, 3>(O_P, O_BG);
  170. Matrix3d dq_dbg = jacobian_.block<3, 3>(O_R, O_BG);
  171. Matrix3d dv_dba = jacobian_.block<3, 3>(O_V, O_BA);
  172. Matrix3d dv_dbg = jacobian_.block<3, 3>(O_V, O_BG);
  173. Vector3d dba = Bai - linearized_ba_;
  174. Vector3d dbg = Bgi - linearized_bg_; // NOTE: optimized one minus the linearized one
  175. Quaterniond corrected_delta_q = delta_q_ * deltaQ(dq_dbg * dbg);
  176. Vector3d corrected_delta_v = delta_v_ + dv_dba * dba + dv_dbg * dbg;
  177. Vector3d corrected_delta_p = delta_p_ + dp_dba * dba + dp_dbg * dbg;
  178. residuals.block<3, 1>(O_P, 0) = Qi.inverse() * (-0.5 * g_vec_ * sum_dt_ * sum_dt_ + Pj - Pi - Vi * sum_dt_) - corrected_delta_p;
  179. residuals.block<3, 1>(O_R, 0) = 2.0 * (corrected_delta_q.inverse() * (Qi.inverse() * Qj)).normalized().vec();
  180. residuals.block<3, 1>(O_V, 0) = Qi.inverse() * (-g_vec_ * sum_dt_ + Vj - Vi) - corrected_delta_v;
  181. residuals.block<3, 1>(O_BA, 0) = Baj - Bai;
  182. residuals.block<3, 1>(O_BG, 0) = Bgj - Bgi;
  183. return residuals;
  184. }
  185. double dt_;
  186. Vector3d acc0_, gyr0_;
  187. Vector3d acc1_, gyr1_;
  188. const Vector3d linearized_acc_, linearized_gyr_;
  189. Vector3d linearized_ba_, linearized_bg_;
  190. Matrix<double, 15, 15> jacobian_, covariance_;
  191. Matrix<double, 18, 18> noise_;
  192. double sum_dt_;
  193. Vector3d delta_p_;
  194. Quaterniond delta_q_;
  195. Vector3d delta_v_;
  196. std::vector<double> dt_buf_;
  197. std::vector<Vector3d> acc_buf_;
  198. std::vector<Vector3d> gyr_buf_;
  199. Eigen::Vector3d g_vec_;
  200. double nf, cf;
  201. double acc_n;
  202. double gyr_n;
  203. double acc_w;
  204. double gyr_w;
  205. ros::NodeHandle nh;
  206. };
  207. #endif //PREINTEGRATION_H_