Initializer for a dynamic visual-inertial system. More...
#include <DynamicInitializer.h>
Public Member Functions | |
DynamicInitializer (const InertialInitializerOptions ¶ms_, std::shared_ptr< ov_core::FeatureDatabase > db, std::shared_ptr< std::vector< ov_core::ImuData >> imu_data_) | |
Default constructor. More... | |
bool | initialize (double ×tamp, Eigen::MatrixXd &covariance, std::vector< std::shared_ptr< ov_type::Type >> &order, std::shared_ptr< ov_type::IMU > &_imu, std::map< double, std::shared_ptr< ov_type::PoseJPL >> &_clones_IMU, std::unordered_map< size_t, std::shared_ptr< ov_type::Landmark >> &_features_SLAM) |
Try to get the initialized system. More... | |
Private Attributes | |
std::shared_ptr< ov_core::FeatureDatabase > | _db |
Feature tracker database with all features in it. More... | |
std::shared_ptr< std::vector< ov_core::ImuData > > | imu_data |
Our history of IMU messages (time, angular, linear) More... | |
InertialInitializerOptions | params |
Initialization parameters. More... | |
Initializer for a dynamic visual-inertial system.
This implementation that will try to recover the initial conditions of the system. Additionally, we will try to recover the covariance of the system. To initialize with arbitrary motion:
Method is based on this work (see this tech report for a high level walk through):
Dong-Si, Tue-Cuong, and Anastasios I. Mourikis. "Estimator initialization in vision-aided inertial navigation with unknown camera-IMU calibration." 2012 IEEE/RSJ International Conference on Intelligent Robots and Systems. IEEE, 2012.
Definition at line 62 of file DynamicInitializer.h.
|
inlineexplicit |
Default constructor.
params_ | Parameters loaded from either ROS or CMDLINE |
db | Feature tracker database with all features in it |
imu_data_ | Shared pointer to our IMU vector of historical information |
Definition at line 70 of file DynamicInitializer.h.
bool DynamicInitializer::initialize | ( | double & | timestamp, |
Eigen::MatrixXd & | covariance, | ||
std::vector< std::shared_ptr< ov_type::Type >> & | order, | ||
std::shared_ptr< ov_type::IMU > & | _imu, | ||
std::map< double, std::shared_ptr< ov_type::PoseJPL >> & | _clones_IMU, | ||
std::unordered_map< size_t, std::shared_ptr< ov_type::Landmark >> & | _features_SLAM | ||
) |
Try to get the initialized system.
[out] | timestamp | Timestamp we have initialized the state at (last imu state) |
[out] | covariance | Calculated covariance of the returned state |
[out] | order | Order of the covariance matrix |
_imu | Pointer to the "active" IMU state (q_GtoI, p_IinG, v_IinG, bg, ba) | |
_clones_IMU | Map between imaging times and clone poses (q_GtoIi, p_IiinG) | |
_features_SLAM | Our current set of SLAM features (3d positions) |
Definition at line 44 of file DynamicInitializer.cpp.
|
private |
Feature tracker database with all features in it.
Definition at line 94 of file DynamicInitializer.h.
|
private |
Our history of IMU messages (time, angular, linear)
Definition at line 97 of file DynamicInitializer.h.
|
private |
Initialization parameters.
Definition at line 91 of file DynamicInitializer.h.