Public Member Functions | List of all members
inertialMeasurementSim Class Reference

Inertial measurement unit (IMU) simulator class. More...

#include <inertialMeasurementSim.hpp>

Public Member Functions

void getMeasurement (Eigen::Vector3d &accOutput, Eigen::Vector3d &gyroOutput, const Eigen::Vector3d specificForce, const Eigen::Vector3d angularVelocity)
 Get IMU measurement. More...
 
 inertialMeasurementSim (double accMeasNoiseVariance, double gyroMeasNoiseVariance, double accBiasProcessNoiseAutoCorrelation, double gyroBiasProcessNoiseAutoCorrelation)
 Construct a new IMU Sim object. More...
 
void proceedBiasDynamics (double dt_secs)
 Proceed accelerometer and gyroscope bias dynamics. More...
 
void setBias (const Eigen::Vector3d &accBias, const Eigen::Vector3d &gyroBias, double accBiasProcessNoiseAutoCorrelation, double gyroBiasProcessNoiseAutoCorrelation)
 Set bias properties. More...
 
void setBias (double accBiasVariance, double gyroBiasVariance)
 Set bias. More...
 
void setBias (double accBiasVariance, double gyroBiasVariance, double accBiasProcessNoiseAutoCorrelation, double gyroBiasProcessNoiseAutoCorrelation)
 Set bias properties. More...
 
void setNoiseVariance (double accMeasNoiseVariance, double gyroMeasNoiseVariance)
 Set additive noise variances. More...
 
void setOrientation (const Eigen::Quaterniond &imuOrient)
 Set IMU orientation with regard to body-frame. More...
 

Private Attributes

Std normal RNG
std::default_random_engine randomNumberGenerator_
 
std::normal_distribution< double > standardNormalDistribution_ = std::normal_distribution<double>(0.0,1.0)
 
Measurement noise variance
double accMeasNoiseVariance_ = 0.
 
double gyroMeasNoiseVariance_ = 0.
 
Bias dynamics process noise auto correlation
double accBiasProcessNoiseAutoCorrelation_ = 0.
 
double gyroBiasProcessNoiseAutoCorrelation_ = 0.
 
Bias states
Eigen::Vector3d accBias_ = Eigen::Vector3d::Zero()
 
Eigen::Vector3d gyroBias_ = Eigen::Vector3d::Zero()
 
Orientation of IMU wrt body-fixed frame
Eigen::Quaterniond imuOrient_ = Eigen::Quaterniond::Identity()
 

Detailed Description

Inertial measurement unit (IMU) simulator class.

Definition at line 19 of file inertialMeasurementSim.hpp.

Constructor & Destructor Documentation

◆ inertialMeasurementSim()

inertialMeasurementSim::inertialMeasurementSim ( double  accMeasNoiseVariance,
double  gyroMeasNoiseVariance,
double  accBiasProcessNoiseAutoCorrelation,
double  gyroBiasProcessNoiseAutoCorrelation 
)

Construct a new IMU Sim object.

Parameters
accMeasNoiseVarianceAccelerometer additive noise variance
gyroMeasNoiseVarianceGyroscope additive noise variance
accBiasProcessNoiseAutoCorrelationAccelerometer bias process noise auto correlation
gyroBiasProcessNoiseAutoCorrelationGyroscope bias process noise auto correlation

Definition at line 18 of file inertialMeasurementSim.cpp.

Member Function Documentation

◆ getMeasurement()

void inertialMeasurementSim::getMeasurement ( Eigen::Vector3d &  accOutput,
Eigen::Vector3d &  gyroOutput,
const Eigen::Vector3d  specificForce,
const Eigen::Vector3d  angularVelocity 
)

Get IMU measurement.

Parameters
accOutputAccelerometer output in IMU frame
gyroOutputGyroscope output in IMU frame
specificForceSpecific force in body-frame
angularVelocityAngular velocity in body-frame

Definition at line 116 of file inertialMeasurementSim.cpp.

◆ proceedBiasDynamics()

void inertialMeasurementSim::proceedBiasDynamics ( double  dt_secs)

Proceed accelerometer and gyroscope bias dynamics.

Parameters
dt_secsTime step

Definition at line 140 of file inertialMeasurementSim.cpp.

◆ setBias() [1/3]

