From 4ce051af82b2103544d96b9402b08e3c16079c9a Mon Sep 17 00:00:00 2001 From: Peter Barker Date: Mon, 25 Sep 2017 12:04:01 +1000 Subject: [PATCH] Plane: ensure we're in short failsafe before using failsafe.ch3_timer_ms --- ArduPlane/system.cpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/ArduPlane/system.cpp b/ArduPlane/system.cpp index a6b0342413..449693593b 100644 --- a/ArduPlane/system.cpp +++ b/ArduPlane/system.cpp @@ -480,7 +480,7 @@ void Plane::check_long_failsafe() // ------------------- if (failsafe.state != FAILSAFE_LONG && failsafe.state != FAILSAFE_GCS && flight_stage != AP_Vehicle::FixedWing::FLIGHT_LAND) { uint32_t radio_timeout_ms = failsafe.last_valid_rc_ms; - if (g.short_fs_action != SHORT_FS_ACTION_DISABLED) { + if (failsafe.state == FAILSAFE_SHORT) { // time is relative to when short failsafe enabled radio_timeout_ms = failsafe.ch3_timer_ms; }