Rover: Move set_reverse method to Mode class

This commit is contained in:
Raouf 2018-08-08 13:48:38 +09:00 committed by Randy Mackay
parent 519be92902
commit ea62c24cef
3 changed files with 12 additions and 11 deletions

View File

@ -226,6 +226,14 @@ bool Mode::set_desired_speed(float speed)
return false; return false;
} }
// execute the mission in reverse (i.e. backing up)
void Mode::set_reversed(bool value)
{
if (_reversed != value) {
_reversed = value;
}
}
void Mode::calc_throttle(float target_speed, bool nudge_allowed, bool avoidance_enabled) void Mode::calc_throttle(float target_speed, bool nudge_allowed, bool avoidance_enabled)
{ {
// add in speed nudging // add in speed nudging

View File

@ -112,6 +112,9 @@ public:
// rtl argument should be true if called from RTL or SmartRTL modes (handled here to avoid duplication) // rtl argument should be true if called from RTL or SmartRTL modes (handled here to avoid duplication)
void set_desired_speed_to_default(bool rtl = false); void set_desired_speed_to_default(bool rtl = false);
// execute the mission in reverse (i.e. backing up)
void set_reversed(bool value);
protected: protected:
// subclasses override this to perform checks before entering the mode // subclasses override this to perform checks before entering the mode
@ -194,6 +197,7 @@ protected:
float _desired_speed_final; // desired speed in m/s when we reach the destination float _desired_speed_final; // desired speed in m/s when we reach the destination
float _speed_error; // ground speed error in m/s float _speed_error; // ground speed error in m/s
uint32_t last_steer_to_wp_ms; // system time of last call to calc_steering_to_waypoint uint32_t last_steer_to_wp_ms; // system time of last call to calc_steering_to_waypoint
bool _reversed; // execute the mission by backing up
}; };
@ -247,8 +251,6 @@ public:
// start RTL (within auto) // start RTL (within auto)
void start_RTL(); void start_RTL();
// execute the mission in reverse (i.e. backing up)
void set_reversed(bool value);
protected: protected:
@ -272,7 +274,6 @@ private:
bool auto_triggered; bool auto_triggered;
bool _reached_heading; // true when vehicle has reached desired heading in TurnToHeading sub mode bool _reached_heading; // true when vehicle has reached desired heading in TurnToHeading sub mode
bool _reversed; // execute the mission by backing up
}; };

View File

@ -140,14 +140,6 @@ void ModeAuto::start_RTL()
} }
} }
// execute the mission in reverse (i.e. backing up)
void ModeAuto::set_reversed(bool value)
{
if (_reversed != value) {
_reversed = value;
}
}
/* /*
check for triggering of start of auto mode check for triggering of start of auto mode
*/ */