mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-22 15:53:56 -04:00
AP_Compass: default SITL compass to having scale factor set
This commit is contained in:
parent
1f21d72c79
commit
8920362212
@ -36,6 +36,12 @@ AP_Compass_SITL::AP_Compass_SITL()
|
||||
}
|
||||
}
|
||||
|
||||
// we want to simulate a calibrated compass by default, so set
|
||||
// scale to 1
|
||||
AP_Param::set_default_by_name("COMPASS_SCALE", 1);
|
||||
AP_Param::set_default_by_name("COMPASS_SCALE2", 1);
|
||||
AP_Param::set_default_by_name("COMPASS_SCALE3", 1);
|
||||
|
||||
// make first compass external
|
||||
set_external(_compass_instance[0], true);
|
||||
|
||||
|
Loading…
Reference in New Issue
Block a user