Rover: set MIS_DONE_BEHAVE to LOITER in boats

Boats should loiter after completing a mission to avoid drifting off
This commit is contained in:
Shiv Tyagi 2021-11-22 23:58:01 +05:30 committed by Randy Mackay
parent ee68072c62
commit f319c36de1
1 changed files with 5 additions and 0 deletions

View File

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