Browse Source

Plane: prevent delayed compass HIL data from disabling compass at system startup only

master
ziltoid2 10 years ago committed by Andrew Tridgell
parent
commit
b9dd6b7aac
  1. 2
      ArduPlane/system.cpp

2
ArduPlane/system.cpp

@ -178,7 +178,7 @@ void Plane::init_ardupilot() @@ -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…
Cancel
Save