Public Member Functions | Static Public Member Functions | Public Attributes | Private Attributes | Friends | List of all members
ov_msckf::State Class Reference

State of our filter. More...

#include <State.h>

Public Member Functions

int imu_intrinsic_size () const
 Calculates the error state size for imu intrinsics. More...
 
double margtimestep ()
 Will return the timestep that we will marginalize next. As of right now, since we are using a sliding window, this is the oldest clone. But if you wanted to do a keyframe system, you could selectively marginalize clones. More...
 
int max_covariance_size ()
 Calculates the current max size of the covariance. More...
 
 State (StateOptions &options_)
 Default Constructor (will initialize variables to defaults) More...
 
 ~State ()
 

Static Public Member Functions

static Eigen::Matrix3d Dm (StateOptions::ImuModel imu_model, const Eigen::MatrixXd &vec)
 Gyroscope and accelerometer intrinsic matrix (scale imperfection and axis misalignment) More...
 
static Eigen::Matrix3d Tg (const Eigen::MatrixXd &vec)
 Gyroscope gravity sensitivity. More...
 

Public Attributes

std::shared_ptr< ov_type::Vec_calib_dt_CAMtoIMU
 Time offset base IMU to camera (t_imu = t_cam + t_off) More...
 
std::shared_ptr< ov_type::JPLQuat_calib_imu_ACCtoIMU
 Rotation from accelerometer to the "IMU" gyroscope frame frame (rpng model) More...
 
std::shared_ptr< ov_type::Vec_calib_imu_da
 Accelerometer IMU intrinsics (scale imperfection and axis misalignment) More...
 
std::shared_ptr< ov_type::Vec_calib_imu_dw
 Gyroscope IMU intrinsics (scale imperfection and axis misalignment) More...
 
std::shared_ptr< ov_type::JPLQuat_calib_imu_GYROtoIMU
 Rotation from gyroscope frame to the "IMU" accelerometer frame (kalibr model) More...
 
std::shared_ptr< ov_type::Vec_calib_imu_tg
 Gyroscope gravity sensitivity. More...
 
std::unordered_map< size_t, std::shared_ptr< ov_type::PoseJPL > > _calib_IMUtoCAM
 Calibration poses for each camera (R_ItoC, p_IinC) More...
 
std::unordered_map< size_t, std::shared_ptr< ov_type::Vec > > _cam_intrinsics
 Camera intrinsics. More...
 
std::unordered_map< size_t, std::shared_ptr< ov_core::CamBase > > _cam_intrinsics_cameras
 Camera intrinsics camera objects. More...
 
std::map< double, std::shared_ptr< ov_type::PoseJPL > > _clones_IMU
 Map between imaging times and clone poses (q_GtoIi, p_IiinG) More...
 
std::unordered_map< size_t, std::shared_ptr< ov_type::Landmark > > _features_SLAM
 Our current set of SLAM features (3d positions) More...
 
std::shared_ptr< ov_type::IMU_imu
 Pointer to the "active" IMU state (q_GtoI, p_IinG, v_IinG, bg, ba) More...
 
std::mutex _mutex_state
 Mutex for locking access to the state. More...
 
StateOptions _options
 Struct containing filter options. More...
 
double _timestamp = -1
 Current timestamp (should be the last update time in camera clock frame!) More...
 

Private Attributes

Eigen::MatrixXd _Cov
 Covariance of all active variables. More...
 
std::vector< std::shared_ptr< ov_type::Type > > _variables
 Vector of variables. More...
 

Friends

class StateHelper
 

Detailed Description

State of our filter.

This state has all the current estimates for the filter. This system is modeled after the MSCKF filter, thus we have a sliding window of clones. We additionally have more parameters for online estimation of calibration and SLAM features. We also have the covariance of the system, which should be managed using the StateHelper class.

Definition at line 49 of file State.h.

Constructor & Destructor Documentation

◆ State()

State::State ( StateOptions options_)

Default Constructor (will initialize variables to defaults)

Parameters
options_Options structure containing filter options

Definition at line 28 of file State.cpp.

◆ ~State()

ov_msckf::State::~State ( )
inline

Definition at line 58 of file State.h.

Member Function Documentation

◆ Dm()

static Eigen::Matrix3d ov_msckf::State::Dm ( StateOptions::ImuModel  imu_model,
const Eigen::MatrixXd &  vec 
)
inlinestatic

Gyroscope and accelerometer intrinsic matrix (scale imperfection and axis misalignment)

If kalibr model, lower triangular of the matrix is used If rpng model, upper triangular of the matrix is used

Returns
3x3 matrix of current imu gyroscope / accelerometer intrinsics

Definition at line 91 of file State.h.

◆ imu_intrinsic_size()

int ov_msckf::State::imu_intrinsic_size ( ) const
inline

Calculates the error state size for imu intrinsics.

This is used to construct our state transition which depends on if we are estimating calibration. 15 if doing intrinsics, another +9 if doing grav sensitivity

