Skip to content

Commit a291aff

Browse files
committed
Rover: use enum-class for mission-done behaviours
1 parent 136e76e commit a291aff

File tree

4 files changed

+28
-17
lines changed

4 files changed

+28
-17
lines changed

Rover/Parameters.h

Lines changed: 3 additions & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -384,8 +384,10 @@ class ParametersG2 {
384384
// windvane
385385
AP_WindVane windvane;
386386

387+
#if AP_MISSION_ENABLED
387388
// mission behave
388-
AP_Int8 mis_done_behave;
389+
AP_Enum<ModeAuto::DoneBehaviour> mis_done_behave;
390+
#endif
389391

390392
// balance both pitch trim
391393
AP_Float bal_pitch_trim;

Rover/mode.h

Lines changed: 5 additions & 5 deletions
Original file line numberDiff line numberDiff line change
@@ -282,11 +282,11 @@ class ModeAuto : public Mode
282282
FUNCTOR_BIND_MEMBER(&ModeAuto::verify_command_callback, bool, const AP_Mission::Mission_Command&),
283283
FUNCTOR_BIND_MEMBER(&ModeAuto::exit_mission, void)};
284284

285-
enum Mis_Done_Behave {
286-
MIS_DONE_BEHAVE_HOLD = 0,
287-
MIS_DONE_BEHAVE_LOITER = 1,
288-
MIS_DONE_BEHAVE_ACRO = 2,
289-
MIS_DONE_BEHAVE_MANUAL = 3
285+
enum class DoneBehaviour : uint8_t {
286+
HOLD = 0,
287+
LOITER = 1,
288+
ACRO = 2,
289+
MANUAL = 3,
290290
};
291291

292292
protected:

Rover/mode_auto.cpp

Lines changed: 19 additions & 10 deletions
Original file line numberDiff line numberDiff line change
@@ -626,16 +626,25 @@ void ModeAuto::exit_mission()
626626
// send message
627627
gcs().send_text(MAV_SEVERITY_NOTICE, "Mission Complete");
628628

629-
if (g2.mis_done_behave == MIS_DONE_BEHAVE_LOITER && start_loiter()) {
630-
return;
631-
}
632-
633-
if (g2.mis_done_behave == MIS_DONE_BEHAVE_ACRO && rover.set_mode(rover.mode_acro, ModeReason::MISSION_END)) {
634-
return;
635-
}
636-
637-
if (g2.mis_done_behave == MIS_DONE_BEHAVE_MANUAL && rover.set_mode(rover.mode_manual, ModeReason::MISSION_END)) {
638-
return;
629+
switch ((DoneBehaviour)g2.mis_done_behave) {
630+
case DoneBehaviour::HOLD:
631+
// the default "start_stop" behaviour is used
632+
break;
633+
case DoneBehaviour::LOITER:
634+
if (start_loiter()) {
635+
return;
636+
}
637+
break;
638+
case DoneBehaviour::ACRO:
639+
if (rover.set_mode(rover.mode_acro, ModeReason::MISSION_END)) {
640+
return;
641+
}
642+
break;
643+
case DoneBehaviour::MANUAL:
644+
if (rover.set_mode(rover.mode_manual, ModeReason::MISSION_END)) {
645+
return;
646+
}
647+
break;
639648
}
640649

641650
start_stop();

Rover/system.cpp

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -145,7 +145,7 @@ void Rover::init_ardupilot()
145145

146146
// boat should loiter after completing a mission to avoid drifting off
147147
if (is_boat()) {
148-
rover.g2.mis_done_behave.set_default(ModeAuto::Mis_Done_Behave::MIS_DONE_BEHAVE_LOITER);
148+
rover.g2.mis_done_behave.set_default(uint8_t(ModeAuto::DoneBehaviour::LOITER));
149149
}
150150

151151
// flag that initialisation has completed

0 commit comments

Comments
 (0)