SaDVIO
Public Member Functions | Public Attributes | List of all members
isae::IMU Class Reference

An Inertial Measurement Unit (IMU) sensor class. More...

#include <IMU.h>

Inheritance diagram for isae::IMU:
Inheritance graph
[legend]
Collaboration diagram for isae::IMU:
Collaboration graph
[legend]

Public Member Functions

 IMU (Eigen::Vector3d acc, Eigen::Vector3d gyr)
 
 IMU (std::shared_ptr< imu_config > config, Eigen::Vector3d acc, Eigen::Vector3d gyr)
 
 ~IMU ()
 
Eigen::Vector3d getAcc ()
 
Eigen::Vector3d getGyr ()
 
void setBa (Eigen::Vector3d ba)
 
void setBg (Eigen::Vector3d bg)
 
void setDeltaP (const Eigen::Vector3d delta_p)
 
void setDeltaV (const Eigen::Vector3d delta_v)
 
void setDeltaR (const Eigen::Matrix3d delta_R)
 
void setVelocity (const Eigen::Vector3d v)
 
Eigen::Vector3d getBa ()
 
Eigen::Vector3d getBg ()
 
Eigen::Vector3d getDeltaP () const
 
Eigen::Vector3d getDeltaV () const
 
Eigen::Matrix3d getDeltaR () const
 
Eigen::Vector3d getVelocity () const
 
Eigen::MatrixXd getCov () const
 
double getGyrNoise () const
 
double getAccNoise () const
 
double getbGyrNoise () const
 
double getbAccNoise () const
 
void setLastKF (std::shared_ptr< Frame > frame)
 
std::shared_ptr< FramegetLastKF ()
 
void setLastIMU (std::shared_ptr< IMU > imu)
 
std::shared_ptr< IMUgetLastIMU ()
 
bool processIMU ()
 Process IMU data to compute pre integration deltas and covariances. More...
 
void estimateTransformIMU (Eigen::Affine3d &dT)
 Estimate the transformation between the Last KF and the current frame with pre integration deltas. More...
 
void biasDeltaCorrection (Eigen::Vector3d d_ba, Eigen::Vector3d d_bg)
 Update deltas with biases variations. More...
 
void updateBiases ()
 Update biases w.r.t the previous KF (e.g. after optimization) More...
 
- Public Member Functions inherited from isae::ASensor
 ASensor (std::string type)
 
 ~ASensor ()
 
std::string getType ()
 
void setFrame (std::shared_ptr< Frame > frame)
 
std::shared_ptr< FramegetFrame ()
 
void setFrame2SensorTransform (Eigen::Affine3d T_s_f)
 
Eigen::Affine3d getFrame2SensorTransform ()
 
Eigen::Affine3d getWorld2SensorTransform ()
 
Eigen::Affine3d getSensor2WorldTransform ()
 

Public Attributes

Eigen::Matrix3d _J_dR_bg
 Jacobian of the delta rotation w.r.t the gyro bias. More...
 
Eigen::Matrix3d _J_dv_ba
 Jacobian of the delta velocity w.r.t the accel bias. More...
 
Eigen::Matrix3d _J_dv_bg
 Jacobian of the delta velocity w.r.t the gyro bias. More...
 
Eigen::Matrix3d _J_dp_ba
 Jacobian of the delta position w.r.t the accel bias. More...
 
Eigen::Matrix3d _J_dp_bg
 Jacobian of the delta position w.r.t the gyro bias. More...
 
unsigned long long _timestamp_imu
 Timestamp stored to avoid dependency on the frame. More...
 
Eigen::Affine3d _T_w_f_imu
 Transform from the world to the frame to avoid dependency on the frame. More...
 

Additional Inherited Members

- Protected Attributes inherited from isae::ASensor
std::weak_ptr< Frame_frame
 
Eigen::Affine3d _T_s_f
 
std::string _type
 
std::mutex _sensor_mtx
 

Detailed Description

An Inertial Measurement Unit (IMU) sensor class.

This class represents an IMU sensor that provides acceleration and gyroscope measurements. It handles the preintegration of IMU data for use in SLAM systems.

Constructor & Destructor Documentation

◆ IMU() [1/2]

isae::IMU::IMU ( Eigen::Vector3d  acc,
Eigen::Vector3d  gyr 
)
inline

◆ IMU() [2/2]

isae::IMU::IMU ( std::shared_ptr< imu_config config,
Eigen::Vector3d  acc,
Eigen::Vector3d  gyr 
)
inline

