Public Member Functions | Private Attributes | List of all members
ov_init::DynamicInitializer Class Reference

Initializer for a dynamic visual-inertial system. More...

#include <DynamicInitializer.h>

Public Member Functions

 DynamicInitializer (const InertialInitializerOptions &params_, std::shared_ptr< ov_core::FeatureDatabase > db, std::shared_ptr< std::vector< ov_core::ImuData >> imu_data_)
 Default constructor. More...
 
bool 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. 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...
 

Detailed Description

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:

  1. Preintegrate our system to get the relative rotation change (biases assumed known)
  2. Construct linear system with features to recover velocity (solve with |g| constraint)
  3. Perform a large MLE with all calibration and recover the covariance.

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.

Constructor & Destructor Documentation

◆ DynamicInitializer()

ov_init::DynamicInitializer::DynamicInitializer ( const InertialInitializerOptions params_,
std::shared_ptr< ov_core::FeatureDatabase db,
std::shared_ptr< std::vector< ov_core::ImuData >>  imu_data_ 
)
inlineexplicit

Default constructor.

Parameters
params_Parameters loaded from either ROS or CMDLINE
dbFeature 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.

Member Function Documentation

◆ initialize()

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.

Parameters
[out]timestampTimestamp we have initialized the state at (last imu state)
[out]covarianceCalculated covariance of the returned state
[out]orderOrder of the covariance matrix
_imuPointer to the "active" IMU state (q_GtoI, p_IinG, v_IinG, bg, ba)
_clones_IMUMap between imaging times and clone poses (q_GtoIi, p_IiinG)
_features_SLAMOur current set of SLAM features (3d positions)
Returns
True if we have successfully initialized our system

Definition at line 44 of file DynamicInitializer.cpp.

Member Data Documentation

◆ _db

std::shared_ptr<ov_core::FeatureDatabase> ov_init::DynamicInitializer::_db
private

Feature tracker database with all features in it.

Definition at line 94 of file DynamicInitializer.h.

◆ imu_data

std::shared_ptr<std::vector<ov_core::ImuData> > ov_init::DynamicInitializer::imu_data
private

Our history of IMU messages (time, angular, linear)

Definition at line 97 of file DynamicInitializer.h.

◆ params

InertialInitializerOptions ov_init::DynamicInitializer::params
private

Initialization parameters.

Definition at line 91 of file DynamicInitializer.h.


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


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