Rover: set_desired_speed range checks speed

This commit is contained in:
Randy Mackay 2018-06-09 10:19:41 +09:00
parent b614ca9b75
commit 8464e82812
2 changed files with 12 additions and 2 deletions

View File

@ -216,6 +216,16 @@ void Mode::set_desired_speed_to_default(bool rtl)
_desired_speed = get_speed_default(rtl); _desired_speed = get_speed_default(rtl);
} }
// set desired speed in m/s
bool Mode::set_desired_speed(float speed)
{
if (!is_negative(speed)) {
_desired_speed = speed;
return true;
}
return false;
}
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

@ -104,8 +104,8 @@ 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)
float get_speed_default(bool rtl = false) const; float get_speed_default(bool rtl = false) const;
// set desired speed // set desired speed in m/s
void set_desired_speed(float speed) { _desired_speed = speed; } bool set_desired_speed(float speed);
// restore desired speed to default from parameter values (CRUISE_SPEED or WP_SPEED) // restore desired speed to default from parameter values (CRUISE_SPEED or WP_SPEED)
// 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)