diff --git a/APMrover2/Parameters.cpp b/APMrover2/Parameters.cpp index 27c18aadf5..863482e4df 100644 --- a/APMrover2/Parameters.cpp +++ b/APMrover2/Parameters.cpp @@ -558,8 +558,8 @@ const AP_Param::GroupInfo ParametersG2::var_info[] = { // @Param: MIS_DONE_BEHAVE // @DisplayName: Mission done behave - // @Description: Mode to become after mission done - // @Values: 0:Hold,1:Loiter, 2:Acro + // @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), diff --git a/APMrover2/mode_auto.cpp b/APMrover2/mode_auto.cpp index 45fcb7231a..75ff6e41c5 100644 --- a/APMrover2/mode_auto.cpp +++ b/APMrover2/mode_auto.cpp @@ -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