From 7618241be438a799db0160762f290bafbaa193e2 Mon Sep 17 00:00:00 2001 From: Randy Mackay Date: Wed, 21 Apr 2021 10:35:06 +0900 Subject: [PATCH] Rover: auto defaults to stop or loiter submode --- Rover/mode_auto.cpp | 14 +++++++++----- 1 file changed, 9 insertions(+), 5 deletions(-) diff --git a/Rover/mode_auto.cpp b/Rover/mode_auto.cpp index 3e77d865a9..b530743e28 100644 --- a/Rover/mode_auto.cpp +++ b/Rover/mode_auto.cpp @@ -11,11 +11,6 @@ bool ModeAuto::_enter() return false; } - // init location target - if (!g2.wp_nav.set_desired_location(rover.current_loc)) { - return false; - } - // initialise waypoint speed g2.wp_nav.set_desired_speed_to_default(); @@ -25,6 +20,15 @@ bool ModeAuto::_enter() // clear guided limits rover.mode_guided.limit_clear(); + // initialise submode to stop or loiter + if (rover.is_boat()) { + if (!start_loiter()) { + start_stop(); + } + } else { + start_stop(); + } + // restart mission processing mission.start_or_resume(); return true;