SITL: Add barometer drift parameter to the SITL library

This commit is contained in:
Ben Nizette 2013-11-24 20:16:46 +11:00 committed by Andrew Tridgell
parent f1bad032dd
commit 59a54aae20
2 changed files with 3 additions and 1 deletions

View File

@ -47,6 +47,7 @@ const AP_Param::GroupInfo SITL::var_info[] PROGMEM = {
AP_GROUPINFO("BATT_VOLTAGE", 19, SITL, batt_voltage, 12.6),
AP_GROUPINFO("ASPD_RND", 20, SITL, aspd_noise, 0.5),
AP_GROUPINFO("ACCEL_FAIL", 21, SITL, accel_fail, 0),
AP_GROUPINFO("BARO_DRIFT", 22, SITL, baro_drift, 0),
AP_GROUPEND
};

View File

@ -46,7 +46,8 @@ public:
static const struct AP_Param::GroupInfo var_info[];
// noise levels for simulated sensors
AP_Float baro_noise; // in Pascals
AP_Float baro_noise; // in metres
AP_Float baro_drift; // in metres per second
AP_Float gyro_noise; // in degrees/second
AP_Float accel_noise; // in m/s/s
AP_Float aspd_noise; // in m/s