Browse Source

Plane: Don't disable compass checks for HIL mode unless actually in hil mode

master
Michael du Breuil 9 years ago
parent
commit
4b40a884e9
  1. 2
      ArduPlane/system.cpp

2
ArduPlane/system.cpp

@ -168,7 +168,9 @@ void Plane::init_ardupilot()
if (g.compass_enabled==true) { if (g.compass_enabled==true) {
bool compass_ok = compass.init() && compass.read(); bool compass_ok = compass.init() && compass.read();
#if HIL_SUPPORT #if HIL_SUPPORT
if (!is_zero(g.hil_mode)) {
compass_ok = true; compass_ok = true;
}
#endif #endif
if (!compass_ok) { if (!compass_ok) {
cliSerial->println("Compass initialisation failed!"); cliSerial->println("Compass initialisation failed!");

Loading…
Cancel
Save