diff --git a/ArduPlane/events.cpp b/ArduPlane/events.cpp index 4ed2df9ce3..3a8cadaad0 100644 --- a/ArduPlane/events.cpp +++ b/ArduPlane/events.cpp @@ -171,7 +171,7 @@ void Plane::handle_battery_failsafe(const char *type_str, const int8_t action) } FALLTHROUGH; case Failsafe_Action_RTL: - if (flight_stage != AP_Vehicle::FixedWing::FLIGHT_LAND && control_mode != &mode_qland ) { + if (flight_stage != AP_Vehicle::FixedWing::FLIGHT_LAND && control_mode != &mode_qland && !quadplane.in_vtol_land_sequence()) { // never stop a landing if we were already committed set_mode(mode_rtl, ModeReason::BATTERY_FAILSAFE); aparm.throttle_cruise.load(); diff --git a/ArduPlane/quadplane.cpp b/ArduPlane/quadplane.cpp index 5d4de19f96..d38bf0e958 100644 --- a/ArduPlane/quadplane.cpp +++ b/ArduPlane/quadplane.cpp @@ -3172,3 +3172,11 @@ bool QuadPlane::in_vtol_land_final(void) const { return in_vtol_land_descent() && poscontrol.state == QPOS_LAND_FINAL; } + +/* + see if we are in any of the phases of a VTOL landing + */ +bool QuadPlane::in_vtol_land_sequence(void) const +{ + return in_vtol_land_approach() || in_vtol_land_descent() || in_vtol_land_final(); +} diff --git a/ArduPlane/quadplane.h b/ArduPlane/quadplane.h index ddd1190939..6e49191959 100644 --- a/ArduPlane/quadplane.h +++ b/ArduPlane/quadplane.h @@ -553,6 +553,11 @@ private: are we in the final landing phase of a VTOL landing? */ bool in_vtol_land_final(void) const; + + /* + are we in any of the phases of a VTOL landing? + */ + bool in_vtol_land_sequence(void) const; public: void motor_test_output();