From 0bfab20bd0e6e8cedd4b77461b255ba826f9a5bc Mon Sep 17 00:00:00 2001 From: Andrew Tridgell Date: Tue, 11 Feb 2020 14:36:02 +1100 Subject: [PATCH] Plane: fixed a bug in LOITER_TURNS in quadplanes if NAV_LOITER_TURNS is used with Q_GUIDED_MODE=1 then we would orbit forever. This ensures we do exit the loiter --- ArduPlane/quadplane.cpp | 5 +++++ 1 file changed, 5 insertions(+) diff --git a/ArduPlane/quadplane.cpp b/ArduPlane/quadplane.cpp index e46ed7dd6d..e0183771d8 100644 --- a/ArduPlane/quadplane.cpp +++ b/ArduPlane/quadplane.cpp @@ -3015,6 +3015,11 @@ bool QuadPlane::guided_mode_enabled(void) if (plane.control_mode != &plane.mode_guided && plane.control_mode != &plane.mode_auto) { return false; } + if (plane.control_mode == &plane.mode_auto && + plane.mission.get_current_nav_cmd().id == MAV_CMD_NAV_LOITER_TURNS) { + // loiter turns is a fixed wing only operation + return false; + } return guided_mode != 0; }