From f319c36de17a55d80ee4d7d3dc41e7a5e86ea8e8 Mon Sep 17 00:00:00 2001 From: Shiv Tyagi Date: Mon, 22 Nov 2021 23:58:01 +0530 Subject: [PATCH] Rover: set MIS_DONE_BEHAVE to LOITER in boats Boats should loiter after completing a mission to avoid drifting off --- Rover/system.cpp | 5 +++++ 1 file changed, 5 insertions(+) diff --git a/Rover/system.cpp b/Rover/system.cpp index fe6c02e40d..0a97d88e9a 100644 --- a/Rover/system.cpp +++ b/Rover/system.cpp @@ -136,6 +136,11 @@ void Rover::init_ardupilot() rover.g2.sailboat.init(); + // boat should loiter after completing a mission to avoid drifting off + if (is_boat()) { + rover.g2.mis_done_behave.set_default(ModeAuto::Mis_Done_Behave::MIS_DONE_BEHAVE_LOITER); + } + // flag that initialisation has completed initialised = true; }