mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-03-11 17:13:56 -03:00
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:
parent
ee68072c62
commit
f319c36de1
@ -136,6 +136,11 @@ void Rover::init_ardupilot()
|
|||||||
|
|
||||||
rover.g2.sailboat.init();
|
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
|
// flag that initialisation has completed
|
||||||
initialised = true;
|
initialised = true;
|
||||||
}
|
}
|
||||||
|
Loading…
Reference in New Issue
Block a user