diff --git a/APMrover2/Parameters.cpp b/APMrover2/Parameters.cpp index 9583896e6b..cc6f367f78 100644 --- a/APMrover2/Parameters.cpp +++ b/APMrover2/Parameters.cpp @@ -684,7 +684,7 @@ 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 + // @Values: 0:Hold,1:Loiter, 2:Acro // @User: Standard AP_GROUPINFO("MIS_DONE_BEHAVE", 38, ParametersG2, mis_done_behave, 0), diff --git a/APMrover2/commands_logic.cpp b/APMrover2/commands_logic.cpp index 34bbe0e098..e00d31ca82 100644 --- a/APMrover2/commands_logic.cpp +++ b/APMrover2/commands_logic.cpp @@ -112,6 +112,11 @@ void ModeAuto::exit_mission() if (g2.mis_done_behave == MIS_DONE_BEHAVE_LOITER && rover.set_mode(rover.mode_loiter, MODE_REASON_MISSION_END)) { return; } + + if (g2.mis_done_behave == MIS_DONE_BEHAVE_ACRO && rover.set_mode(rover.mode_acro, MODE_REASON_MISSION_END)) { + return; + } + rover.set_mode(rover.mode_hold, MODE_REASON_MISSION_END); } diff --git a/APMrover2/mode.h b/APMrover2/mode.h index 0f5cbc4533..9226896dba 100644 --- a/APMrover2/mode.h +++ b/APMrover2/mode.h @@ -319,7 +319,8 @@ private: enum Mis_Done_Behave { MIS_DONE_BEHAVE_HOLD = 0, - MIS_DONE_BEHAVE_LOITER = 1 + MIS_DONE_BEHAVE_LOITER = 1, + MIS_DONE_BEHAVE_ACRO = 2 }; // Loiter control