AP_MotorsUGV: do not limit just because of saturation

steering and throttle limit flags should only be set when there is no point in the caller passing in higher values because it will not result in an increased response.  In the case of saturation, higher inputs will still result in a higher response.
This commit is contained in:
Randy Mackay 2017-11-30 20:13:11 +09:00
parent 5612292802
commit 6d472376bb
1 changed files with 0 additions and 11 deletions

View File

@ -258,17 +258,6 @@ void AP_MotorsUGV::output_skid_steering(bool armed, float steering, float thrott
if (saturation_value > 1.0f) {
steering_scaled = steering_scaled / saturation_value;
throttle_scaled = throttle_scaled / saturation_value;
// set limits
if (is_negative(steering)) {
limit.steer_left = true;
} else {
limit.steer_right = true;
}
if (is_negative(throttle)) {
limit.throttle_lower = true;
} else {
limit.throttle_upper = true;
}
}
// add in throttle