inertialMeasurementSim.hpp
Go to the documentation of this file.
1 
8 #ifndef INERTIALMEASUREMENTSIM_H
9 #define INERTIALMEASUREMENTSIM_H
10 
11 #include <Eigen/Dense>
12 #include <Eigen/Geometry>
13 #include <random>
14 
20 {
21  public:
22  inertialMeasurementSim(double accMeasNoiseVariance, double gyroMeasNoiseVariance,
23  double accBiasProcessNoiseAutoCorrelation, double gyroBiasProcessNoiseAutoCorrelation);
24 
25  void setBias(const Eigen::Vector3d & accBias, const Eigen::Vector3d & gyroBias,
26  double accBiasProcessNoiseAutoCorrelation,
27  double gyroBiasProcessNoiseAutoCorrelation);
28  void setBias(double accBiasVariance, double gyroBiasVariance,
29  double accBiasProcessNoiseAutoCorrelation,
30  double gyroBiasProcessNoiseAutoCorrelation);
31 
32  void setBias(double accBiasVariance, double gyroBiasVariance);
33 
34  void setNoiseVariance(double accMeasNoiseVariance, double gyroMeasNoiseVariance);
35 
36  void setOrientation(const Eigen::Quaterniond & imuOrient);
37 
38  void getMeasurement(Eigen::Vector3d & accOutput, Eigen::Vector3d & gyroOutput,
39  const Eigen::Vector3d specificForce, const Eigen::Vector3d angularVelocity);
40 
41  void proceedBiasDynamics(double dt_secs);
42 
43  private:
45 
46  std::default_random_engine randomNumberGenerator_;
47  std::normal_distribution<double> standardNormalDistribution_ = std::normal_distribution<double>(0.0,1.0);
49 
51 
52  double accMeasNoiseVariance_ = 0.; // m^2/s^4
53  double gyroMeasNoiseVariance_ = 0.; // rad^2/s^2
55 
57 
58  double accBiasProcessNoiseAutoCorrelation_ = 0.; // m^2/s^5
59  double gyroBiasProcessNoiseAutoCorrelation_ = 0.; // rad^2/s^3
61 
63 
64  Eigen::Vector3d accBias_ = Eigen::Vector3d::Zero(); // m/s^2
65  Eigen::Vector3d gyroBias_ = Eigen::Vector3d::Zero(); // rad/s
67 
69 
70  Eigen::Quaterniond imuOrient_ = Eigen::Quaterniond::Identity();
72 };
73 
74 #endif // INERTIALMEASUREMENTSIM_H
inertialMeasurementSim::setNoiseVariance
void setNoiseVariance(double accMeasNoiseVariance, double gyroMeasNoiseVariance)
Set additive noise variances.
Definition: inertialMeasurementSim.cpp:94
inertialMeasurementSim::gyroBiasProcessNoiseAutoCorrelation_
double gyroBiasProcessNoiseAutoCorrelation_
Definition: inertialMeasurementSim.hpp:59
inertialMeasurementSim::imuOrient_
Eigen::Quaterniond imuOrient_
Definition: inertialMeasurementSim.hpp:70
inertialMeasurementSim::accBiasProcessNoiseAutoCorrelation_
double accBiasProcessNoiseAutoCorrelation_
Definition: inertialMeasurementSim.hpp:58
inertialMeasurementSim::setBias
void setBias(const Eigen::Vector3d &accBias, const Eigen::Vector3d &gyroBias, double accBiasProcessNoiseAutoCorrelation, double gyroBiasProcessNoiseAutoCorrelation)
Set bias properties.
Definition: inertialMeasurementSim.cpp:38
inertialMeasurementSim::accMeasNoiseVariance_
double accMeasNoiseVariance_
Definition: inertialMeasurementSim.hpp:52
inertialMeasurementSim::standardNormalDistribution_
std::normal_distribution< double > standardNormalDistribution_
Definition: inertialMeasurementSim.hpp:47
inertialMeasurementSim::gyroBias_
Eigen::Vector3d gyroBias_
Definition: inertialMeasurementSim.hpp:65
inertialMeasurementSim::getMeasurement
void getMeasurement(Eigen::Vector3d &accOutput, Eigen::Vector3d &gyroOutput, const Eigen::Vector3d specificForce, const Eigen::Vector3d angularVelocity)
Get IMU measurement.
Definition: inertialMeasurementSim.cpp:116
inertialMeasurementSim::randomNumberGenerator_
std::default_random_engine randomNumberGenerator_
Definition: inertialMeasurementSim.hpp:46
inertialMeasurementSim::setOrientation
void setOrientation(const Eigen::Quaterniond &imuOrient)
Set IMU orientation with regard to body-frame.
Definition: inertialMeasurementSim.cpp:104
inertialMeasurementSim::inertialMeasurementSim
inertialMeasurementSim(double accMeasNoiseVariance, double gyroMeasNoiseVariance, double accBiasProcessNoiseAutoCorrelation, double gyroBiasProcessNoiseAutoCorrelation)
Construct a new IMU Sim object.
Definition: inertialMeasurementSim.cpp:18
inertialMeasurementSim::gyroMeasNoiseVariance_
double gyroMeasNoiseVariance_
Definition: inertialMeasurementSim.hpp:53
inertialMeasurementSim
Inertial measurement unit (IMU) simulator class.
Definition: inertialMeasurementSim.hpp:19
inertialMeasurementSim::accBias_
Eigen::Vector3d accBias_
Definition: inertialMeasurementSim.hpp:64
inertialMeasurementSim::proceedBiasDynamics
void proceedBiasDynamics(double dt_secs)
Proceed accelerometer and gyroscope bias dynamics.
Definition: inertialMeasurementSim.cpp:140


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