void inertialMeasurementSim::setBias ( const Eigen::Vector3d &  accBias,
const Eigen::Vector3d &  gyroBias,
double  accBiasProcessNoiseAutoCorrelation,
double  gyroBiasProcessNoiseAutoCorrelation 
)

Set bias properties.

Parameters
accBiasAccelerometer bias value
gyroBiasGyroscope bias value
accBiasProcessNoiseAutoCorrelationAccelerometer bias process noise auto correlation
gyroBiasProcessNoiseAutoCorrelationGyroscope bias process noise auto correlation

Definition at line 38 of file inertialMeasurementSim.cpp.

◆ setBias() [2/3]

void inertialMeasurementSim::setBias ( double  accBiasVariance,
double  gyroBiasVariance 
)

Set bias.

Parameters
accBiasAccelerometer bias variance
gyroBiasGyroscope bias variance

Definition at line 77 of file inertialMeasurementSim.cpp.

◆ setBias() [3/3]

void inertialMeasurementSim::setBias ( double  accBiasVariance,
double  gyroBiasVariance,
double  accBiasProcessNoiseAutoCorrelation,
double  gyroBiasProcessNoiseAutoCorrelation 
)

Set bias properties.

Parameters
accBiasAccelerometer bias variance
gyroBiasGyroscope bias variance
accBiasProcessNoiseAutoCorrelationAccelerometer bias process noise auto correlation
gyroBiasProcessNoiseAutoCorrelationGyroscope bias process noise auto correlation

Definition at line 55 of file inertialMeasurementSim.cpp.

◆ setNoiseVariance()

void inertialMeasurementSim::setNoiseVariance ( double  accMeasNoiseVariance,
double  gyroMeasNoiseVariance 
)

Set additive noise variances.

Parameters
accMeasNoiseVarianceAccelerometer additive noise variance
gyroMeasNoiseVarianceGyroscope additive noise variance

Definition at line 94 of file inertialMeasurementSim.cpp.

◆ setOrientation()

void inertialMeasurementSim::setOrientation ( const Eigen::Quaterniond &  imuOrient)

Set IMU orientation with regard to body-frame.

Parameters
imuOrientIMU orientation with regard to body-frame

Definition at line 104 of file inertialMeasurementSim.cpp.

Member Data Documentation

◆ accBias_

Eigen::Vector3d inertialMeasurementSim::accBias_ = Eigen::Vector3d::Zero()
private

Definition at line 64 of file inertialMeasurementSim.hpp.

◆ accBiasProcessNoiseAutoCorrelation_

double inertialMeasurementSim::accBiasProcessNoiseAutoCorrelation_ = 0.
private

Definition at line 58 of file inertialMeasurementSim.hpp.

◆ accMeasNoiseVariance_

double inertialMeasurementSim::accMeasNoiseVariance_ = 0.
private

Definition at line 52 of file inertialMeasurementSim.hpp.

◆ gyroBias_

Eigen::Vector3d inertialMeasurementSim::gyroBias_ = Eigen::Vector3d::Zero()
private

Definition at line 65 of file inertialMeasurementSim.hpp.

◆ gyroBiasProcessNoiseAutoCorrelation_

double inertialMeasurementSim::gyroBiasProcessNoiseAutoCorrelation_ = 0.
private

Definition at line 59 of file inertialMeasurementSim.hpp.

◆ gyroMeasNoiseVariance_

double inertialMeasurementSim::gyroMeasNoiseVariance_ = 0.
private

Definition at line 53 of file inertialMeasurementSim.hpp.

◆ imuOrient_

Eigen::Quaterniond inertialMeasurementSim::imuOrient_ = Eigen::Quaterniond::Identity()
private

Definition at line 70 of file inertialMeasurementSim.hpp.

◆ randomNumberGenerator_

std::default_random_engine inertialMeasurementSim::randomNumberGenerator_
private

Definition at line 46 of file inertialMeasurementSim.hpp.

◆ standardNormalDistribution_

std::normal_distribution<double> inertialMeasurementSim::standardNormalDistribution_ = std::normal_distribution<double>(0.0,1.0)
private

Definition at line 47 of file inertialMeasurementSim.hpp.


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


inno_vtol_dynamics
Author(s): Roman Fedorenko, Dmitry Ponomarev, Ezra Tal, Winter Guerra
autogenerated on Mon Dec 9 2024 03:13:35