IMUParameters
struct gazebo::IMUParameters
¶
IMUParameters stores all IMU model parameters. A description of these parameters can be found here: https://github.com/ethz-asl/kalibr/wiki/IMU-Noise-Model-and-Intrinsics.
Summary¶
Members | Descriptions |
---|---|
public double gyroscopeNoiseDensity |
Gyroscope noise density (two-sided spectrum) [rad/s/sqrt(Hz)]. |
public double gyroscopeRandomWalk |
Gyroscope bias random walk [rad/s/s/sqrt(Hz)]. |
public double gyroscopeBiasCorrelationTime |
Gyroscope bias correlation time constant [s]. |
public double gyroscopeTurnOnBiasSigma |
Gyroscope turn on bias standard deviation [rad/s]. |
public double accelerometerNoiseDensity |
Accelerometer noise density (two-sided spectrum) [m/s^2/sqrt(Hz)]. |
public double accelerometerRandomWalk |
Accelerometer bias random walk. [m/s^2/s/sqrt(Hz)]. |
public double accelerometerBiasCorrelationTime |
Accelerometer bias correlation time constant [s]. |
public double accelerometerTurnOnBiasSigma |
Accelerometer turn on bias standard deviation [m/s^2]. |
public double orientationNoise |
Standard deviation of orientation noise per axis [rad]. |
public inline IMUParameters () |
Constructor. |
Members¶
public double
gyroscopeNoiseDensity
¶
Gyroscope noise density (two-sided spectrum) [rad/s/sqrt(Hz)].
public double
gyroscopeRandomWalk
¶
Gyroscope bias random walk [rad/s/s/sqrt(Hz)].
public double
gyroscopeBiasCorrelationTime
¶
Gyroscope bias correlation time constant [s].
public double
gyroscopeTurnOnBiasSigma
¶
Gyroscope turn on bias standard deviation [rad/s].
public double
accelerometerNoiseDensity
¶
Accelerometer noise density (two-sided spectrum) [m/s^2/sqrt(Hz)].
public double
accelerometerRandomWalk
¶
Accelerometer bias random walk. [m/s^2/s/sqrt(Hz)].
public double
accelerometerBiasCorrelationTime
¶
Accelerometer bias correlation time constant [s].
public double
accelerometerTurnOnBiasSigma
¶
Accelerometer turn on bias standard deviation [m/s^2].
public double
orientationNoise
¶
Standard deviation of orientation noise per axis [rad].
public inline
IMUParameters
()
¶
Constructor.