mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-22 07:44:03 -04:00
Plane: prevent delayed compass HIL data from disabling compass at system startup only
This commit is contained in:
parent
0b1a997800
commit
b9dd6b7aac
@ -178,7 +178,7 @@ void Plane::init_ardupilot()
|
||||
airspeed.init();
|
||||
|
||||
if (g.compass_enabled==true) {
|
||||
if (!compass.init() || !compass.read()) {
|
||||
if (!compass.init() || (!g.hil_mode && !compass.read())) {
|
||||
cliSerial->println_P(PSTR("Compass initialisation failed!"));
|
||||
g.compass_enabled = false;
|
||||
} else {
|
||||
|
Loading…
Reference in New Issue
Block a user