mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-03 06:28:27 -04:00
Rover: Hold or Loiter within Auto on mission completion
This commit is contained in:
parent
d2cf0939a5
commit
80c58696d0
@ -558,7 +558,7 @@ const AP_Param::GroupInfo ParametersG2::var_info[] = {
|
||||
|
||||
// @Param: MIS_DONE_BEHAVE
|
||||
// @DisplayName: Mission done behave
|
||||
// @Description: Mode to become after mission done
|
||||
// @Description: Behaviour after mission completes
|
||||
// @Values: 0:Hold,1:Loiter,2:Acro
|
||||
// @User: Standard
|
||||
AP_GROUPINFO("MIS_DONE_BEHAVE", 38, ParametersG2, mis_done_behave, 0),
|
||||
|
@ -437,7 +437,7 @@ void ModeAuto::exit_mission()
|
||||
// send message
|
||||
gcs().send_text(MAV_SEVERITY_NOTICE, "Mission Complete");
|
||||
|
||||
if (g2.mis_done_behave == MIS_DONE_BEHAVE_LOITER && rover.set_mode(rover.mode_loiter, MODE_REASON_MISSION_END)) {
|
||||
if (g2.mis_done_behave == MIS_DONE_BEHAVE_LOITER && start_loiter()) {
|
||||
return;
|
||||
}
|
||||
|
||||
@ -445,7 +445,7 @@ void ModeAuto::exit_mission()
|
||||
return;
|
||||
}
|
||||
|
||||
rover.set_mode(rover.mode_hold, MODE_REASON_MISSION_END);
|
||||
start_stop();
|
||||
}
|
||||
|
||||
// verify_command_callback - callback function called from ap-mission at 10hz or higher when a command is being run
|
||||
|
Loading…
Reference in New Issue
Block a user