Go to the documentation of this file.
22 #ifndef OV_MSCKF_STATE_PROPAGATOR_H
23 #define OV_MSCKF_STATE_PROPAGATOR_H
85 if (it0->timestamp < oldest_time) {
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);
141 static std::vector<ov_core::ImuData>
select_imu_readings(
const std::vector<ov_core::ImuData> &
imu_data,
double time0,
double time1,
161 data.
am = (1 - lambda) * imu_1.
am + lambda * imu_2.
am;
162 data.
wm = (1 - lambda) * imu_1.
wm + lambda * imu_2.
wm;
184 static Eigen::MatrixXd
compute_H_Dw(std::shared_ptr<State> state,
const Eigen::Vector3d &w_uncorrected);
204 static Eigen::MatrixXd
compute_H_Da(std::shared_ptr<State> state,
const Eigen::Vector3d &a_uncorrected);
220 static Eigen::MatrixXd
compute_H_Tg(std::shared_ptr<State> state,
const Eigen::Vector3d &a_inI);
240 Eigen::MatrixXd &F, Eigen::MatrixXd &Qd);
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);
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);
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);
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);
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);
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);
458 #endif // OV_MSCKF_STATE_PROPAGATOR_H
double sigma_a_2
Accelerometer white noise covariance.
double sigma_a
Accelerometer white noise (m/s^2/sqrt(hz))
bool have_last_prop_time_offset
NoiseManager _noises
Container for the noise values.
static Eigen::MatrixXd compute_H_Tg(std::shared_ptr< State > state, const Eigen::Vector3d &a_inI)
compute the Jacobians for Tg
std::vector< ov_core::ImuData > imu_data
Our history of IMU messages (time, angular, linear)
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.
Eigen::Vector3d _gravity
Gravity vector.
double last_prop_time_offset
double sigma_wb
Gyroscope random walk (rad/s^2/sqrt(hz))
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.
Extended Kalman Filter estimator.
double sigma_wb_2
Gyroscope random walk covariance.
double sigma_ab
Accelerometer random walk (m/s^3/sqrt(hz))
std::atomic< bool > cache_imu_valid
void propagate_and_clone(std::shared_ptr< State > state, double timestamp)
Propagate state up to given timestamp and then clone.
void clean_old_imu_measurements(double oldest_time)
This will remove any IMU measurements that are older then the given measurement time.
Eigen::MatrixXd cache_state_covariance
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.
double sigma_w
Gyroscope white noise (rad/s/sqrt(hz))
Performs the state covariance and mean propagation using imu measurements.
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.
static Eigen::MatrixXd compute_H_Da(std::shared_ptr< State > state, const Eigen::Vector3d &a_uncorrected)
compute the Jacobians for Da
double sigma_ab_2
Accelerometer random walk covariance.
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
Eigen::Matrix< double, 3, 1 > wm
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...
void feed_imu(const ov_core::ImuData &message, double oldest_time=-1)
Stores incoming inertial readings.
Eigen::Matrix< double, 3, 1 > am
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.
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.
void invalidate_cache()
Will invalidate the cache used for fast propagation.
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.
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.
double sigma_w_2
Gyroscope white noise covariance.
Eigen::MatrixXd cache_state_est
static Eigen::MatrixXd compute_H_Dw(std::shared_ptr< State > state, const Eigen::Vector3d &w_uncorrected)
compute the Jacobians for Dw
Struct of our imu noise parameters.
Propagator(NoiseManager noises, double gravity_mag)
Default constructor.
ov_msckf
Author(s): Patrick Geneva
, Kevin Eckenhoff , Guoquan Huang
autogenerated on Mon Dec 16 2024 03:06:54