Skip to content

Commit

Permalink
Rover: use enum-class for mission-done behaviours
Browse files Browse the repository at this point in the history
  • Loading branch information
peterbarker authored and rmackay9 committed Jun 17, 2024
1 parent 136e76e commit 7003647
Show file tree
Hide file tree
Showing 4 changed files with 28 additions and 17 deletions.
4 changes: 3 additions & 1 deletion Rover/Parameters.h
Original file line number Diff line number Diff line change
Expand Up @@ -384,8 +384,10 @@ class ParametersG2 {
// windvane
AP_WindVane windvane;

#if AP_MISSION_ENABLED
// mission behave
AP_Int8 mis_done_behave;
AP_Enum<ModeAuto::DoneBehaviour> mis_done_behave;
#endif

// balance both pitch trim
AP_Float bal_pitch_trim;
Expand Down
10 changes: 5 additions & 5 deletions Rover/mode.h
Original file line number Diff line number Diff line change
Expand Up @@ -282,11 +282,11 @@ class ModeAuto : public Mode
FUNCTOR_BIND_MEMBER(&ModeAuto::verify_command_callback, bool, const AP_Mission::Mission_Command&),
FUNCTOR_BIND_MEMBER(&ModeAuto::exit_mission, void)};

enum Mis_Done_Behave {
MIS_DONE_BEHAVE_HOLD = 0,
MIS_DONE_BEHAVE_LOITER = 1,
MIS_DONE_BEHAVE_ACRO = 2,
MIS_DONE_BEHAVE_MANUAL = 3
enum class DoneBehaviour : uint8_t {
HOLD = 0,
LOITER = 1,
ACRO = 2,
MANUAL = 3,
};

protected:
Expand Down
29 changes: 19 additions & 10 deletions Rover/mode_auto.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -626,16 +626,25 @@ void ModeAuto::exit_mission()
// send message
gcs().send_text(MAV_SEVERITY_NOTICE, "Mission Complete");

if (g2.mis_done_behave == MIS_DONE_BEHAVE_LOITER && start_loiter()) {
return;
}

if (g2.mis_done_behave == MIS_DONE_BEHAVE_ACRO && rover.set_mode(rover.mode_acro, ModeReason::MISSION_END)) {
return;
}

if (g2.mis_done_behave == MIS_DONE_BEHAVE_MANUAL && rover.set_mode(rover.mode_manual, ModeReason::MISSION_END)) {
return;
switch ((DoneBehaviour)g2.mis_done_behave) {
case DoneBehaviour::HOLD:
// the default "start_stop" behaviour is used
break;
case DoneBehaviour::LOITER:
if (start_loiter()) {
return;
}
break;
case DoneBehaviour::ACRO:
if (rover.set_mode(rover.mode_acro, ModeReason::MISSION_END)) {
return;
}
break;
case DoneBehaviour::MANUAL:
if (rover.set_mode(rover.mode_manual, ModeReason::MISSION_END)) {
return;
}
break;
}

start_stop();
Expand Down
2 changes: 1 addition & 1 deletion Rover/system.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -145,7 +145,7 @@ void Rover::init_ardupilot()

// 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);
rover.g2.mis_done_behave.set_default(uint8_t(ModeAuto::DoneBehaviour::LOITER));
}

// flag that initialisation has completed
Expand Down

0 comments on commit 7003647

Please sign in to comment.