ArduPlane: Ensure Plane reaches loiter target for loiter turns

This commit is contained in:
James O'Shannessy 2024-11-14 12:10:12 +11:00
parent d2afc05221
commit e8827d037e
1 changed files with 4 additions and 2 deletions

View File

@ -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;