SITL: added SIM_MAG_SCALING for testing scale factor errors

# Conflicts:
#	libraries/SITL/SITL.cpp
This commit is contained in:
Andrew Tridgell 2019-12-09 13:15:28 +11:00
parent bc7f811ff0
commit c36687a79f
2 changed files with 3 additions and 0 deletions

View File

@ -189,6 +189,8 @@ const AP_Param::GroupInfo SITL::var_info2[] = {
// extra delay per main loop
AP_GROUPINFO("LOOP_DELAY", 55, SITL, loop_delay, 0),
AP_GROUPINFO("MAG_SCALING", 60, SITL, mag_scaling, 1),
AP_GROUPEND
};

View File

@ -177,6 +177,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
// wind control
enum WindType {