Returns
size of error state

Definition at line 126 of file State.h.

◆ margtimestep()

double ov_msckf::State::margtimestep ( )
inline

Will return the timestep that we will marginalize next. As of right now, since we are using a sliding window, this is the oldest clone. But if you wanted to do a keyframe system, you could selectively marginalize clones.

Returns
timestep of clone we will marginalize

Definition at line 66 of file State.h.

◆ max_covariance_size()

int ov_msckf::State::max_covariance_size ( )
inline

Calculates the current max size of the covariance.

Returns
Size of the current covariance matrix

Definition at line 81 of file State.h.

◆ Tg()

static Eigen::Matrix3d ov_msckf::State::Tg ( const Eigen::MatrixXd &  vec)
inlinestatic

Gyroscope gravity sensitivity.

For both kalibr and rpng models, this a 3x3 that is column-wise filled.

Returns
3x3 matrix of current gravity sensitivity

Definition at line 110 of file State.h.

Friends And Related Function Documentation

◆ StateHelper

friend class StateHelper
friend

Definition at line 186 of file State.h.

Member Data Documentation

◆ _calib_dt_CAMtoIMU

std::shared_ptr<ov_type::Vec> ov_msckf::State::_calib_dt_CAMtoIMU

Time offset base IMU to camera (t_imu = t_cam + t_off)

Definition at line 156 of file State.h.

◆ _calib_imu_ACCtoIMU

std::shared_ptr<ov_type::JPLQuat> ov_msckf::State::_calib_imu_ACCtoIMU

Rotation from accelerometer to the "IMU" gyroscope frame frame (rpng model)

Definition at line 180 of file State.h.

◆ _calib_imu_da

std::shared_ptr<ov_type::Vec> ov_msckf::State::_calib_imu_da

Accelerometer IMU intrinsics (scale imperfection and axis misalignment)

Definition at line 171 of file State.h.

◆ _calib_imu_dw

std::shared_ptr<ov_type::Vec> ov_msckf::State::_calib_imu_dw

Gyroscope IMU intrinsics (scale imperfection and axis misalignment)

Definition at line 168 of file State.h.

◆ _calib_imu_GYROtoIMU

std::shared_ptr<ov_type::JPLQuat> ov_msckf::State::_calib_imu_GYROtoIMU

Rotation from gyroscope frame to the "IMU" accelerometer frame (kalibr model)

Definition at line 177 of file State.h.

◆ _calib_imu_tg

std::shared_ptr<ov_type::Vec> ov_msckf::State::_calib_imu_tg

Gyroscope gravity sensitivity.

Definition at line 174 of file State.h.

◆ _calib_IMUtoCAM

std::unordered_map<size_t, std::shared_ptr<ov_type::PoseJPL> > ov_msckf::State::_calib_IMUtoCAM

Calibration poses for each camera (R_ItoC, p_IinC)

Definition at line 159 of file State.h.

◆ _cam_intrinsics

std::unordered_map<size_t, std::shared_ptr<ov_type::Vec> > ov_msckf::State::_cam_intrinsics

Camera intrinsics.

Definition at line 162 of file State.h.

◆ _cam_intrinsics_cameras

std::unordered_map<size_t, std::shared_ptr<ov_core::CamBase> > ov_msckf::State::_cam_intrinsics_cameras

Camera intrinsics camera objects.

Definition at line 165 of file State.h.

◆ _clones_IMU

std::map<double, std::shared_ptr<ov_type::PoseJPL> > ov_msckf::State::_clones_IMU

Map between imaging times and clone poses (q_GtoIi, p_IiinG)

Definition at line 150 of file State.h.

◆ _Cov

Eigen::MatrixXd ov_msckf::State::_Cov
private

Covariance of all active variables.

Definition at line 189 of file State.h.

◆ _features_SLAM

std::unordered_map<size_t, std::shared_ptr<ov_type::Landmark> > ov_msckf::State::_features_SLAM

Our current set of SLAM features (3d positions)

Definition at line 153 of file State.h.

◆ _imu

std::shared_ptr<ov_type::IMU> ov_msckf::State::_imu

Pointer to the "active" IMU state (q_GtoI, p_IinG, v_IinG, bg, ba)

Definition at line 147 of file State.h.

◆ _mutex_state

std::mutex ov_msckf::State::_mutex_state

Mutex for locking access to the state.

Definition at line 138 of file State.h.

◆ _options

StateOptions ov_msckf::State::_options

Struct containing filter options.

Definition at line 144 of file State.h.

◆ _timestamp

double ov_msckf::State::_timestamp = -1

Current timestamp (should be the last update time in camera clock frame!)

Definition at line 141 of file State.h.

◆ _variables

std::vector<std::shared_ptr<ov_type::Type> > ov_msckf::State::_variables
private

Vector of variables.

Definition at line 192 of file State.h.


The documentation for this class was generated from the following files:


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