33 void Propagator::propagate_and_clone(std::shared_ptr<State> state,
double timestamp) {
37 if (state->_timestamp == timestamp) {
38 PRINT_ERROR(
RED "Propagator::propagate_and_clone(): Propagation called again at same timestep at last update timestep!!!!\n" RESET);
39 std::exit(EXIT_FAILURE);
43 if (state->_timestamp > timestamp) {
44 PRINT_ERROR(
RED "Propagator::propagate_and_clone(): Propagation called trying to propagate backwards in time!!!!\n" RESET);
45 PRINT_ERROR(
RED "Propagator::propagate_and_clone(): desired propagation = %.4f\n" RESET, (timestamp - state->_timestamp));
46 std::exit(EXIT_FAILURE);
54 if (!have_last_prop_time_offset) {
55 last_prop_time_offset = state->_calib_dt_CAMtoIMU->value()(0);
56 have_last_prop_time_offset =
true;
60 double t_off_new = state->_calib_dt_CAMtoIMU->value()(0);
63 double time0 = state->_timestamp + last_prop_time_offset;
64 double time1 = timestamp + t_off_new;
65 std::vector<ov_core::ImuData> prop_data;
67 std::lock_guard<std::mutex> lck(imu_data_mtx);
68 prop_data = Propagator::select_imu_readings(imu_data, time0, time1);
76 Eigen::MatrixXd Phi_summed = Eigen::MatrixXd::Identity(state->imu_intrinsic_size() + 15, state->imu_intrinsic_size() + 15);
77 Eigen::MatrixXd Qd_summed = Eigen::MatrixXd::Zero(state->imu_intrinsic_size() + 15, state->imu_intrinsic_size() + 15);
82 if (prop_data.size() > 1) {
83 for (
size_t i = 0; i < prop_data.size() - 1; i++) {
86 Eigen::MatrixXd F, Qdi;
87 predict_and_compute(state, prop_data.at(i), prop_data.at(i + 1), F, Qdi);
95 Phi_summed = F * Phi_summed;
96 Qd_summed = F * Qd_summed * F.transpose() + Qdi;
97 Qd_summed = 0.5 * (Qd_summed + Qd_summed.transpose());
98 dt_summed += prop_data.at(i + 1).timestamp - prop_data.at(i).timestamp;
101 assert(std::abs((time1 - time0) - dt_summed) < 1e-4);
105 Eigen::Vector3d last_a = Eigen::Vector3d::Zero();
106 Eigen::Vector3d last_w = Eigen::Vector3d::Zero();
107 if (!prop_data.empty()) {
108 Eigen::Matrix3d Dw = State::Dm(state->_options.imu_model, state->_calib_imu_dw->value());
109 Eigen::Matrix3d Da = State::Dm(state->_options.imu_model, state->_calib_imu_da->value());
110 Eigen::Matrix3d Tg = State::Tg(state->_calib_imu_tg->value());
111 last_a = state->_calib_imu_ACCtoIMU->Rot() * Da * (prop_data.at(prop_data.size() - 1).am - state->_imu->bias_a());
112 last_w = state->_calib_imu_GYROtoIMU->Rot() * Dw * (prop_data.at(prop_data.size() - 1).wm - state->_imu->bias_g() - Tg * last_a);
116 std::vector<std::shared_ptr<Type>> Phi_order;
117 Phi_order.push_back(state->_imu);
118 if (state->_options.do_calib_imu_intrinsics) {
119 Phi_order.push_back(state->_calib_imu_dw);
120 Phi_order.push_back(state->_calib_imu_da);
121 if (state->_options.do_calib_imu_g_sensitivity) {
122 Phi_order.push_back(state->_calib_imu_tg);
124 if (state->_options.imu_model == StateOptions::ImuModel::KALIBR) {
125 Phi_order.push_back(state->_calib_imu_GYROtoIMU);
127 Phi_order.push_back(state->_calib_imu_ACCtoIMU);
130 StateHelper::EKFPropagation(state, Phi_order, Phi_order, Phi_summed, Qd_summed);
133 state->_timestamp = timestamp;
134 last_prop_time_offset = t_off_new;
137 StateHelper::augment_clone(state, last_w);
140 bool Propagator::fast_state_propagate(std::shared_ptr<State> state,
double timestamp, Eigen::Matrix<double, 13, 1> &state_plus,
141 Eigen::Matrix<double, 12, 12> &covariance) {
144 if (!cache_imu_valid) {
145 cache_state_time = state->_timestamp;
146 cache_state_est = state->_imu->value();
147 cache_state_covariance = StateHelper::get_marginal_covariance(state, {state->_imu});
148 cache_t_off = state->_calib_dt_CAMtoIMU->value()(0);
149 cache_imu_valid =
true;
153 double time0 = cache_state_time + cache_t_off;
154 double time1 = timestamp + cache_t_off;
155 std::vector<ov_core::ImuData> prop_data;
157 std::lock_guard<std::mutex> lck(imu_data_mtx);
158 prop_data = Propagator::select_imu_readings(imu_data, time0, time1,
false);
160 if (prop_data.size() < 2)
164 Eigen::Vector3d bias_g = cache_state_est.block(10, 0, 3, 1);
165 Eigen::Vector3d bias_a = cache_state_est.block(13, 0, 3, 1);
168 Eigen::Matrix3d Dw = State::Dm(state->_options.imu_model, state->_calib_imu_dw->value());
169 Eigen::Matrix3d Da = State::Dm(state->_options.imu_model, state->_calib_imu_da->value());
170 Eigen::Matrix3d Tg = State::Tg(state->_calib_imu_tg->value());
171 Eigen::Matrix3d R_ACCtoIMU = state->_calib_imu_ACCtoIMU->Rot();
172 Eigen::Matrix3d R_GYROtoIMU = state->_calib_imu_GYROtoIMU->Rot();
176 for (
size_t i = 0; i < prop_data.size() - 1; i++) {
179 auto data_minus = prop_data.at(i);
180 auto data_plus = prop_data.at(i + 1);
181 double dt = data_plus.timestamp - data_minus.timestamp;
184 Eigen::Vector3d a_hat1 = R_ACCtoIMU * Da * (data_minus.am - bias_a);
185 Eigen::Vector3d a_hat2 = R_ACCtoIMU * Da * (data_plus.am - bias_a);
186 Eigen::Vector3d a_hat = 0.5 * (a_hat1 + a_hat2);
189 Eigen::Vector3d w_hat1 = R_GYROtoIMU * Dw * (data_minus.wm - bias_g - Tg * a_hat1);
190 Eigen::Vector3d w_hat2 = R_GYROtoIMU * Dw * (data_plus.wm - bias_g - Tg * a_hat2);
191 Eigen::Vector3d w_hat = 0.5 * (w_hat1 + w_hat2);
194 Eigen::Matrix3d R_Gtoi =
quat_2_Rot(cache_state_est.block(0, 0, 4, 1));
195 Eigen::Vector3d v_iinG = cache_state_est.block(7, 0, 3, 1);
196 Eigen::Vector3d p_iinG = cache_state_est.block(4, 0, 3, 1);
201 Eigen::Matrix<double, 15, 15> F = Eigen::Matrix<double, 15, 15>::Zero();
202 F.block(0, 0, 3, 3) =
exp_so3(-w_hat * dt);
203 F.block(0, 9, 3, 3).noalias() = -
exp_so3(-w_hat * dt) *
Jr_so3(-w_hat * dt) * dt;
204 F.block(9, 9, 3, 3).setIdentity();
205 F.block(6, 0, 3, 3).noalias() = -R_Gtoi.transpose() *
skew_x(a_hat * dt);
206 F.block(6, 6, 3, 3).setIdentity();
207 F.block(6, 12, 3, 3) = -R_Gtoi.transpose() * dt;
208 F.block(12, 12, 3, 3).setIdentity();
209 F.block(3, 0, 3, 3).noalias() = -0.5 * R_Gtoi.transpose() *
skew_x(a_hat * dt * dt);
210 F.block(3, 6, 3, 3) = Eigen::Matrix3d::Identity() * dt;
211 F.block(3, 12, 3, 3) = -0.5 * R_Gtoi.transpose() * dt * dt;
212 F.block(3, 3, 3, 3).setIdentity();
213 Eigen::Matrix<double, 15, 12> G = Eigen::Matrix<double, 15, 12>::Zero();
214 G.block(0, 0, 3, 3) = -
exp_so3(-w_hat * dt) *
Jr_so3(-w_hat * dt) * dt;
215 G.block(6, 3, 3, 3) = -R_Gtoi.transpose() * dt;
216 G.block(3, 3, 3, 3) = -0.5 * R_Gtoi.transpose() * dt * dt;
217 G.block(9, 6, 3, 3).setIdentity();
218 G.block(12, 9, 3, 3).setIdentity();
223 Eigen::Matrix<double, 15, 15> Qd = Eigen::Matrix<double, 15, 15>::Zero();
224 Eigen::Matrix<double, 12, 12> Qc = Eigen::Matrix<double, 12, 12>::Zero();
225 Qc.block(0, 0, 3, 3) = _noises.sigma_w_2 / dt * Eigen::Matrix3d::Identity();
226 Qc.block(3, 3, 3, 3) = _noises.sigma_a_2 / dt * Eigen::Matrix3d::Identity();
227 Qc.block(6, 6, 3, 3) = _noises.sigma_wb_2 * dt * Eigen::Matrix3d::Identity();
228 Qc.block(9, 9, 3, 3) = _noises.sigma_ab_2 * dt * Eigen::Matrix3d::Identity();
229 Qd = G * Qc * G.transpose();
230 Qd = 0.5 * (Qd + Qd.transpose());
231 cache_state_covariance = F * cache_state_covariance * F.transpose() + Qd;
235 cache_state_est.block(4, 0, 3, 1) = p_iinG + v_iinG * dt + 0.5 * R_Gtoi.transpose() * a_hat * dt * dt - 0.5 * _gravity * dt * dt;
236 cache_state_est.block(7, 0, 3, 1) = v_iinG + R_Gtoi.transpose() * a_hat * dt - _gravity * dt;
241 cache_state_time = time1;
245 Eigen::Vector4d q_Gtoi = cache_state_est.block(0, 0, 4, 1);
246 Eigen::Vector3d v_iinG = cache_state_est.block(7, 0, 3, 1);
247 Eigen::Vector3d p_iinG = cache_state_est.block(4, 0, 3, 1);
248 state_plus.setZero();
249 state_plus.block(0, 0, 4, 1) = q_Gtoi;
250 state_plus.block(4, 0, 3, 1) = p_iinG;
251 state_plus.block(7, 0, 3, 1) =
quat_2_Rot(q_Gtoi) * v_iinG;
252 Eigen::Vector3d last_a = R_ACCtoIMU * Da * (prop_data.at(prop_data.size() - 1).am - bias_a);
253 Eigen::Vector3d last_w = R_GYROtoIMU * Dw * (prop_data.at(prop_data.size() - 1).wm - bias_g - Tg * last_a);
254 state_plus.block(10, 0, 3, 1) = last_w;
259 covariance.setZero();
260 Eigen::Matrix<double, 15, 15> Phi = Eigen::Matrix<double, 15, 15>::Identity();
262 Eigen::MatrixXd covariance_tmp = Phi * cache_state_covariance * Phi.transpose();
263 covariance.block(0, 0, 9, 9) = covariance_tmp.block(0, 0, 9, 9);
264 double dt = prop_data.at(prop_data.size() - 1).timestamp - prop_data.at(prop_data.size() - 2).timestamp;
265 covariance.block(9, 9, 3, 3) = _noises.sigma_w_2 / dt * Eigen::Matrix3d::Identity();
269 std::vector<ov_core::ImuData> Propagator::select_imu_readings(
const std::vector<ov_core::ImuData> &imu_data,
double time0,
double time1,
273 std::vector<ov_core::ImuData> prop_data;
276 if (imu_data.empty()) {
278 PRINT_WARNING(
YELLOW "Propagator::select_imu_readings(): No IMU measurements. IMU-CAMERA are likely messed up!!!\n" RESET);
284 for (
size_t i = 0; i < imu_data.size() - 1; i++) {
290 if (imu_data.at(i + 1).timestamp > time0 && imu_data.at(i).timestamp < time0) {
291 ov_core::ImuData data = Propagator::interpolate_data(imu_data.at(i), imu_data.at(i + 1), time0);
292 prop_data.push_back(data);
301 if (imu_data.at(i).timestamp >= time0 && imu_data.at(i + 1).timestamp <= time1) {
302 prop_data.push_back(imu_data.at(i));
312 if (imu_data.at(i + 1).timestamp > time1) {
317 if (imu_data.at(i).timestamp > time1 && i == 0) {
322 }
else if (imu_data.at(i).timestamp > time1) {
323 ov_core::ImuData data = interpolate_data(imu_data.at(i - 1), imu_data.at(i), time1);
324 prop_data.push_back(data);
328 prop_data.push_back(imu_data.at(i));
334 if (prop_data.at(prop_data.size() - 1).timestamp != time1) {
335 ov_core::ImuData data = interpolate_data(imu_data.at(i), imu_data.at(i + 1), time1);
336 prop_data.push_back(data);
345 if (prop_data.empty()) {
349 "Propagator::select_imu_readings(): No IMU measurements to propagate with (%d of 2). IMU-CAMERA are likely messed up!!!\n" RESET,
350 (
int)prop_data.size());
358 if (prop_data.at(prop_data.size() - 1).timestamp != time1) {
360 PRINT_DEBUG(
YELLOW "Propagator::select_imu_readings(): Missing inertial measurements to propagate with (%f sec missing)!\n" RESET,
361 (time1 - imu_data.at(imu_data.size() - 1).timestamp));
362 ov_core::ImuData data = interpolate_data(imu_data.at(imu_data.size() - 2), imu_data.at(imu_data.size() - 1), time1);
363 prop_data.push_back(data);
371 for (
size_t i = 0; i < prop_data.size() - 1; i++) {
372 if (std::abs(prop_data.at(i + 1).timestamp - prop_data.at(i).timestamp) < 1e-12) {
374 PRINT_WARNING(
YELLOW "Propagator::select_imu_readings(): Zero DT between IMU reading %d and %d, removing it!\n" RESET, (
int)i,
376 prop_data.erase(prop_data.begin() + i);
382 if (prop_data.size() < 2) {
386 "Propagator::select_imu_readings(): No IMU measurements to propagate with (%d of 2). IMU-CAMERA are likely messed up!!!\n" RESET,
387 (
int)prop_data.size());
396 Eigen::MatrixXd &F, Eigen::MatrixXd &Qd) {
403 Eigen::Matrix3d Dw = State::Dm(state->_options.imu_model, state->_calib_imu_dw->value());
404 Eigen::Matrix3d Da = State::Dm(state->_options.imu_model, state->_calib_imu_da->value());
405 Eigen::Matrix3d Tg = State::Tg(state->_calib_imu_tg->value());
408 Eigen::Vector3d a_hat1 = data_minus.
am - state->_imu->bias_a();
409 Eigen::Vector3d a_hat2 = data_plus.
am - state->_imu->bias_a();
410 Eigen::Vector3d a_hat_avg = .5 * (a_hat1 + a_hat2);
413 Eigen::Vector3d a_uncorrected = a_hat_avg;
414 Eigen::Matrix3d R_ACCtoIMU = state->_calib_imu_ACCtoIMU->Rot();
415 a_hat1 = R_ACCtoIMU * Da * a_hat1;
416 a_hat2 = R_ACCtoIMU * Da * a_hat2;
417 a_hat_avg = R_ACCtoIMU * Da * a_hat_avg;
420 Eigen::Vector3d w_hat1 = data_minus.
wm - state->_imu->bias_g() - Tg * a_hat1;
421 Eigen::Vector3d w_hat2 = data_plus.
wm - state->_imu->bias_g() - Tg * a_hat2;
422 Eigen::Vector3d w_hat_avg = .5 * (w_hat1 + w_hat2);
425 Eigen::Vector3d w_uncorrected = w_hat_avg;
426 Eigen::Matrix3d R_GYROtoIMU = state->_calib_imu_GYROtoIMU->Rot();
427 w_hat1 = R_GYROtoIMU * Dw * w_hat1;
428 w_hat2 = R_GYROtoIMU * Dw * w_hat2;
429 w_hat_avg = R_GYROtoIMU * Dw * w_hat_avg;
432 Eigen::Matrix<double, 3, 18> Xi_sum = Eigen::Matrix<double, 3, 18>::Zero(3, 18);
433 if (state->_options.integration_method == StateOptions::IntegrationMethod::RK4 ||
434 state->_options.integration_method == StateOptions::IntegrationMethod::ANALYTICAL) {
435 compute_Xi_sum(state, dt, w_hat_avg, a_hat_avg, Xi_sum);
439 Eigen::Vector4d new_q;
440 Eigen::Vector3d new_v, new_p;
441 if (state->_options.integration_method == StateOptions::IntegrationMethod::ANALYTICAL) {
442 predict_mean_analytic(state, dt, w_hat_avg, a_hat_avg, new_q, new_v, new_p, Xi_sum);
443 }
else if (state->_options.integration_method == StateOptions::IntegrationMethod::RK4) {
444 predict_mean_rk4(state, dt, w_hat1, a_hat1, w_hat2, a_hat2, new_q, new_v, new_p);
446 predict_mean_discrete(state, dt, w_hat_avg, a_hat_avg, new_q, new_v, new_p);
450 F = Eigen::MatrixXd::Zero(state->imu_intrinsic_size() + 15, state->imu_intrinsic_size() + 15);
451 Eigen::MatrixXd G = Eigen::MatrixXd::Zero(state->imu_intrinsic_size() + 15, 12);
452 if (state->_options.integration_method == StateOptions::IntegrationMethod::RK4 ||
453 state->_options.integration_method == StateOptions::IntegrationMethod::ANALYTICAL) {
454 compute_F_and_G_analytic(state, dt, w_hat_avg, a_hat_avg, w_uncorrected, a_uncorrected, new_q, new_v, new_p, Xi_sum, F, G);
456 compute_F_and_G_discrete(state, dt, w_hat_avg, a_hat_avg, w_uncorrected, a_uncorrected, new_q, new_v, new_p, F, G);
462 Eigen::Matrix<double, 12, 12> Qc = Eigen::Matrix<double, 12, 12>::Zero();
463 Qc.block(0, 0, 3, 3) = std::pow(_noises.sigma_w, 2) / dt * Eigen::Matrix3d::Identity();
464 Qc.block(3, 3, 3, 3) = std::pow(_noises.sigma_a, 2) / dt * Eigen::Matrix3d::Identity();
465 Qc.block(6, 6, 3, 3) = std::pow(_noises.sigma_wb, 2) / dt * Eigen::Matrix3d::Identity();
466 Qc.block(9, 9, 3, 3) = std::pow(_noises.sigma_ab, 2) / dt * Eigen::Matrix3d::Identity();
469 Qd = Eigen::MatrixXd::Zero(state->imu_intrinsic_size() + 15, state->imu_intrinsic_size() + 15);
470 Qd = G * Qc * G.transpose();
471 Qd = 0.5 * (Qd + Qd.transpose());
474 Eigen::Matrix<double, 16, 1> imu_x = state->_imu->value();
475 imu_x.block(0, 0, 4, 1) = new_q;
476 imu_x.block(4, 0, 3, 1) = new_p;
477 imu_x.block(7, 0, 3, 1) = new_v;
478 state->_imu->set_value(imu_x);
479 state->_imu->set_fej(imu_x);
482 void Propagator::predict_mean_discrete(std::shared_ptr<State> state,
double dt,
const Eigen::Vector3d &w_hat,
const Eigen::Vector3d &a_hat,
483 Eigen::Vector4d &new_q, Eigen::Vector3d &new_v, Eigen::Vector3d &new_p) {
486 double w_norm = w_hat.norm();
487 Eigen::Matrix4d I_4x4 = Eigen::Matrix4d::Identity();
488 Eigen::Matrix3d R_Gtoi = state->_imu->Rot();
491 Eigen::Matrix<double, 4, 4> bigO;
492 if (w_norm > 1e-12) {
493 bigO = cos(0.5 * w_norm * dt) * I_4x4 + 1 / w_norm * sin(0.5 * w_norm * dt) *
Omega(w_hat);
495 bigO = I_4x4 + 0.5 * dt *
Omega(w_hat);
497 new_q =
quatnorm(bigO * state->_imu->quat());
501 new_v = state->_imu->vel() + R_Gtoi.transpose() * a_hat * dt - _gravity * dt;
504 new_p = state->_imu->pos() + state->_imu->vel() * dt + 0.5 * R_Gtoi.transpose() * a_hat * dt * dt - 0.5 * _gravity * dt * dt;
507 void Propagator::predict_mean_rk4(std::shared_ptr<State> state,
double dt,
const Eigen::Vector3d &w_hat1,
const Eigen::Vector3d &a_hat1,
508 const Eigen::Vector3d &w_hat2,
const Eigen::Vector3d &a_hat2, Eigen::Vector4d &new_q,
509 Eigen::Vector3d &new_v, Eigen::Vector3d &new_p) {
512 Eigen::Vector3d w_hat = w_hat1;
513 Eigen::Vector3d a_hat = a_hat1;
514 Eigen::Vector3d w_alpha = (w_hat2 - w_hat1) / dt;
515 Eigen::Vector3d a_jerk = (a_hat2 - a_hat1) / dt;
518 Eigen::Vector4d q_0 = state->_imu->quat();
519 Eigen::Vector3d p_0 = state->_imu->pos();
520 Eigen::Vector3d v_0 = state->_imu->vel();
523 Eigen::Vector4d dq_0 = {0, 0, 0, 1};
524 Eigen::Vector4d q0_dot = 0.5 *
Omega(w_hat) * dq_0;
525 Eigen::Vector3d p0_dot = v_0;
527 Eigen::Vector3d v0_dot = R_Gto0.transpose() * a_hat - _gravity;
529 Eigen::Vector4d k1_q = q0_dot * dt;
530 Eigen::Vector3d k1_p = p0_dot * dt;
531 Eigen::Vector3d k1_v = v0_dot * dt;
534 w_hat += 0.5 * w_alpha * dt;
535 a_hat += 0.5 * a_jerk * dt;
537 Eigen::Vector4d dq_1 =
quatnorm(dq_0 + 0.5 * k1_q);
539 Eigen::Vector3d v_1 = v_0 + 0.5 * k1_v;
541 Eigen::Vector4d q1_dot = 0.5 *
Omega(w_hat) * dq_1;
542 Eigen::Vector3d p1_dot = v_1;
544 Eigen::Vector3d v1_dot = R_Gto1.transpose() * a_hat - _gravity;
546 Eigen::Vector4d k2_q = q1_dot * dt;
547 Eigen::Vector3d k2_p = p1_dot * dt;
548 Eigen::Vector3d k2_v = v1_dot * dt;
551 Eigen::Vector4d dq_2 =
quatnorm(dq_0 + 0.5 * k2_q);
553 Eigen::Vector3d v_2 = v_0 + 0.5 * k2_v;
555 Eigen::Vector4d q2_dot = 0.5 *
Omega(w_hat) * dq_2;
556 Eigen::Vector3d p2_dot = v_2;
558 Eigen::Vector3d v2_dot = R_Gto2.transpose() * a_hat - _gravity;
560 Eigen::Vector4d k3_q = q2_dot * dt;
561 Eigen::Vector3d k3_p = p2_dot * dt;
562 Eigen::Vector3d k3_v = v2_dot * dt;
565 w_hat += 0.5 * w_alpha * dt;
566 a_hat += 0.5 * a_jerk * dt;
568 Eigen::Vector4d dq_3 =
quatnorm(dq_0 + k3_q);
570 Eigen::Vector3d v_3 = v_0 + k3_v;
572 Eigen::Vector4d q3_dot = 0.5 *
Omega(w_hat) * dq_3;
573 Eigen::Vector3d p3_dot = v_3;
575 Eigen::Vector3d v3_dot = R_Gto3.transpose() * a_hat - _gravity;
577 Eigen::Vector4d k4_q = q3_dot * dt;
578 Eigen::Vector3d k4_p = p3_dot * dt;
579 Eigen::Vector3d k4_v = v3_dot * dt;
582 Eigen::Vector4d dq =
quatnorm(dq_0 + (1.0 / 6.0) * k1_q + (1.0 / 3.0) * k2_q + (1.0 / 3.0) * k3_q + (1.0 / 6.0) * k4_q);
584 new_p = p_0 + (1.0 / 6.0) * k1_p + (1.0 / 3.0) * k2_p + (1.0 / 3.0) * k3_p + (1.0 / 6.0) * k4_p;
585 new_v = v_0 + (1.0 / 6.0) * k1_v + (1.0 / 3.0) * k2_v + (1.0 / 3.0) * k3_v + (1.0 / 6.0) * k4_v;
588 void Propagator::compute_Xi_sum(std::shared_ptr<State> state,
double dt,
const Eigen::Vector3d &w_hat,
const Eigen::Vector3d &a_hat,
589 Eigen::Matrix<double, 3, 18> &Xi_sum) {
592 double w_norm = w_hat.norm();
593 double d_th = w_norm * dt;
594 Eigen::Vector3d k_hat = Eigen::Vector3d::Zero();
595 if (w_norm > 1e-12) {
596 k_hat = w_hat / w_norm;
600 Eigen::Matrix3d I_3x3 = Eigen::Matrix3d::Identity();
601 double d_t2 = std::pow(dt, 2);
602 double d_t3 = std::pow(dt, 3);
603 double w_norm2 = std::pow(w_norm, 2);
604 double w_norm3 = std::pow(w_norm, 3);
605 double cos_dth = std::cos(d_th);
606 double sin_dth = std::sin(d_th);
607 double d_th2 = std::pow(d_th, 2);
608 double d_th3 = std::pow(d_th, 3);
610 Eigen::Matrix3d sK2 = sK * sK;
614 Eigen::Matrix3d R_ktok1, Xi_1, Xi_2, Jr_ktok1, Xi_3, Xi_4;
620 bool small_w = (w_norm < 1.0 / 180 * M_PI / 2);
624 Xi_1 = I_3x3 * dt + (1.0 - cos_dth) / w_norm * sK + (dt - sin_dth / w_norm) * sK2;
627 Xi_2 = 1.0 / 2 * d_t2 * I_3x3 + (d_th - sin_dth) / w_norm2 * sK + (1.0 / 2 * d_t2 - (1.0 - cos_dth) / w_norm2) * sK2;
630 Xi_3 = 1.0 / 2 * d_t2 * sA + (sin_dth - d_th) / w_norm2 * sA * sK + (sin_dth - d_th * cos_dth) / w_norm2 * sK * sA +
631 (1.0 / 2 * d_t2 - (1.0 - cos_dth) / w_norm2) * sA * sK2 +
632 (1.0 / 2 * d_t2 + (1.0 - cos_dth - d_th * sin_dth) / w_norm2) * (sK2 * sA + k_hat.dot(a_hat) * sK) -
633 (3 * sin_dth - 2 * d_th - d_th * cos_dth) / w_norm2 * k_hat.dot(a_hat) * sK2;
636 Xi_4 = 1.0 / 6 * d_t3 * sA + (2 * (1.0 - cos_dth) - d_th2) / (2 * w_norm3) * sA * sK +
637 ((2 * (1.0 - cos_dth) - d_th * sin_dth) / w_norm3) * sK * sA + ((sin_dth - d_th) / w_norm3 + d_t3 / 6) * sA * sK2 +
638 ((d_th - 2 * sin_dth + 1.0 / 6 * d_th3 + d_th * cos_dth) / w_norm3) * (sK2 * sA + k_hat.dot(a_hat) * sK) +
639 (4 * cos_dth - 4 + d_th2 + d_th * sin_dth) / w_norm3 * k_hat.dot(a_hat) * sK2;
644 Xi_1 = dt * (I_3x3 + sin_dth * sK + (1.0 - cos_dth) * sK2);
647 Xi_2 = 1.0 / 2 * dt * Xi_1;
650 Xi_3 = 1.0 / 2 * d_t2 *
651 (sA + sin_dth * (-sA * sK + sK * sA + k_hat.dot(a_hat) * sK2) + (1.0 - cos_dth) * (sA * sK2 + sK2 * sA + k_hat.dot(a_hat) * sK));
654 Xi_4 = 1.0 / 3 * dt * Xi_3;
659 Xi_sum.block(0, 0, 3, 3) = R_ktok1;
660 Xi_sum.block(0, 3, 3, 3) = Xi_1;
661 Xi_sum.block(0, 6, 3, 3) = Xi_2;
662 Xi_sum.block(0, 9, 3, 3) = Jr_ktok1;
663 Xi_sum.block(0, 12, 3, 3) = Xi_3;
664 Xi_sum.block(0, 15, 3, 3) = Xi_4;
667 void Propagator::predict_mean_analytic(std::shared_ptr<State> state,
double dt,
const Eigen::Vector3d &w_hat,
const Eigen::Vector3d &a_hat,
668 Eigen::Vector4d &new_q, Eigen::Vector3d &new_v, Eigen::Vector3d &new_p,
669 Eigen::Matrix<double, 3, 18> &Xi_sum) {
672 Eigen::Matrix3d R_Gtok = state->_imu->Rot();
674 Eigen::Matrix3d Xi_1 = Xi_sum.block(0, 3, 3, 3);
675 Eigen::Matrix3d Xi_2 = Xi_sum.block(0, 6, 3, 3);
679 new_v = state->_imu->vel() + R_Gtok.transpose() * Xi_1 * a_hat - _gravity * dt;
680 new_p = state->_imu->pos() + state->_imu->vel() * dt + R_Gtok.transpose() * Xi_2 * a_hat - 0.5 * _gravity * dt * dt;
683 void Propagator::compute_F_and_G_analytic(std::shared_ptr<State> state,
double dt,
const Eigen::Vector3d &w_hat,
684 const Eigen::Vector3d &a_hat,
const Eigen::Vector3d &w_uncorrected,
685 const Eigen::Vector3d &a_uncorrected,
const Eigen::Vector4d &new_q,
const Eigen::Vector3d &new_v,
686 const Eigen::Vector3d &new_p,
const Eigen::Matrix<double, 3, 18> &Xi_sum, Eigen::MatrixXd &F,
687 Eigen::MatrixXd &G) {
691 int th_id = local_size;
692 local_size += state->_imu->q()->size();
693 int p_id = local_size;
694 local_size += state->_imu->p()->size();
695 int v_id = local_size;
696 local_size += state->_imu->v()->size();
697 int bg_id = local_size;
698 local_size += state->_imu->bg()->size();
699 int ba_id = local_size;
700 local_size += state->_imu->ba()->size();
708 if (state->_options.do_calib_imu_intrinsics) {
710 local_size += state->_calib_imu_dw->size();
712 local_size += state->_calib_imu_da->size();
713 if (state->_options.do_calib_imu_g_sensitivity) {
715 local_size += state->_calib_imu_tg->size();
717 if (state->_options.imu_model == StateOptions::ImuModel::KALIBR) {
718 th_wtoI_id = local_size;
719 local_size += state->_calib_imu_GYROtoIMU->size();
721 th_atoI_id = local_size;
722 local_size += state->_calib_imu_ACCtoIMU->size();
728 Eigen::Matrix3d R_k = state->_imu->Rot();
729 Eigen::Vector3d v_k = state->_imu->vel();
730 Eigen::Vector3d p_k = state->_imu->pos();
731 if (state->_options.do_fej) {
732 R_k = state->_imu->Rot_fej();
733 v_k = state->_imu->vel_fej();
734 p_k = state->_imu->pos_fej();
736 Eigen::Matrix3d dR_ktok1 =
quat_2_Rot(new_q) * R_k.transpose();
738 Eigen::Matrix3d Dw = State::Dm(state->_options.imu_model, state->_calib_imu_dw->value());
739 Eigen::Matrix3d Da = State::Dm(state->_options.imu_model, state->_calib_imu_da->value());
740 Eigen::Matrix3d Tg = State::Tg(state->_calib_imu_tg->value());
741 Eigen::Matrix3d R_atoI = state->_calib_imu_ACCtoIMU->Rot();
742 Eigen::Matrix3d R_wtoI = state->_calib_imu_GYROtoIMU->Rot();
743 Eigen::Vector3d a_k = R_atoI * Da * a_uncorrected;
744 Eigen::Vector3d w_k = R_wtoI * Dw * w_uncorrected;
746 Eigen::Matrix3d Xi_1 = Xi_sum.block(0, 3, 3, 3);
747 Eigen::Matrix3d Xi_2 = Xi_sum.block(0, 6, 3, 3);
748 Eigen::Matrix3d Jr_ktok1 = Xi_sum.block(0, 9, 3, 3);
749 Eigen::Matrix3d Xi_3 = Xi_sum.block(0, 12, 3, 3);
750 Eigen::Matrix3d Xi_4 = Xi_sum.block(0, 15, 3, 3);
753 F.block(th_id, th_id, 3, 3) = dR_ktok1;
754 F.block(p_id, th_id, 3, 3) = -
skew_x(new_p - p_k - v_k * dt + 0.5 * _gravity * dt * dt) * R_k.transpose();
755 F.block(v_id, th_id, 3, 3) = -
skew_x(new_v - v_k + _gravity * dt) * R_k.transpose();
758 F.block(p_id, p_id, 3, 3).setIdentity();
761 F.block(p_id, v_id, 3, 3) = Eigen::Matrix3d::Identity() * dt;
762 F.block(v_id, v_id, 3, 3).setIdentity();
765 F.block(th_id, bg_id, 3, 3) = -dR_ktok1 * Jr_ktok1 * dt * R_wtoI * Dw;
766 F.block(p_id, bg_id, 3, 3) = R_k.transpose() * Xi_4 * R_wtoI * Dw;
767 F.block(v_id, bg_id, 3, 3) = R_k.transpose() * Xi_3 * R_wtoI * Dw;
768 F.block(bg_id, bg_id, 3, 3).setIdentity();
771 F.block(th_id, ba_id, 3, 3) = dR_ktok1 * Jr_ktok1 * dt * R_wtoI * Dw * Tg * R_atoI * Da;
772 F.block(p_id, ba_id, 3, 3) = -R_k.transpose() * (Xi_2 + Xi_4 * R_wtoI * Dw * Tg) * R_atoI * Da;
773 F.block(v_id, ba_id, 3, 3) = -R_k.transpose() * (Xi_1 + Xi_3 * R_wtoI * Dw * Tg) * R_atoI * Da;
774 F.block(ba_id, ba_id, 3, 3).setIdentity();
778 Eigen::MatrixXd H_Dw = compute_H_Dw(state, w_uncorrected);
779 F.block(th_id, Dw_id, 3, state->_calib_imu_dw->size()) = dR_ktok1 * Jr_ktok1 * dt * R_wtoI * H_Dw;
780 F.block(p_id, Dw_id, 3, state->_calib_imu_dw->size()) = -R_k.transpose() * Xi_4 * R_wtoI * H_Dw;
781 F.block(v_id, Dw_id, 3, state->_calib_imu_dw->size()) = -R_k.transpose() * Xi_3 * R_wtoI * H_Dw;
782 F.block(Dw_id, Dw_id, state->_calib_imu_dw->size(), state->_calib_imu_dw->size()).setIdentity();
787 Eigen::MatrixXd H_Da = compute_H_Da(state, a_uncorrected);
788 F.block(th_id, Da_id, 3, state->_calib_imu_da->size()) = -dR_ktok1 * Jr_ktok1 * dt * R_wtoI * Dw * Tg * R_atoI * H_Da;
789 F.block(p_id, Da_id, 3, state->_calib_imu_da->size()) = R_k.transpose() * (Xi_2 + Xi_4 * R_wtoI * Dw * Tg) * R_atoI * H_Da;
790 F.block(v_id, Da_id, 3, state->_calib_imu_da->size()) = R_k.transpose() * (Xi_1 + Xi_3 * R_wtoI * Dw * Tg) * R_atoI * H_Da;
791 F.block(Da_id, Da_id, state->_calib_imu_da->size(), state->_calib_imu_da->size()).
setIdentity();
796 Eigen::MatrixXd H_Tg = compute_H_Tg(state, a_k);
797 F.block(th_id, Tg_id, 3, state->_calib_imu_tg->size()) = -dR_ktok1 * Jr_ktok1 * dt * R_wtoI * Dw * H_Tg;
798 F.block(p_id, Tg_id, 3, state->_calib_imu_tg->size()) = R_k.transpose() * Xi_4 * R_wtoI * Dw * H_Tg;
799 F.block(v_id, Tg_id, 3, state->_calib_imu_tg->size()) = R_k.transpose() * Xi_3 * R_wtoI * Dw * H_Tg;
800 F.block(Tg_id, Tg_id, state->_calib_imu_tg->size(), state->_calib_imu_tg->size()).setIdentity();
804 if (th_atoI_id != -1) {
805 F.block(th_id, th_atoI_id, 3, 3) = -dR_ktok1 * Jr_ktok1 * dt * R_wtoI * Dw * Tg *
ov_core::skew_x(a_k);
806 F.block(p_id, th_atoI_id, 3, 3) = R_k.transpose() * (Xi_2 + Xi_4 * R_wtoI * Dw * Tg) *
ov_core::skew_x(a_k);
807 F.block(v_id, th_atoI_id, 3, 3) = R_k.transpose() * (Xi_1 + Xi_3 * R_wtoI * Dw * Tg) *
ov_core::skew_x(a_k);
808 F.block(th_atoI_id, th_atoI_id, 3, 3).setIdentity();
812 if (th_wtoI_id != -1) {
813 F.block(th_id, th_wtoI_id, 3, 3) = dR_ktok1 * Jr_ktok1 * dt *
ov_core::skew_x(w_k);
814 F.block(p_id, th_wtoI_id, 3, 3) = -R_k.transpose() * Xi_4 *
ov_core::skew_x(w_k);
815 F.block(v_id, th_wtoI_id, 3, 3) = -R_k.transpose() * Xi_3 *
ov_core::skew_x(w_k);
816 F.block(th_wtoI_id, th_wtoI_id, 3, 3).setIdentity();
820 G.block(th_id, 0, 3, 3) = -dR_ktok1 * Jr_ktok1 * dt * R_wtoI * Dw;
821 G.block(p_id, 0, 3, 3) = R_k.transpose() * Xi_4 * R_wtoI * Dw;
822 G.block(v_id, 0, 3, 3) = R_k.transpose() * Xi_3 * R_wtoI * Dw;
823 G.block(th_id, 3, 3, 3) = dR_ktok1 * Jr_ktok1 * dt * R_wtoI * Dw * Tg * R_atoI * Da;
824 G.block(p_id, 3, 3, 3) = -R_k.transpose() * (Xi_2 + Xi_4 * R_wtoI * Dw * Tg) * R_atoI * Da;
825 G.block(v_id, 3, 3, 3) = -R_k.transpose() * (Xi_1 + Xi_3 * R_wtoI * Dw * Tg) * R_atoI * Da;
826 G.block(bg_id, 6, 3, 3) = dt * Eigen::Matrix3d::Identity();
827 G.block(ba_id, 9, 3, 3) = dt * Eigen::Matrix3d::Identity();
830 void Propagator::compute_F_and_G_discrete(std::shared_ptr<State> state,
double dt,
const Eigen::Vector3d &w_hat,
831 const Eigen::Vector3d &a_hat,
const Eigen::Vector3d &w_uncorrected,
832 const Eigen::Vector3d &a_uncorrected,
const Eigen::Vector4d &new_q,
const Eigen::Vector3d &new_v,
833 const Eigen::Vector3d &new_p, Eigen::MatrixXd &F, Eigen::MatrixXd &G) {
837 int th_id = local_size;
838 local_size += state->_imu->q()->size();
839 int p_id = local_size;
840 local_size += state->_imu->p()->size();
841 int v_id = local_size;
842 local_size += state->_imu->v()->size();
843 int bg_id = local_size;
844 local_size += state->_imu->bg()->size();
845 int ba_id = local_size;
846 local_size += state->_imu->ba()->size();
854 if (state->_options.do_calib_imu_intrinsics) {
856 local_size += state->_calib_imu_dw->size();
858 local_size += state->_calib_imu_da->size();
859 if (state->_options.do_calib_imu_g_sensitivity) {
861 local_size += state->_calib_imu_tg->size();
863 if (state->_options.imu_model == StateOptions::ImuModel::KALIBR) {
864 th_wtoI_id = local_size;
865 local_size += state->_calib_imu_GYROtoIMU->size();
867 th_atoI_id = local_size;
868 local_size += state->_calib_imu_ACCtoIMU->size();
874 Eigen::Matrix3d R_k = state->_imu->Rot();
875 Eigen::Vector3d v_k = state->_imu->vel();
876 Eigen::Vector3d p_k = state->_imu->pos();
877 if (state->_options.do_fej) {
878 R_k = state->_imu->Rot_fej();
879 v_k = state->_imu->vel_fej();
880 p_k = state->_imu->pos_fej();
882 Eigen::Matrix3d dR_ktok1 =
quat_2_Rot(new_q) * R_k.transpose();
886 Eigen::Matrix3d Dw = State::Dm(state->_options.imu_model, state->_calib_imu_dw->value());
887 Eigen::Matrix3d Da = State::Dm(state->_options.imu_model, state->_calib_imu_da->value());
888 Eigen::Matrix3d Tg = State::Tg(state->_calib_imu_tg->value());
889 Eigen::Matrix3d R_atoI = state->_calib_imu_ACCtoIMU->Rot();
890 Eigen::Matrix3d R_wtoI = state->_calib_imu_GYROtoIMU->Rot();
891 Eigen::Vector3d a_k = R_atoI * Da * a_uncorrected;
892 Eigen::Vector3d w_k = R_wtoI * Dw * w_uncorrected;
896 F.block(th_id, th_id, 3, 3) = dR_ktok1;
898 F.block(th_id, bg_id, 3, 3) = -dR_ktok1 * Jr_ktok1 * dt * R_wtoI * Dw;
899 F.block(th_id, ba_id, 3, 3) = dR_ktok1 * Jr_ktok1 * dt * R_wtoI * Dw * Tg * R_atoI * Da;
902 F.block(p_id, th_id, 3, 3) = -
skew_x(new_p - p_k - v_k * dt + 0.5 * _gravity * dt * dt) * R_k.transpose();
903 F.block(p_id, p_id, 3, 3).setIdentity();
904 F.block(p_id, v_id, 3, 3) = Eigen::Matrix3d::Identity() * dt;
905 F.block(p_id, ba_id, 3, 3) = -0.5 * R_k.transpose() * dt * dt * R_atoI * Da;
908 F.block(v_id, th_id, 3, 3) = -
skew_x(new_v - v_k + _gravity * dt) * R_k.transpose();
909 F.block(v_id, v_id, 3, 3).setIdentity();
910 F.block(v_id, ba_id, 3, 3) = -R_k.transpose() * dt * R_atoI * Da;
913 F.block(bg_id, bg_id, 3, 3).setIdentity();
916 F.block(ba_id, ba_id, 3, 3).setIdentity();
920 Eigen::MatrixXd H_Dw = compute_H_Dw(state, w_uncorrected);
921 F.block(th_id, Dw_id, 3, state->_calib_imu_dw->size()) = dR_ktok1 * Jr_ktok1 * dt * R_wtoI * H_Dw;
922 F.block(Dw_id, Dw_id, state->_calib_imu_dw->size(), state->_calib_imu_dw->size()).setIdentity();
927 Eigen::MatrixXd H_Da = compute_H_Da(state, a_uncorrected);
928 F.block(th_id, Da_id, 3, state->_calib_imu_da->size()) = -dR_ktok1 * Jr_ktok1 * dt * R_wtoI * Tg * R_atoI * H_Da;
929 F.block(p_id, Da_id, 3, state->_calib_imu_da->size()) = 0.5 * R_k.transpose() * dt * dt * R_atoI * H_Da;
930 F.block(v_id, Da_id, 3, state->_calib_imu_da->size()) = R_k.transpose() * dt * R_atoI * H_Da;
931 F.block(Da_id, Da_id, state->_calib_imu_da->size(), state->_calib_imu_da->size()).setIdentity();
936 Eigen::MatrixXd H_Tg = compute_H_Tg(state, a_k);
937 F.block(th_id, Tg_id, 3, state->_calib_imu_tg->size()) = -dR_ktok1 * Jr_ktok1 * dt * R_wtoI * Dw * H_Tg;
938 F.block(Tg_id, Tg_id, state->_calib_imu_tg->size(), state->_calib_imu_tg->size()).setIdentity();
942 if (th_atoI_id != -1) {
943 F.block(th_id, th_atoI_id, 3, 3) = -dR_ktok1 * Jr_ktok1 * dt * R_wtoI * Dw * Tg *
ov_core::skew_x(a_k);
944 F.block(p_id, th_atoI_id, 3, 3) = 0.5 * R_k.transpose() * dt * dt *
ov_core::skew_x(a_k);
945 F.block(v_id, th_atoI_id, 3, 3) = R_k.transpose() * dt *
ov_core::skew_x(a_k);
946 F.block(th_atoI_id, th_atoI_id, 3, 3).setIdentity();
950 if (th_wtoI_id != -1) {
951 F.block(th_id, th_wtoI_id, 3, 3) = dR_ktok1 * Jr_ktok1 * dt *
ov_core::skew_x(w_k);
952 F.block(th_wtoI_id, th_wtoI_id, 3, 3).setIdentity();
956 G.block(th_id, 0, 3, 3) = -dR_ktok1 * Jr_ktok1 * dt * R_wtoI * Dw;
957 G.block(th_id, 3, 3, 3) = dR_ktok1 * Jr_ktok1 * dt * R_wtoI * Dw * Tg * R_atoI * Da;
958 G.block(v_id, 3, 3, 3) = -R_k.transpose() * dt * R_atoI * Da;
959 G.block(p_id, 3, 3, 3) = -0.5 * R_k.transpose() * dt * dt * R_atoI * Da;
960 G.block(bg_id, 6, 3, 3) = dt * Eigen::Matrix3d::Identity();
961 G.block(ba_id, 9, 3, 3) = dt * Eigen::Matrix3d::Identity();
964 Eigen::MatrixXd Propagator::compute_H_Dw(std::shared_ptr<State> state,
const Eigen::Vector3d &w_uncorrected) {
966 Eigen::Matrix3d I_3x3 = Eigen::MatrixXd::Identity(3, 3);
967 Eigen::Vector3d e_1 = I_3x3.block(0, 0, 3, 1);
968 Eigen::Vector3d e_2 = I_3x3.block(0, 1, 3, 1);
969 Eigen::Vector3d e_3 = I_3x3.block(0, 2, 3, 1);
970 double w_1 = w_uncorrected(0);
971 double w_2 = w_uncorrected(1);
972 double w_3 = w_uncorrected(2);
973 assert(state->_options.do_calib_imu_intrinsics);
975 Eigen::MatrixXd H_Dw = Eigen::MatrixXd::Zero(3, 6);
976 if (state->_options.imu_model == StateOptions::ImuModel::KALIBR) {
977 H_Dw << w_1 * I_3x3, w_2 * e_2, w_2 * e_3, w_3 * e_3;
979 H_Dw << w_1 * e_1, w_2 * e_1, w_2 * e_2, w_3 * I_3x3;
984 Eigen::MatrixXd Propagator::compute_H_Da(std::shared_ptr<State> state,
const Eigen::Vector3d &a_uncorrected) {
986 Eigen::Matrix3d I_3x3 = Eigen::MatrixXd::Identity(3, 3);
987 Eigen::Vector3d e_1 = I_3x3.block(0, 0, 3, 1);
988 Eigen::Vector3d e_2 = I_3x3.block(0, 1, 3, 1);
989 Eigen::Vector3d e_3 = I_3x3.block(0, 2, 3, 1);
990 double a_1 = a_uncorrected(0);
991 double a_2 = a_uncorrected(1);
992 double a_3 = a_uncorrected(2);
993 assert(state->_options.do_calib_imu_intrinsics);
995 Eigen::MatrixXd H_Da = Eigen::MatrixXd::Zero(3, 6);
996 if (state->_options.imu_model == StateOptions::ImuModel::KALIBR) {
997 H_Da << a_1 * I_3x3, a_2 * e_2, a_2 * e_3, a_3 * e_3;
999 H_Da << a_1 * e_1, a_2 * e_1, a_2 * e_2, a_3 * I_3x3;
1004 Eigen::MatrixXd Propagator::compute_H_Tg(std::shared_ptr<State> state,
const Eigen::Vector3d &a_inI) {
1006 Eigen::Matrix3d I_3x3 = Eigen::MatrixXd::Identity(3, 3);
1007 double a_1 = a_inI(0);
1008 double a_2 = a_inI(1);
1009 double a_3 = a_inI(2);
1010 assert(state->_options.do_calib_imu_intrinsics);
1011 assert(state->_options.do_calib_imu_g_sensitivity);
1013 Eigen::MatrixXd H_Tg = Eigen::MatrixXd::Zero(3, 9);
1014 H_Tg << a_1 * I_3x3, a_2 * I_3x3, a_3 * I_3x3;