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. More...
#include <IMUROSPlugin.hh>
Public Member Functions | |
IMUParameters () | |
Constructor. More... | |
Public Attributes | |
double | accelerometerBiasCorrelationTime |
Accelerometer bias correlation time constant [s]. More... | |
double | accelerometerNoiseDensity |
Accelerometer noise density (two-sided spectrum) [m/s^2/sqrt(Hz)]. More... | |
double | accelerometerRandomWalk |
Accelerometer bias random walk. [m/s^2/s/sqrt(Hz)]. More... | |
double | accelerometerTurnOnBiasSigma |
Accelerometer turn on bias standard deviation [m/s^2]. More... | |
double | gyroscopeBiasCorrelationTime |
Gyroscope bias correlation time constant [s]. More... | |
double | gyroscopeNoiseDensity |
Gyroscope noise density (two-sided spectrum) [rad/s/sqrt(Hz)]. More... | |
double | gyroscopeRandomWalk |
Gyroscope bias random walk [rad/s/s/sqrt(Hz)]. More... | |
double | gyroscopeTurnOnBiasSigma |
Gyroscope turn on bias standard deviation [rad/s]. More... | |
double | orientationNoise |
Standard deviation of orientation noise per axis [rad]. More... | |
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.
Definition at line 55 of file IMUROSPlugin.hh.
|
inline |
Constructor.
Definition at line 84 of file IMUROSPlugin.hh.
double gazebo::IMUParameters::accelerometerBiasCorrelationTime |
Accelerometer bias correlation time constant [s].
Definition at line 75 of file IMUROSPlugin.hh.
double gazebo::IMUParameters::accelerometerNoiseDensity |
Accelerometer noise density (two-sided spectrum) [m/s^2/sqrt(Hz)].
Definition at line 69 of file IMUROSPlugin.hh.
double gazebo::IMUParameters::accelerometerRandomWalk |
Accelerometer bias random walk. [m/s^2/s/sqrt(Hz)].
Definition at line 72 of file IMUROSPlugin.hh.
double gazebo::IMUParameters::accelerometerTurnOnBiasSigma |
Accelerometer turn on bias standard deviation [m/s^2].
Definition at line 78 of file IMUROSPlugin.hh.
double gazebo::IMUParameters::gyroscopeBiasCorrelationTime |
Gyroscope bias correlation time constant [s].
Definition at line 63 of file IMUROSPlugin.hh.
double gazebo::IMUParameters::gyroscopeNoiseDensity |
Gyroscope noise density (two-sided spectrum) [rad/s/sqrt(Hz)].
Definition at line 57 of file IMUROSPlugin.hh.
double gazebo::IMUParameters::gyroscopeRandomWalk |
Gyroscope bias random walk [rad/s/s/sqrt(Hz)].
Definition at line 60 of file IMUROSPlugin.hh.
double gazebo::IMUParameters::gyroscopeTurnOnBiasSigma |
Gyroscope turn on bias standard deviation [rad/s].
Definition at line 66 of file IMUROSPlugin.hh.
double gazebo::IMUParameters::orientationNoise |
Standard deviation of orientation noise per axis [rad].
Definition at line 81 of file IMUROSPlugin.hh.