SITL: added SIM_GYR_SCALE_{X,Y,Z}

allows testing of gyro scale factor learning in EKF2
This commit is contained in:
Andrew Tridgell 2016-01-19 15:28:53 +11:00
parent 23eef91c59
commit a828db792e
2 changed files with 2 additions and 0 deletions

View File

@ -75,6 +75,7 @@ const AP_Param::GroupInfo SITL::var_info[] = {
AP_GROUPINFO("MAG_OFS", 41, SITL, mag_ofs, 0),
AP_GROUPINFO("ACC2_RND", 42, SITL, accel2_noise, 0),
AP_GROUPINFO("ARSP_FAIL", 43, SITL, aspd_fail, 0),
AP_GROUPINFO("GYR_SCALE", 44, SITL, gyro_scale, 0),
AP_GROUPEND
};

View File

@ -63,6 +63,7 @@ public:
AP_Float baro_drift; // in metres per second
AP_Float baro_glitch; // glitch in meters
AP_Float gyro_noise; // in degrees/second
AP_Vector3f gyro_scale; // percentage
AP_Float accel_noise; // in m/s/s
AP_Float accel2_noise; // in m/s/s
AP_Vector3f accel_bias; // in m/s/s