AR_Motors: remove redundant set of throttle limit flags

set_limits_from_input is called lower in the method and will set the limits correctly
This commit is contained in:
Randy Mackay 2022-02-14 20:00:50 +09:00
parent 0ecbfa5ba9
commit 4a2af10f96
1 changed files with 0 additions and 6 deletions

View File

@ -667,12 +667,6 @@ void AP_MotorsUGV::output_regular(bool armed, float ground_speed, float steering
const float throttle_scaler_inv = cosf(steering_angle_rad);
if (!is_zero(throttle_scaler_inv)) {
throttle /= throttle_scaler_inv;
if (throttle >= 100.0f) {
limit.throttle_upper = true;
}
if (throttle <= -100.0f) {
limit.throttle_lower = true;
}
}
}
} else {