Browse Source

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.
mission-4.1.18
Randy Mackay 7 years ago
parent
commit
6d472376bb
  1. 11
      APMrover2/AP_MotorsUGV.cpp

11
APMrover2/AP_MotorsUGV.cpp

@ -258,17 +258,6 @@ void AP_MotorsUGV::output_skid_steering(bool armed, float steering, float thrott @@ -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

Loading…
Cancel
Save