From 87c6545ac60f700144d1c1df51b591635b78583e Mon Sep 17 00:00:00 2001 From: Andrew Tridgell Date: Sat, 9 Mar 2013 13:48:21 +1100 Subject: [PATCH] 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 --- ArduPlane/system.pde | 1 + 1 file changed, 1 insertion(+) diff --git a/ArduPlane/system.pde b/ArduPlane/system.pde index f54af45e07..ad94985ec9 100644 --- a/ArduPlane/system.pde +++ b/ArduPlane/system.pde @@ -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); }