Propagator.h
Go to the documentation of this file.
1 /*
2  * OpenVINS: An Open Platform for Visual-Inertial Research
3  * Copyright (C) 2018-2023 Patrick Geneva
4  * Copyright (C) 2018-2023 Guoquan Huang
5  * Copyright (C) 2018-2023 OpenVINS Contributors
6  * Copyright (C) 2018-2019 Kevin Eckenhoff
7  *
8  * This program is free software: you can redistribute it and/or modify
9  * it under the terms of the GNU General Public License as published by
10  * the Free Software Foundation, either version 3 of the License, or
11  * (at your option) any later version.
12  *
13  * This program is distributed in the hope that it will be useful,
14  * but WITHOUT ANY WARRANTY; without even the implied warranty of
15  * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
16  * GNU General Public License for more details.
17  *
18  * You should have received a copy of the GNU General Public License
19  * along with this program. If not, see <https://www.gnu.org/licenses/>.
20  */
21 
22 #ifndef OV_MSCKF_STATE_PROPAGATOR_H
23 #define OV_MSCKF_STATE_PROPAGATOR_H
24 
25 #include <atomic>
26 #include <memory>
27 #include <mutex>
28 
29 #include "utils/sensor_data.h"
30 
31 #include "utils/NoiseManager.h"
32 
33 namespace ov_msckf {
34 
35 class State;
36 
44 class Propagator {
45 public:
51  Propagator(NoiseManager noises, double gravity_mag) : _noises(noises), cache_imu_valid(false) {
52  _noises.sigma_w_2 = std::pow(_noises.sigma_w, 2);
53  _noises.sigma_a_2 = std::pow(_noises.sigma_a, 2);
54  _noises.sigma_wb_2 = std::pow(_noises.sigma_wb, 2);
55  _noises.sigma_ab_2 = std::pow(_noises.sigma_ab, 2);
57  _gravity << 0.0, 0.0, gravity_mag;
58  }
59 
65  void feed_imu(const ov_core::ImuData &message, double oldest_time = -1) {
66 
67  // Append it to our vector
68  std::lock_guard<std::mutex> lck(imu_data_mtx);
69  imu_data.emplace_back(message);
70 
71  // Clean old measurements
72  // std::cout << "PROP: imu_data.size() " << imu_data.size() << std::endl;
73  clean_old_imu_measurements(oldest_time - 0.10);
74  }
75 
80  void clean_old_imu_measurements(double oldest_time) {
81  if (oldest_time < 0)
82  return;
83  auto it0 = imu_data.begin();
84  while (it0 != imu_data.end()) {
85  if (it0->timestamp < oldest_time) {
86  it0 = imu_data.erase(it0);
87  } else {
88  it0++;
89  }
90  }
91  }
92 
96  void invalidate_cache() { cache_imu_valid = false; }
97 
110  void propagate_and_clone(std::shared_ptr<State> state, double timestamp);
111 
125  bool fast_state_propagate(std::shared_ptr<State> state, double timestamp, Eigen::Matrix<double, 13, 1> &state_plus,
126  Eigen::Matrix<double, 12, 12> &covariance);
127 
141  static std::vector<ov_core::ImuData> select_imu_readings(const std::vector<ov_core::ImuData> &imu_data, double time0, double time1,
142  bool warn = true);
143 
154  static ov_core::ImuData interpolate_data(const ov_core::ImuData &imu_1, const ov_core::ImuData &imu_2, double timestamp) {
155  // time-distance lambda
156  double lambda = (timestamp - imu_1.timestamp) / (imu_2.timestamp - imu_1.timestamp);
157  // PRINT_DEBUG("lambda - %d\n", lambda);
158  // interpolate between the two times
159  ov_core::ImuData data;
160  data.timestamp = timestamp;
161  data.am = (1 - lambda) * imu_1.am + lambda * imu_2.am;
162  data.wm = (1 - lambda) * imu_1.wm + lambda * imu_2.wm;
163  return data;
164  }
165 
184  static Eigen::MatrixXd compute_H_Dw(std::shared_ptr<State> state, const Eigen::Vector3d &w_uncorrected);
185 
204  static Eigen::MatrixXd compute_H_Da(std::shared_ptr<State> state, const Eigen::Vector3d &a_uncorrected);
205 
220  static Eigen::MatrixXd compute_H_Tg(std::shared_ptr<State> state, const Eigen::Vector3d &a_inI);
221 
222 protected:
239  void predict_and_compute(std::shared_ptr<State> state, const ov_core::ImuData &data_minus, const ov_core::ImuData &data_plus,
240  Eigen::MatrixXd &F, Eigen::MatrixXd &Qd);
241 
266  void predict_mean_discrete(std::shared_ptr<State> state, double dt, const Eigen::Vector3d &w_hat, const Eigen::Vector3d &a_hat,
267  Eigen::Vector4d &new_q, Eigen::Vector3d &new_v, Eigen::Vector3d &new_p);
268 
295  void predict_mean_rk4(std::shared_ptr<State> state, double dt, const Eigen::Vector3d &w_hat1, const Eigen::Vector3d &a_hat1,
296  const Eigen::Vector3d &w_hat2, const Eigen::Vector3d &a_hat2, Eigen::Vector4d &new_q, Eigen::Vector3d &new_v,
297  Eigen::Vector3d &new_p);
298 
358  void compute_Xi_sum(std::shared_ptr<State> state, double dt, const Eigen::Vector3d &w_hat, const Eigen::Vector3d &a_hat,
359  Eigen::Matrix<double, 3, 18> &Xi_sum);
360 
383  void predict_mean_analytic(std::shared_ptr<State> state, double dt, const Eigen::Vector3d &w_hat, const Eigen::Vector3d &a_hat,
384  Eigen::Vector4d &new_q, Eigen::Vector3d &new_v, Eigen::Vector3d &new_p, Eigen::Matrix<double, 3, 18> &Xi_sum);
385 
406  void compute_F_and_G_analytic(std::shared_ptr<State> state, double dt, const Eigen::Vector3d &w_hat, const Eigen::Vector3d &a_hat,
407  const Eigen::Vector3d &w_uncorrected, const Eigen::Vector3d &a_uncorrected, const Eigen::Vector4d &new_q,
408  const Eigen::Vector3d &new_v, const Eigen::Vector3d &new_p, const Eigen::Matrix<double, 3, 18> &Xi_sum,
409  Eigen::MatrixXd &F, Eigen::MatrixXd &G);
410 
430  void compute_F_and_G_discrete(std::shared_ptr<State> state, double dt, const Eigen::Vector3d &w_hat, const Eigen::Vector3d &a_hat,
431  const Eigen::Vector3d &w_uncorrected, const Eigen::Vector3d &a_uncorrected, const Eigen::Vector4d &new_q,
432  const Eigen::Vector3d &new_v, const Eigen::Vector3d &new_p, Eigen::MatrixXd &F, Eigen::MatrixXd &G);
433 
436 
438  std::vector<ov_core::ImuData> imu_data;
439  std::mutex imu_data_mtx;
440 
442  Eigen::Vector3d _gravity;
443 
444  // Estimate for time offset at last propagation time
445  double last_prop_time_offset = 0.0;
447 
448  // Cache of the last fast propagated state
449  std::atomic<bool> cache_imu_valid;
451  Eigen::MatrixXd cache_state_est;
452  Eigen::MatrixXd cache_state_covariance;
453  double cache_t_off;
454 };
455 
456 } // namespace ov_msckf
457 
458 #endif // OV_MSCKF_STATE_PROPAGATOR_H
ov_msckf::NoiseManager::sigma_a_2
double sigma_a_2
Accelerometer white noise covariance.
Definition: NoiseManager.h:52
ov_msckf::NoiseManager::sigma_a
double sigma_a
Accelerometer white noise (m/s^2/sqrt(hz))
Definition: NoiseManager.h:49
ov_msckf::Propagator::have_last_prop_time_offset
bool have_last_prop_time_offset
Definition: Propagator.h:446
ov_msckf::Propagator::cache_t_off
double cache_t_off
Definition: Propagator.h:453
ov_msckf::Propagator::_noises
NoiseManager _noises
Container for the noise values.
Definition: Propagator.h:435
ov_msckf::Propagator::compute_H_Tg
static Eigen::MatrixXd compute_H_Tg(std::shared_ptr< State > state, const Eigen::Vector3d &a_inI)
compute the Jacobians for Tg
Definition: Propagator.cpp:1004
ov_msckf::Propagator::imu_data
std::vector< ov_core::ImuData > imu_data
Our history of IMU messages (time, angular, linear)
Definition: Propagator.h:438
ov_msckf::Propagator::predict_mean_rk4
void predict_mean_rk4(std::shared_ptr< State > state, double dt, const Eigen::Vector3d &w_hat1, const Eigen::Vector3d &a_hat1, const Eigen::Vector3d &w_hat2, const Eigen::Vector3d &a_hat2, Eigen::Vector4d &new_q, Eigen::Vector3d &new_v, Eigen::Vector3d &new_p)
RK4 imu mean propagation.
Definition: Propagator.cpp:507
ov_msckf::Propagator::_gravity
Eigen::Vector3d _gravity
Gravity vector.
Definition: Propagator.h:442
ov_msckf::Propagator::last_prop_time_offset
double last_prop_time_offset
Definition: Propagator.h:445
ov_msckf::NoiseManager::sigma_wb
double sigma_wb
Gyroscope random walk (rad/s^2/sqrt(hz))
Definition: NoiseManager.h:43
ov_msckf::Propagator::predict_mean_analytic
void predict_mean_analytic(std::shared_ptr< State > state, double dt, const Eigen::Vector3d &w_hat, const Eigen::Vector3d &a_hat, Eigen::Vector4d &new_q, Eigen::Vector3d &new_v, Eigen::Vector3d &new_p, Eigen::Matrix< double, 3, 18 > &Xi_sum)
Analytically predict IMU mean based on ACI^2.
Definition: Propagator.cpp:667
ov_msckf
Extended Kalman Filter estimator.
Definition: VioManager.h:46
ov_msckf::NoiseManager::sigma_wb_2
double sigma_wb_2
Gyroscope random walk covariance.
Definition: NoiseManager.h:46
sensor_data.h
ov_msckf::NoiseManager::sigma_ab
double sigma_ab
Accelerometer random walk (m/s^3/sqrt(hz))
Definition: NoiseManager.h:55
ov_msckf::Propagator::cache_imu_valid
std::atomic< bool > cache_imu_valid
Definition: Propagator.h:449
ov_msckf::Propagator::propagate_and_clone
void propagate_and_clone(std::shared_ptr< State > state, double timestamp)
Propagate state up to given timestamp and then clone.
Definition: Propagator.cpp:33
ov_msckf::Propagator::clean_old_imu_measurements
void clean_old_imu_measurements(double oldest_time)
This will remove any IMU measurements that are older then the given measurement time.
Definition: Propagator.h:80
ov_msckf::Propagator::cache_state_covariance
Eigen::MatrixXd cache_state_covariance
Definition: Propagator.h:452
ov_msckf::Propagator::compute_F_and_G_analytic
void compute_F_and_G_analytic(std::shared_ptr< State > state, double dt, const Eigen::Vector3d &w_hat, const Eigen::Vector3d &a_hat, const Eigen::Vector3d &w_uncorrected, const Eigen::Vector3d &a_uncorrected, const Eigen::Vector4d &new_q, const Eigen::Vector3d &new_v, const Eigen::Vector3d &new_p, const Eigen::Matrix< double, 3, 18 > &Xi_sum, Eigen::MatrixXd &F, Eigen::MatrixXd &G)
Analytically compute state transition matrix F and noise Jacobian G based on ACI^2.
Definition: Propagator.cpp:683
ov_msckf::NoiseManager::sigma_w
double sigma_w
Gyroscope white noise (rad/s/sqrt(hz))
Definition: NoiseManager.h:37
ov_msckf::Propagator
Performs the state covariance and mean propagation using imu measurements.
Definition: Propagator.h:44
ov_msckf::Propagator::fast_state_propagate
bool fast_state_propagate(std::shared_ptr< State > state, double timestamp, Eigen::Matrix< double, 13, 1 > &state_plus, Eigen::Matrix< double, 12, 12 > &covariance)
Gets what the state and its covariance will be at a given timestamp.
Definition: Propagator.cpp:140
ov_msckf::Propagator::compute_H_Da
static Eigen::MatrixXd compute_H_Da(std::shared_ptr< State > state, const Eigen::Vector3d &a_uncorrected)
compute the Jacobians for Da
Definition: Propagator.cpp:984
ov_msckf::NoiseManager::sigma_ab_2
double sigma_ab_2
Accelerometer random walk covariance.
Definition: NoiseManager.h:58
ov_msckf::Propagator::compute_F_and_G_discrete
void compute_F_and_G_discrete(std::shared_ptr< State > state, double dt, const Eigen::Vector3d &w_hat, const Eigen::Vector3d &a_hat, const Eigen::Vector3d &w_uncorrected, const Eigen::Vector3d &a_uncorrected, const Eigen::Vector4d &new_q, const Eigen::Vector3d &new_v, const Eigen::Vector3d &new_p, Eigen::MatrixXd &F, Eigen::MatrixXd &G)
compute state transition matrix F and noise Jacobian G
Definition: Propagator.cpp:830
ov_core::ImuData::wm
Eigen::Matrix< double, 3, 1 > wm
ov_msckf::Propagator::predict_and_compute
void predict_and_compute(std::shared_ptr< State > state, const ov_core::ImuData &data_minus, const ov_core::ImuData &data_plus, Eigen::MatrixXd &F, Eigen::MatrixXd &Qd)
Propagates the state forward using the imu data and computes the noise covariance and state-transitio...
Definition: Propagator.cpp:395
ov_core::ImuData
ov_msckf::Propagator::feed_imu
void feed_imu(const ov_core::ImuData &message, double oldest_time=-1)
Stores incoming inertial readings.
Definition: Propagator.h:65
ov_core::ImuData::am
Eigen::Matrix< double, 3, 1 > am
ov_msckf::Propagator::select_imu_readings
static std::vector< ov_core::ImuData > select_imu_readings(const std::vector< ov_core::ImuData > &imu_data, double time0, double time1, bool warn=true)
Helper function that given current imu data, will select imu readings between the two times.
Definition: Propagator.cpp:269
ov_msckf::Propagator::predict_mean_discrete
void predict_mean_discrete(std::shared_ptr< State > state, double dt, const Eigen::Vector3d &w_hat, const Eigen::Vector3d &a_hat, Eigen::Vector4d &new_q, Eigen::Vector3d &new_v, Eigen::Vector3d &new_p)
Discrete imu mean propagation.
Definition: Propagator.cpp:482
ov_msckf::Propagator::invalidate_cache
void invalidate_cache()
Will invalidate the cache used for fast propagation.
Definition: Propagator.h:96
NoiseManager.h
ov_msckf::Propagator::interpolate_data
static ov_core::ImuData interpolate_data(const ov_core::ImuData &imu_1, const ov_core::ImuData &imu_2, double timestamp)
Nice helper function that will linearly interpolate between two imu messages.
Definition: Propagator.h:154
ov_msckf::Propagator::compute_Xi_sum
void compute_Xi_sum(std::shared_ptr< State > state, double dt, const Eigen::Vector3d &w_hat, const Eigen::Vector3d &a_hat, Eigen::Matrix< double, 3, 18 > &Xi_sum)
Analytically compute the integration components based on ACI^2.
Definition: Propagator.cpp:588
ov_msckf::NoiseManager::sigma_w_2
double sigma_w_2
Gyroscope white noise covariance.
Definition: NoiseManager.h:40
ov_msckf::Propagator::imu_data_mtx
std::mutex imu_data_mtx
Definition: Propagator.h:439
ov_msckf::Propagator::cache_state_time
double cache_state_time
Definition: Propagator.h:450
ov_msckf::Propagator::cache_state_est
Eigen::MatrixXd cache_state_est
Definition: Propagator.h:451
ov_core::ImuData::timestamp
double timestamp
ov_msckf::Propagator::compute_H_Dw
static Eigen::MatrixXd compute_H_Dw(std::shared_ptr< State > state, const Eigen::Vector3d &w_uncorrected)
compute the Jacobians for Dw
Definition: Propagator.cpp:964
ov_msckf::NoiseManager
Struct of our imu noise parameters.
Definition: NoiseManager.h:34
ov_msckf::Propagator::Propagator
Propagator(NoiseManager noises, double gravity_mag)
Default constructor.
Definition: Propagator.h:51


ov_msckf
Author(s): Patrick Geneva , Kevin Eckenhoff , Guoquan Huang
autogenerated on Mon Dec 16 2024 03:06:54