#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 |
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.
State::State | ( | StateOptions & | options_ | ) |
|
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
|
inline |
|
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.
|
inline |
|
inlinestatic |
|
friend |
std::shared_ptr<ov_type::Vec> ov_msckf::State::_calib_dt_CAMtoIMU |
std::shared_ptr<ov_type::JPLQuat> ov_msckf::State::_calib_imu_ACCtoIMU |
std::shared_ptr<ov_type::Vec> ov_msckf::State::_calib_imu_da |
std::shared_ptr<ov_type::Vec> ov_msckf::State::_calib_imu_dw |
std::shared_ptr<ov_type::JPLQuat> ov_msckf::State::_calib_imu_GYROtoIMU |
std::shared_ptr<ov_type::Vec> ov_msckf::State::_calib_imu_tg |
std::unordered_map<size_t, std::shared_ptr<ov_type::PoseJPL> > ov_msckf::State::_calib_IMUtoCAM |
std::unordered_map<size_t, std::shared_ptr<ov_type::Vec> > ov_msckf::State::_cam_intrinsics |
std::unordered_map<size_t, std::shared_ptr<ov_core::CamBase> > ov_msckf::State::_cam_intrinsics_cameras |
std::map<double, std::shared_ptr<ov_type::PoseJPL> > ov_msckf::State::_clones_IMU |
|
private |
std::unordered_map<size_t, std::shared_ptr<ov_type::Landmark> > ov_msckf::State::_features_SLAM |
std::shared_ptr<ov_type::IMU> ov_msckf::State::_imu |
std::mutex ov_msckf::State::_mutex_state |
StateOptions ov_msckf::State::_options |
double ov_msckf::State::_timestamp = -1 |
|
private |