19 #include <eigen3/Eigen/Eigen>
26 #include "ekf/constants.hpp"
27 #include "ekf/types.hpp"
28 #include "infrastructure/data_logger.hpp"
29 #include "infrastructure/debug_logger.hpp"
54 Eigen::VectorXd
process_noise{Eigen::VectorXd::Ones(g_body_state_size)};
172 const Eigen::MatrixXd & covariance);
183 const Eigen::Matrix3d & covariance);
194 const Eigen::MatrixXd & covariance);
209 Eigen::MatrixXd
AugmentCovariance(
const Eigen::MatrixXd & in_cov,
unsigned int index);
240 void SetGpsReference(
const Eigen::VectorXd & pos_e_in_g,
double ang_l_to_e);
304 Eigen::Vector3d gps_lla);
394 Eigen::MatrixXd
m_cov = Eigen::MatrixXd::Identity(g_body_state_size, g_body_state_size) * 1e-2;
397 unsigned int m_state_size{g_body_state_size};
398 unsigned int m_imu_state_size{0};
399 unsigned int m_gps_state_size{0};
400 unsigned int m_cam_state_size{0};
401 unsigned int m_aug_state_size{0};
402 unsigned int m_fid_state_size{0};
403 double m_current_time {0};
404 double m_reference_time {0};
405 bool m_time_initialized {
false};
406 unsigned int m_max_track_length{20};
407 Eigen::MatrixXd m_process_noise {Eigen::MatrixXd::Zero(g_body_state_size, g_body_state_size)};
408 Eigen::VectorXd m_body_process_noise {Eigen::VectorXd::Zero(g_body_state_size)};
409 std::shared_ptr<DebugLogger> m_debug_logger;
412 double m_data_log_rate{0.0};
414 GpsInitType m_gps_init_type;
415 double m_gps_init_pos_thresh;
416 double m_gps_init_ang_thresh;
417 double m_gps_init_baseline_dist;
418 bool m_is_lla_initialized;
419 Eigen::Vector3d m_pos_e_in_g;
421 std::vector<double> m_gps_time_vec;
422 std::vector<Eigen::Vector3d> m_gps_ecef_vec;
423 std::vector<Eigen::Vector3d> m_gps_xyz_vec;
425 AugmentationType m_augmenting_type;
426 double m_augmenting_prev_time;
427 double m_augmenting_delta_time;
428 double m_augmenting_pos_error;
429 double m_augmenting_ang_error;
430 unsigned int m_primary_camera_id{0};
431 double m_max_frame_period {0.0};
432 double m_max_track_duration {0.0};
433 double m_min_aug_period {1.0};
435 unsigned int m_imu_state_start{0};
436 unsigned int m_gps_state_start{0};
437 unsigned int m_cam_state_start{0};
438 unsigned int m_aug_state_start{0};
439 unsigned int m_fid_state_start{0};
441 bool m_is_gravity_initialized{
false};
442 double m_motion_detection_chi_squared{1.0};
443 double m_imu_noise_scale_factor{100.0};
445 bool m_use_root_covariance{
true};
446 bool m_use_first_estimate_jacobian{
false};
447 bool m_is_zero_acceleration{
true};
448 bool m_frame_received_since_last_aug {
true};
AugState structure.
Definition: types.hpp:203
BodyState structure.
Definition: types.hpp:81
CamState structure.
Definition: types.hpp:226
DataLogger class.
Definition: data_logger.hpp:26
Calibration EKF class.
Definition: ekf.hpp:39
bool IsGravityInitialized()
Checks if the gravity angle has been initialized.
Definition: ekf.cpp:664
void SetZeroAcceleration(bool is_zero_acceleration)
Zero acceleration flag setter.
Definition: ekf.cpp:641
void SetMaxTrackLength(unsigned int max_track_length)
Setter for maximum track length.
Definition: ekf.cpp:628
unsigned int GetImuStateSize()
IMU state size getter method.
Definition: ekf.cpp:212
AugState GetAugState(unsigned int camera_id, int frame_id, double time)
Find or interpolate augmented state.
Definition: ekf.cpp:569
void SetGpsReference(const Eigen::VectorXd &pos_e_in_g, double ang_l_to_e)
GPS reference position setter.
Definition: ekf.cpp:634
State m_state
EKF state.
Definition: ekf.hpp:391
unsigned int GetGpsStateSize()
GPS state size getter method.
Definition: ekf.cpp:222
Eigen::MatrixXd GetStateTransition(double dT)
State transition matrix getter method.
Definition: ekf.cpp:93
void AttemptGpsInitialization(double time, Eigen::Vector3d gps_lla)
GPS LLA to ENU Initialization Routine.
Definition: ekf.cpp:753
Eigen::MatrixXd m_cov
EKF covariance.
Definition: ekf.hpp:394
void RegisterIMU(unsigned int imu_id, const ImuState &imu_state, const Eigen::MatrixXd &covariance)
IMU Registration function.
Definition: ekf.cpp:249
double GetImuNoiseScaleFactor()
IMU noise scale factor getter.
Definition: ekf.cpp:848
std::vector< double > GetGpsTimeVector()
GPS time vector getter.
Definition: ekf.cpp:800
CamState GetCamState(unsigned int cam_id)
Get camera sensor state.
Definition: ekf.cpp:202
void AugmentStateIfNeeded()
Check if state should be augmented using current state.
Definition: ekf.cpp:431
void RegisterGPS(unsigned int gps_id, const GpsState &gps_state, const Eigen::Matrix3d &covariance)
GPS Registration function.
Definition: ekf.cpp:285
struct EKF::Parameters Parameters
EKF class parameters.
unsigned int GetFidStateStart()
Fiducial state start getter.
Definition: ekf.cpp:833
unsigned int GetAugStateSize()
Get augmented state size.
Definition: ekf.cpp:237
Eigen::MatrixXd AugmentCovariance(const Eigen::MatrixXd &in_cov, unsigned int index)
Augment the state covariance matrix.
Definition: ekf.cpp:376
unsigned int GetImuCount()
IMU count getter method.
Definition: ekf.cpp:207
std::vector< Eigen::Vector3d > GetGpsEcefVector()
GPS ECEF vector getter.
Definition: ekf.cpp:804
bool GetUseFirstEstimateJacobian()
Getter for use first estimate Jacobians.
Definition: ekf.cpp:858
unsigned int GetGpsStateStart()
GPS state start getter.
Definition: ekf.cpp:818
double CalculateLocalTime(double time)
Calculate UTF time to local EKF time.
Definition: ekf.cpp:863
unsigned int GetImuStateStart()
IMU state start getter.
Definition: ekf.cpp:813
void InitializeGravity()
Function to initialize gravity angle.
Definition: ekf.cpp:669
double GetCurrentTime()
Current time getter.
Definition: ekf.cpp:838
unsigned int GetAugStateStart()
Augmented states start getter.
Definition: ekf.cpp:828
void PredictModel(double local_time)
Predict state to given time using IMU measurements.
Definition: ekf.cpp:124
unsigned int GetStateSize()
Getter for state size.
Definition: ekf.cpp:187
unsigned int GetCamCount()
Camera count getter method.
Definition: ekf.cpp:232
bool IsLlaInitialized()
Checks if the LLA reference frame has been initialized.
Definition: ekf.cpp:659
GpsState GetGpsState(unsigned int gps_id)
Get GPS sensor state.
Definition: ekf.cpp:197
void RegisterFiducial(const FidState &fid_state, const Eigen::MatrixXd &covariance)
Fiducial Registration function.
Definition: ekf.cpp:353
double GetReferenceAngle()
Getter for the LLA reference frame heading.
Definition: ekf.cpp:654
void RegisterCamera(unsigned int cam_id, const CamState &cam_state, const Eigen::MatrixXd &covariance)
Camera Registration function.
Definition: ekf.cpp:314
ImuState GetImuState(unsigned int imu_id)
Get IMU sensor state.
Definition: ekf.cpp:192
void LogBodyStateIfNeeded(int execution_count)
Check if body data should be logged and do so if necessary.
Definition: ekf.cpp:101
bool GetUseRootCovariance()
Getter for use root covariance flag.
Definition: ekf.cpp:853
unsigned int GetCamStateSize()
Camera state size getter method.
Definition: ekf.cpp:227
unsigned int GetCamStateStart()
Camera state start getter.
Definition: ekf.cpp:823
void Initialize(double timeInit, const BodyState &bodyStateInit)
EKF state initialization method.
Definition: ekf.cpp:242
void SetBodyProcessNoise(const Eigen::VectorXd &process_noise)
EKF process noise setter.
Definition: ekf.cpp:564
Eigen::VectorXd GetReferenceLLA()
Getter for the LLA reference position.
Definition: ekf.cpp:646
void RefreshIndices()
Refresh the sub-state indices.
Definition: ekf.cpp:674
double GetMotionDetectionChiSquared()
Motion detection Chi squared threshold getter.
Definition: ekf.cpp:843
unsigned int GetGpsCount()
IMU count getter method.
Definition: ekf.cpp:217
EKF(Parameters params)
EKF class constructor.
Definition: ekf.cpp:37
std::vector< Eigen::Vector3d > GetGpsXyzVector()
GPS XYZ vector getter.
Definition: ekf.cpp:808
Fiducial state structure.
Definition: types.hpp:303
GpsState structure.
Definition: types.hpp:168
ImuState structure.
Definition: types.hpp:114
EKF State Class.
Definition: types.hpp:343
EKF class parameters.
Definition: ekf.hpp:45
double gps_init_pos_thresh
Minimum ang projection error.
Definition: ekf.hpp:61
Eigen::VectorXd process_noise
Process noise.
Definition: ekf.hpp:54
AugmentationType augmenting_type
Augmenting type.
Definition: ekf.hpp:49
double augmenting_ang_error
Augmenting ang error.
Definition: ekf.hpp:52
double data_log_rate
Body data log rate.
Definition: ekf.hpp:47
std::shared_ptr< DebugLogger > debug_logger
Debug logger.
Definition: ekf.hpp:46
bool use_first_estimate_jacobian
Flag to use first estimate Jacobians.
Definition: ekf.hpp:66
Eigen::Quaterniond ang_b_to_l
Body local orientation.
Definition: ekf.hpp:56
double gps_init_baseline_dist
Minimum pos projection error.
Definition: ekf.hpp:60
double motion_detection_chi_squared
Motion detection chi squared threshold.
Definition: ekf.hpp:63
GpsInitType gps_init_type
GPS initialization type.
Definition: ekf.hpp:59
double imu_noise_scale_factor
Motion detection IMU noise scale factor.
Definition: ekf.hpp:64
double gps_init_ang_thresh
Baseline distance threshold.
Definition: ekf.hpp:62
double augmenting_pos_error
Augmenting pos error.
Definition: ekf.hpp:51
bool use_root_covariance
Flag to use the square-root form of Kalman filter.
Definition: ekf.hpp:65
Eigen::Vector3d pos_e_in_g
Local frame position.
Definition: ekf.hpp:57
std::string log_directory
Data log directory.
Definition: ekf.hpp:48
Eigen::Vector3d pos_b_in_l
Body local position.
Definition: ekf.hpp:55
double augmenting_delta_time
Augmenting time.
Definition: ekf.hpp:50
double ang_l_to_e
Local frame heading.
Definition: ekf.hpp:58