From 6a98ad5a291247608067ec02d5ad663ea08a806b Mon Sep 17 00:00:00 2001 From: Randy Mackay Date: Sun, 11 Apr 2021 17:42:52 +0900 Subject: [PATCH] Copter: loiter-turns fix --- ArduCopter/mode_auto.cpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/ArduCopter/mode_auto.cpp b/ArduCopter/mode_auto.cpp index d49da30b73..6506e1d9e3 100644 --- a/ArduCopter/mode_auto.cpp +++ b/ArduCopter/mode_auto.cpp @@ -1185,7 +1185,6 @@ bool ModeAuto::set_next_wp(const AP_Mission::Mission_Command& current_cmd, const switch (next_cmd.id) { case MAV_CMD_NAV_WAYPOINT: case MAV_CMD_NAV_LOITER_UNLIM: - case MAV_CMD_NAV_LOITER_TURNS: case MAV_CMD_NAV_LOITER_TIME: { const Location dest_loc = loc_from_cmd(current_cmd, default_loc); const Location next_dest_loc = loc_from_cmd(next_cmd, dest_loc); @@ -1200,6 +1199,7 @@ bool ModeAuto::set_next_wp(const AP_Mission::Mission_Command& current_cmd, const } case MAV_CMD_NAV_LAND: // stop because we may change between rel,abs and terrain alt types + case MAV_CMD_NAV_LOITER_TURNS: case MAV_CMD_NAV_RETURN_TO_LAUNCH: case MAV_CMD_NAV_TAKEOFF: // always stop for RTL and takeoff commands