Browse Source

Plane: don't trigger GCS failsafe if GCS never connected

The we have never received a heartbeat message from the GCS then don't
use the lack of heartbeat to trigger a failsafe event
master
Andrew Tridgell 12 years ago
parent
commit
87c6545ac6
  1. 1
      ArduPlane/system.pde

1
ArduPlane/system.pde

@ -393,6 +393,7 @@ static void check_long_failsafe() @@ -393,6 +393,7 @@ static void check_long_failsafe()
failsafe_long_on_event(FAILSAFE_LONG);
}
if (g.gcs_heartbeat_fs_enabled &&
last_heartbeat_ms != 0 &&
(tnow - last_heartbeat_ms) > FAILSAFE_LONG_TIME) {
failsafe_long_on_event(FAILSAFE_GCS);
}

Loading…
Cancel
Save