diff --git a/ArduPlane/Plane.h b/ArduPlane/Plane.h index 43c8d70a16..d536121a6c 100644 --- a/ArduPlane/Plane.h +++ b/ArduPlane/Plane.h @@ -1129,7 +1129,10 @@ private: #if HAL_QUADPLANE_ENABLED Failsafe_Action_QLand = 4, #endif - Failsafe_Action_Parachute = 5 + Failsafe_Action_Parachute = 5, +#if HAL_QUADPLANE_ENABLED + Failsafe_Action_Loiter_alt_QLand = 6, +#endif }; // list of priorities, highest priority first diff --git a/ArduPlane/events.cpp b/ArduPlane/events.cpp index 87a1757fee..549bd4f9d5 100644 --- a/ArduPlane/events.cpp +++ b/ArduPlane/events.cpp @@ -203,13 +203,20 @@ void Plane::handle_battery_failsafe(const char *type_str, const int8_t action) { switch ((Failsafe_Action)action) { #if HAL_QUADPLANE_ENABLED + case Failsafe_Action_Loiter_alt_QLand: + if (quadplane.available()) { + plane.set_mode(mode_lotier_qland, ModeReason::BATTERY_FAILSAFE); + break; + } + FALLTHROUGH; + case Failsafe_Action_QLand: if (quadplane.available()) { plane.set_mode(mode_qland, ModeReason::BATTERY_FAILSAFE); break; } FALLTHROUGH; -#endif +#endif // HAL_QUADPLANE_ENABLED case Failsafe_Action_Land: { bool already_landing = flight_stage == AP_Vehicle::FixedWing::FLIGHT_LAND; #if HAL_QUADPLANE_ENABLED