◆ ~IMU()

isae::IMU::~IMU ( )
inline

Member Function Documentation

◆ biasDeltaCorrection()

void isae::IMU::biasDeltaCorrection ( Eigen::Vector3d  d_ba,
Eigen::Vector3d  d_bg 
)

Update deltas with biases variations.

◆ estimateTransformIMU()

void isae::IMU::estimateTransformIMU ( Eigen::Affine3d &  dT)

Estimate the transformation between the Last KF and the current frame with pre integration deltas.

◆ getAcc()

Eigen::Vector3d isae::IMU::getAcc ( )
inline

◆ getAccNoise()

double isae::IMU::getAccNoise ( ) const
inline

◆ getBa()

Eigen::Vector3d isae::IMU::getBa ( )
inline

◆ getbAccNoise()

double isae::IMU::getbAccNoise ( ) const
inline

◆ getBg()

Eigen::Vector3d isae::IMU::getBg ( )
inline

◆ getbGyrNoise()

double isae::IMU::getbGyrNoise ( ) const
inline

◆ getCov()

Eigen::MatrixXd isae::IMU::getCov ( ) const
inline

◆ getDeltaP()

Eigen::Vector3d isae::IMU::getDeltaP ( ) const
inline

◆ getDeltaR()

Eigen::Matrix3d isae::IMU::getDeltaR ( ) const
inline

◆ getDeltaV()

Eigen::Vector3d isae::IMU::getDeltaV ( ) const
inline

◆ getGyr()

Eigen::Vector3d isae::IMU::getGyr ( )
inline

◆ getGyrNoise()

double isae::IMU::getGyrNoise ( ) const
inline

◆ getLastIMU()

std::shared_ptr<IMU> isae::IMU::getLastIMU ( )
inline

◆ getLastKF()

std::shared_ptr<Frame> isae::IMU::getLastKF ( )
inline

◆ getVelocity()

Eigen::Vector3d isae::IMU::getVelocity ( ) const
inline

◆ processIMU()

bool isae::IMU::processIMU ( )

Process IMU data to compute pre integration deltas and covariances.

This function processes the IMU data to compute the deltas in position, velocity, and orientation on SO(3) It is based on "On-Manifold Preintegration for Real-Time Visual-Inertial Odometry" by Forster et al. Source: https://arxiv.org/abs/1512.02363

◆ setBa()

void isae::IMU::setBa ( Eigen::Vector3d  ba)
inline

◆ setBg()

void isae::IMU::setBg ( Eigen::Vector3d  bg)
inline

◆ setDeltaP()

void isae::IMU::setDeltaP ( const Eigen::Vector3d  delta_p)
inline

◆ setDeltaR()

void isae::IMU::setDeltaR ( const Eigen::Matrix3d  delta_R)
inline

◆ setDeltaV()

void isae::IMU::setDeltaV ( const Eigen::Vector3d  delta_v)
inline

◆ setLastIMU()

void isae::IMU::setLastIMU ( std::shared_ptr< IMU imu)
inline

◆ setLastKF()

void isae::IMU::setLastKF ( std::shared_ptr< Frame frame)
inline

◆ setVelocity()

void isae::IMU::setVelocity ( const Eigen::Vector3d  v)
inline

◆ updateBiases()

void isae::IMU::updateBiases ( )

Update biases w.r.t the previous KF (e.g. after optimization)

Member Data Documentation

◆ _J_dp_ba

Eigen::Matrix3d isae::IMU::_J_dp_ba

Jacobian of the delta position w.r.t the accel bias.

◆ _J_dp_bg

Eigen::Matrix3d isae::IMU::_J_dp_bg

Jacobian of the delta position w.r.t the gyro bias.

◆ _J_dR_bg

Eigen::Matrix3d isae::IMU::_J_dR_bg

Jacobian of the delta rotation w.r.t the gyro bias.

◆ _J_dv_ba

Eigen::Matrix3d isae::IMU::_J_dv_ba

Jacobian of the delta velocity w.r.t the accel bias.

◆ _J_dv_bg

Eigen::Matrix3d isae::IMU::_J_dv_bg

Jacobian of the delta velocity w.r.t the gyro bias.

◆ _T_w_f_imu

Eigen::Affine3d isae::IMU::_T_w_f_imu

Transform from the world to the frame to avoid dependency on the frame.

◆ _timestamp_imu

unsigned long long isae::IMU::_timestamp_imu

Timestamp stored to avoid dependency on the frame.


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