19 double accBiasProcessNoiseAutoCorrelation,
double gyroBiasProcessNoiseAutoCorrelation){
39 double accBiasProcessNoiseAutoCorrelation,
40 double gyroBiasProcessNoiseAutoCorrelation){
56 double accBiasProcessNoiseAutoCorrelation,
57 double gyroBiasProcessNoiseAutoCorrelation){
117 const Eigen::Vector3d specificForce,
const Eigen::Vector3d angularVelocity){
119 Eigen::Vector3d accNoise;
125 Eigen::Vector3d gyroNoise;
141 Eigen::Vector3d accBiasDerivative;
147 Eigen::Vector3d gyroBiasDerivative;
153 accBias_ += dt_secs*accBiasDerivative;
std::default_random_engine randomNumberGenerator_
Eigen::Vector3d gyroBias_
inertialMeasurementSim(double accMeasNoiseVariance, double gyroMeasNoiseVariance, double accBiasProcessNoiseAutoCorrelation, double gyroBiasProcessNoiseAutoCorrelation)
Construct a new IMU Sim object.
void setOrientation(const Eigen::Quaterniond &imuOrient)
Set IMU orientation with regard to body-frame.
void proceedBiasDynamics(double dt_secs)
Proceed accelerometer and gyroscope bias dynamics.
double gyroMeasNoiseVariance_
double gyroBiasProcessNoiseAutoCorrelation_
void setBias(const Eigen::Vector3d &accBias, const Eigen::Vector3d &gyroBias, double accBiasProcessNoiseAutoCorrelation, double gyroBiasProcessNoiseAutoCorrelation)
Set bias properties.
double accBiasProcessNoiseAutoCorrelation_
std::normal_distribution< double > standardNormalDistribution_
void setNoiseVariance(double accMeasNoiseVariance, double gyroMeasNoiseVariance)
Set additive noise variances.
Eigen::Quaterniond imuOrient_
double accMeasNoiseVariance_
double time_since_epoch()
Inertial measurement unit (IMU) simulator class header file.
void getMeasurement(Eigen::Vector3d &accOutput, Eigen::Vector3d &gyroOutput, const Eigen::Vector3d specificForce, const Eigen::Vector3d angularVelocity)
Get IMU measurement.