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.
This commit is contained in:
Andre Kjellstrup 2015-06-20 23:29:01 +02:00 committed by Andrew Tridgell
parent baf4989a80
commit 9d525d4382

View File

@ -516,7 +516,8 @@ void Plane::check_short_failsafe()
{ {
// only act on changes // 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 if(failsafe.ch3_failsafe) { // The condition is checked and the flag ch3_failsafe is set in radio.pde
failsafe_short_on_event(FAILSAFE_SHORT); failsafe_short_on_event(FAILSAFE_SHORT);
} }