From a828db792e6c84f774d97646b5e35d5657a36b24 Mon Sep 17 00:00:00 2001 From: Andrew Tridgell Date: Tue, 19 Jan 2016 15:28:53 +1100 Subject: [PATCH] SITL: added SIM_GYR_SCALE_{X,Y,Z} allows testing of gyro scale factor learning in EKF2 --- libraries/SITL/SITL.cpp | 1 + libraries/SITL/SITL.h | 1 + 2 files changed, 2 insertions(+) diff --git a/libraries/SITL/SITL.cpp b/libraries/SITL/SITL.cpp index 3b32c32b17..2e33d2abb7 100644 --- a/libraries/SITL/SITL.cpp +++ b/libraries/SITL/SITL.cpp @@ -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 }; diff --git a/libraries/SITL/SITL.h b/libraries/SITL/SITL.h index 1a7b02859f..73c3c495d9 100644 --- a/libraries/SITL/SITL.h +++ b/libraries/SITL/SITL.h @@ -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