mirror of https://github.com/ArduPilot/ardupilot
Rover: resetting reversed flag more generally
This commit is contained in:
parent
b93ba1ae68
commit
49ba800f88
|
@ -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();
|
||||
|
|
10
Rover/mode.h
10
Rover/mode.h
|
@ -124,6 +124,9 @@ public:
|
|||
// 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();
|
||||
|
||||
|
@ -277,6 +280,13 @@ public:
|
|||
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&),
|
||||
|
|
Loading…
Reference in New Issue