Inertial measurement unit (IMU) simulator class.
More...
#include <inertialMeasurementSim.hpp>
|
| 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...
|
| |
Inertial measurement unit (IMU) simulator class.
Definition at line 19 of file inertialMeasurementSim.hpp.
◆ inertialMeasurementSim()
| inertialMeasurementSim::inertialMeasurementSim |
( |
double |
accMeasNoiseVariance, |
|
|
double |
gyroMeasNoiseVariance, |
|
|
double |
accBiasProcessNoiseAutoCorrelation, |
|
|
double |
gyroBiasProcessNoiseAutoCorrelation |
|
) |
| |
Construct a new IMU Sim object.
- Parameters
-
| accMeasNoiseVariance | Accelerometer additive noise variance |
| gyroMeasNoiseVariance | Gyroscope additive noise variance |
| accBiasProcessNoiseAutoCorrelation | Accelerometer bias process noise auto correlation |
| gyroBiasProcessNoiseAutoCorrelation | Gyroscope bias process noise auto correlation |
Definition at line 18 of file inertialMeasurementSim.cpp.
◆ getMeasurement()
| void inertialMeasurementSim::getMeasurement |
( |
Eigen::Vector3d & |
accOutput, |
|
|
Eigen::Vector3d & |
gyroOutput, |
|
|
const Eigen::Vector3d |
specificForce, |
|
|
const Eigen::Vector3d |
angularVelocity |
|
) |
| |
Get IMU measurement.
- Parameters
-
| accOutput | Accelerometer output in IMU frame |
| gyroOutput | Gyroscope output in IMU frame |
| specificForce | Specific force in body-frame |
| angularVelocity | Angular velocity in body-frame |
Definition at line 116 of file inertialMeasurementSim.cpp.
◆ proceedBiasDynamics()
| void inertialMeasurementSim::proceedBiasDynamics |
( |
double |
dt_secs | ) |
|
◆ setBias() [1/3]
| void inertialMeasurementSim::setBias |
( |
const Eigen::Vector3d & |
accBias, |
|
|
const Eigen::Vector3d & |
gyroBias, |
|
|
double |
accBiasProcessNoiseAutoCorrelation, |
|
|
double |
gyroBiasProcessNoiseAutoCorrelation |
|
) |
| |
Set bias properties.
- Parameters
-
| accBias | Accelerometer bias value |
| gyroBias | Gyroscope bias value |
| accBiasProcessNoiseAutoCorrelation | Accelerometer bias process noise auto correlation |
| gyroBiasProcessNoiseAutoCorrelation | Gyroscope 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
-
| accBias | Accelerometer bias variance |
| gyroBias | Gyroscope 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
-
| accBias | Accelerometer bias variance |
| gyroBias | Gyroscope bias variance |
| accBiasProcessNoiseAutoCorrelation | Accelerometer bias process noise auto correlation |
| gyroBiasProcessNoiseAutoCorrelation | Gyroscope 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
-
| accMeasNoiseVariance | Accelerometer additive noise variance |
| gyroMeasNoiseVariance | Gyroscope 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
-
| imuOrient | IMU orientation with regard to body-frame |
Definition at line 104 of file inertialMeasurementSim.cpp.
◆ accBias_
| Eigen::Vector3d inertialMeasurementSim::accBias_ = Eigen::Vector3d::Zero() |
|
private |
◆ accBiasProcessNoiseAutoCorrelation_
| double inertialMeasurementSim::accBiasProcessNoiseAutoCorrelation_ = 0. |
|
private |
◆ accMeasNoiseVariance_
| double inertialMeasurementSim::accMeasNoiseVariance_ = 0. |
|
private |
◆ gyroBias_
| Eigen::Vector3d inertialMeasurementSim::gyroBias_ = Eigen::Vector3d::Zero() |
|
private |
◆ gyroBiasProcessNoiseAutoCorrelation_
| double inertialMeasurementSim::gyroBiasProcessNoiseAutoCorrelation_ = 0. |
|
private |
◆ gyroMeasNoiseVariance_
| double inertialMeasurementSim::gyroMeasNoiseVariance_ = 0. |
|
private |
◆ imuOrient_
◆ randomNumberGenerator_
| std::default_random_engine inertialMeasurementSim::randomNumberGenerator_ |
|
private |
◆ standardNormalDistribution_
| std::normal_distribution<double> inertialMeasurementSim::standardNormalDistribution_ = std::normal_distribution<double>(0.0,1.0) |
|
private |
The documentation for this class was generated from the following files: