mirror of https://github.com/ArduPilot/ardupilot
SITL: added SIM_MAG_SAVE_IDS
this controls whether SITL saves device IDs for compasses on startup so the compasses always appear calibrated
This commit is contained in:
parent
24bed08c4e
commit
f7a1227c25
|
@ -744,6 +744,14 @@ const AP_Param::GroupInfo SIM::var_mag[] = {
|
|||
AP_GROUPINFO("MAG3_SCALING", 30, SIM, mag_scaling[2], 1),
|
||||
AP_GROUPINFO("MAG3_ORIENT", 36, SIM, mag_orient[2], 0),
|
||||
#endif
|
||||
|
||||
// @Param: MAG_SAVE_IDS
|
||||
// @DisplayName: Save MAG devids on startup
|
||||
// @Description: This forces saving of compass devids on startup so that simulated compasses start as calibrated
|
||||
// @Values: 0:Disabled, 1:Enabled
|
||||
// @User: Advanced
|
||||
AP_GROUPINFO("MAG_SAVE_IDS", 37, SIM, mag_save_ids, 1),
|
||||
|
||||
AP_GROUPEND
|
||||
};
|
||||
|
||||
|
|
|
@ -178,6 +178,7 @@ public:
|
|||
AP_Vector3f mag_offdiag[HAL_COMPASS_MAX_SENSORS]; // off-diagonal corrections
|
||||
AP_Int8 mag_orient[HAL_COMPASS_MAX_SENSORS]; // external compass orientation
|
||||
AP_Int8 mag_fail[HAL_COMPASS_MAX_SENSORS]; // fail magnetometer, 1 for no data, 2 for freeze
|
||||
AP_Int8 mag_save_ids;
|
||||
AP_Float servo_speed; // servo speed in seconds
|
||||
|
||||
AP_Float sonar_glitch;// probability between 0-1 that any given sonar sample will read as max distance
|
||||
|
|
Loading…
Reference in New Issue