From 9d525d4382e2b2c46257938dc9033c6aa6543fd5 Mon Sep 17 00:00:00 2001 From: Andre Kjellstrup Date: Sat, 20 Jun 2015 23:29:01 +0200 Subject: [PATCH] Plane: Do not run FailSafe if on final approach or landing. A failsafe (Circle, RTL) would easily become a disaster if trigged during approach or final. --- ArduPlane/system.cpp | 3 ++- 1 file changed, 2 insertions(+), 1 deletion(-) diff --git a/ArduPlane/system.cpp b/ArduPlane/system.cpp index 4f9aca51c7..8be6e89b67 100644 --- a/ArduPlane/system.cpp +++ b/ArduPlane/system.cpp @@ -516,7 +516,8 @@ void Plane::check_short_failsafe() { // only act on changes // ------------------- - if(failsafe.state == FAILSAFE_NONE) { + if(failsafe.state == FAILSAFE_NONE && (flight_stage != AP_SpdHgtControl::FLIGHT_LAND_FINAL && + flight_stage != AP_SpdHgtControl::FLIGHT_LAND_APPROACH)) { if(failsafe.ch3_failsafe) { // The condition is checked and the flag ch3_failsafe is set in radio.pde failsafe_short_on_event(FAILSAFE_SHORT); }