Public Member Functions | Protected Attributes | List of all members
ov_init::InertialInitializer Class Reference

Initializer for visual-inertial system. More...

#include <InertialInitializer.h>

Public Member Functions

void feed_imu (const ov_core::ImuData &message, double oldest_time=-1)
 Feed function for inertial data. More...
 
 InertialInitializer (InertialInitializerOptions &params_, std::shared_ptr< ov_core::FeatureDatabase > db)
 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 > t_imu, bool wait_for_jerk=true)
 Try to get the initialized system. More...
 

Protected 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...
 
std::shared_ptr< DynamicInitializerinit_dynamic
 Dynamic initialization helper class. More...
 
std::shared_ptr< StaticInitializerinit_static
 Static initialization helper class. More...
 
InertialInitializerOptions params
 Initialization parameters. More...
 

Detailed Description

Initializer for visual-inertial system.

This will try to do both dynamic and state initialization of the state. The user can request to wait for a jump in our IMU readings (i.e. device is picked up) or to initialize as soon as possible. For state initialization, the user needs to specify the calibration beforehand, otherwise dynamic is always used. The logic is as follows:

  1. Try to perform dynamic initialization of state elements.
  2. If this fails and we have calibration then we can try to do static initialization
  3. If the unit is stationary and we are waiting for a jerk, just return, otherwise initialize the state!

The dynamic system is based on an implementation and extension of the work Estimator initialization in vision-aided inertial navigation with unknown camera-IMU calibration [Dong2012IROS] which solves the initialization problem by first creating a linear system for recovering the camera to IMU rotation, then for velocity, gravity, and feature positions, and finally a full optimization to allow for covariance recovery. Another paper which might be of interest to the reader is An Analytical Solution to the IMU Initialization Problem for Visual-Inertial Systems which has some detailed experiments on scale recovery and the accelerometer bias.

Definition at line 60 of file InertialInitializer.h.

Constructor & Destructor Documentation

◆ InertialInitializer()

InertialInitializer::InertialInitializer ( InertialInitializerOptions params_,
std::shared_ptr< ov_core::FeatureDatabase db 
)
explicit

Default constructor.

Parameters
params_Parameters loaded from either ROS or CMDLINE
dbFeature tracker database with all features in it

Definition at line 38 of file InertialInitializer.cpp.

Member Function Documentation

◆ feed_imu()

void InertialInitializer::feed_imu ( const ov_core::ImuData message,
double  oldest_time = -1 
)

Feed function for inertial data.

Parameters
messageContains our timestamp and inertial information
oldest_timeTime that we can discard measurements before

Definition at line 49 of file InertialInitializer.cpp.

◆ initialize()

bool InertialInitializer::initialize ( double &  timestamp,
Eigen::MatrixXd &  covariance,
std::vector< std::shared_ptr< ov_type::Type >> &  order,
std::shared_ptr< ov_type::IMU t_imu,
bool  wait_for_jerk = true 
)

Try to get the initialized system.

@m_class{m-note m-warning}

Processing Cost
This is a serial process that can take on orders of seconds to complete. If you are a real-time application then you will likely want to call this from a async thread which allows for this to process in the background. The features used are cloned from the feature database thus should be thread-safe to continue to append new feature tracks to the database.
Parameters
[out]timestampTimestamp we have initialized the state at
[out]covarianceCalculated covariance of the returned state
[out]orderOrder of the covariance matrix
[out]t_imuOur imu type (need to have correct ids)
wait_for_jerkIf true we will wait for a "jerk"
Returns
True if we have successfully initialized our system

Definition at line 73 of file InertialInitializer.cpp.

Member Data Documentation

◆ _db

std::shared_ptr<ov_core::FeatureDatabase> ov_init::InertialInitializer::_db
protected

Feature tracker database with all features in it.

Definition at line 105 of file InertialInitializer.h.

◆ imu_data

std::shared_ptr<std::vector<ov_core::ImuData> > ov_init::InertialInitializer::imu_data
protected

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

Definition at line 108 of file InertialInitializer.h.

◆ init_dynamic

std::shared_ptr<DynamicInitializer> ov_init::InertialInitializer::init_dynamic
protected

Dynamic initialization helper class.

Definition at line 114 of file InertialInitializer.h.

◆ init_static

std::shared_ptr<StaticInitializer> ov_init::InertialInitializer::init_static
protected

Static initialization helper class.

Definition at line 111 of file InertialInitializer.h.

◆ params

InertialInitializerOptions ov_init::InertialInitializer::params
protected

Initialization parameters.

Definition at line 102 of file InertialInitializer.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