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

This commit is contained in:
ziltoid2 2015-05-21 15:28:29 +03:00 committed by Andrew Tridgell
parent 0b1a997800
commit b9dd6b7aac

View File

@ -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 {