SITL: added SIM_MAG_SCALING for testing scale factor errors

This commit is contained in:
Andrew Tridgell 2019-12-05 17:59:24 +11:00
parent 9ae5ffa215
commit cc71efbca1
2 changed files with 3 additions and 1 deletions

View File

@ -121,6 +121,7 @@ const AP_Param::GroupInfo SITL::var_info2[] = {
AP_GROUPINFO("MAG_DIA", 18, SITL, mag_diag, 0),
AP_GROUPINFO("MAG_ODI", 19, SITL, mag_offdiag, 0),
AP_GROUPINFO("MAG_ORIENT", 20, SITL, mag_orient, 0),
AP_GROUPINFO("MAG_SCALING", 60, SITL, mag_scaling, 1),
AP_GROUPEND
};

View File

@ -143,6 +143,7 @@ public:
AP_Int16 pin_mask; // for GPIO emulation
AP_Float speedup; // simulation speedup
AP_Int8 odom_enable; // enable visual odomotry data
AP_Float mag_scaling; // scaling factor on first compasses
// wind control
enum WindType {