Skip to content

Commit

Permalink
Rover: resetting reversed flag more generally
Browse files Browse the repository at this point in the history
  • Loading branch information
robot-to-society committed Jun 18, 2024
1 parent e83afcf commit 910972e
Show file tree
Hide file tree
Showing 2 changed files with 12 additions and 1 deletion.
3 changes: 2 additions & 1 deletion Rover/mode.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -44,7 +44,8 @@ bool Mode::enter()

// initialisation common to all modes
if (ret) {
set_reversed(false);
// init reversed flag
init_reversed_flag();

// clear sailboat tacking flags
g2.sailboat.clear_tack();
Expand Down
10 changes: 10 additions & 0 deletions Rover/mode.h
Original file line number Diff line number Diff line change
Expand Up @@ -124,6 +124,9 @@ class Mode
// execute the mission in reverse (i.e. backing up)
void set_reversed(bool value);

// init reversed flag for autopilot mode
virtual void init_reversed_flag() { if (is_autopilot_mode()) { set_reversed(false); } }

// handle tacking request (from auxiliary switch) in sailboats
virtual void handle_tack_request();

Expand Down Expand Up @@ -277,6 +280,13 @@ class ModeAuto : public Mode
bool nav_script_time(uint16_t &id, uint8_t &cmd, float &arg1, float &arg2, int16_t &arg3, int16_t &arg4);
void nav_script_time_done(uint16_t id);

//
void init_reversed_flag() override {
if (!mission.is_resume()) {
set_reversed(false);
}
}

AP_Mission mission{
FUNCTOR_BIND_MEMBER(&ModeAuto::start_command, bool, const AP_Mission::Mission_Command&),
FUNCTOR_BIND_MEMBER(&ModeAuto::verify_command_callback, bool, const AP_Mission::Mission_Command&),
Expand Down

0 comments on commit 910972e

Please sign in to comment.