SITL: added SIM_MAG_SCALING for testing scale factor errors

This commit is contained in:
Andrew Tridgell 2019-11-27 09:12:33 +11:00
parent 54582814aa
commit 7b203f6816
2 changed files with 3 additions and 0 deletions

View File

@ -202,6 +202,8 @@ const AP_Param::GroupInfo SITL::var_info2[] = {
AP_GROUPINFO("SAFETY_STATE", 59, SITL, _safety_switch_state, 0),
AP_GROUPINFO("MAG_SCALING", 60, SITL, mag_scaling, 1),
AP_GROUPEND
};

View File

@ -184,6 +184,7 @@ public:
AP_Int8 baro_count; // number of simulated baros to create
AP_Int8 gps_hdg_enabled; // enable the output of a NMEA heading HDT sentence
AP_Int32 loop_delay; // extra delay to add to every loop
AP_Float mag_scaling; // scaling factor on first compasses
// EFI type
enum EFIType {