Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

Rover: HOLD mode in AUTO will keep reversed flag #27309

Merged
merged 2 commits into from
Jun 19, 2024
Merged
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
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
3 changes: 3 additions & 0 deletions libraries/AP_Mission/AP_Mission.h
Original file line number Diff line number Diff line change
Expand Up @@ -709,6 +709,9 @@ class AP_Mission
_force_resume = force_resume;
}

// returns true if configured to resume
bool is_resume() const { return _restart == 0 || _force_resume; }

// get a reference to the AP_Mission semaphore, allowing an external caller to lock the
// storage while working with multiple waypoints
HAL_Semaphore &get_semaphore(void)
Expand Down
Loading