From e8827d037e1558db79dec53d7fea776be3ed4386 Mon Sep 17 00:00:00 2001 From: James O'Shannessy <12959316+joshanne@users.noreply.github.com> Date: Thu, 14 Nov 2024 12:10:12 +1100 Subject: [PATCH] ArduPlane: Ensure Plane reaches loiter target for loiter turns --- ArduPlane/commands_logic.cpp | 6 ++++-- 1 file changed, 4 insertions(+), 2 deletions(-) diff --git a/ArduPlane/commands_logic.cpp b/ArduPlane/commands_logic.cpp index 90c3e02480..2e0a3957e2 100644 --- a/ArduPlane/commands_logic.cpp +++ b/ArduPlane/commands_logic.cpp @@ -726,8 +726,10 @@ bool Plane::verify_loiter_turns(const AP_Mission::Mission_Command &cmd) // LOITER_TURNS makes no sense as VTOL auto_state.vtol_loiter = false; - if (condition_value != 0) { - // primary goal, loiter time + if (!reached_loiter_target()) { + result = false; + } else if (condition_value != 0) { + // primary goal, loiter turns if (loiter.sum_cd > loiter.total_cd && loiter.sum_cd > 1) { // primary goal completed, initialize secondary heading goal condition_value = 0;