SITL: added SIM_MAG_SCALING
This commit is contained in:
parent
ffc2ca4b51
commit
fdc7dac61c
@ -195,6 +195,8 @@ const AP_Param::GroupInfo SITL::var_info2[] = {
|
||||
// @Path: ./SIM_ToneAlarm.cpp
|
||||
AP_SUBGROUPINFO(tonealarm_sim, "TA_", 57, SITL, ToneAlarm),
|
||||
|
||||
AP_GROUPINFO("MAG_SCALING", 60, SITL, mag_scaling, 1),
|
||||
|
||||
AP_GROUPEND
|
||||
|
||||
};
|
||||
|
@ -179,6 +179,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 {
|
||||
|
Loading…
Reference in New Issue
Block a user