SITL: add ACC_BIAS and BARO_GLITCH parameters

These allow testing accelerometer bias which often comes from vibration
and sudden changes in baro altitude.
This commit is contained in:
Randy Mackay 2014-07-28 17:40:17 +09:00
parent 7cc1501dc6
commit 79291f25a0
2 changed files with 4 additions and 0 deletions

View File

@ -58,6 +58,8 @@ const AP_Param::GroupInfo SITL::var_info[] PROGMEM = {
AP_GROUPINFO("BARO_DISABLE", 27, SITL, baro_disable, 0),
AP_GROUPINFO("FLOAT_EXCEPT", 28, SITL, float_exception, 1),
AP_GROUPINFO("MAG_MOT", 29, SITL, mag_mot, 0),
AP_GROUPINFO("ACC_BIAS", 30, SITL, accel_bias, 0),
AP_GROUPINFO("BARO_GLITCH", 31, SITL, baro_glitch, 0),
AP_GROUPEND
};

View File

@ -51,8 +51,10 @@ public:
// noise levels for simulated sensors
AP_Float baro_noise; // in metres
AP_Float baro_drift; // in metres per second
AP_Float baro_glitch; // glitch in meters
AP_Float gyro_noise; // in degrees/second
AP_Float accel_noise; // in m/s/s
AP_Vector3f accel_bias; // in m/s/s
AP_Float aspd_noise; // in m/s
AP_Float mag_noise; // in mag units (earth field is 818)
AP_Float mag_error; // in degrees