From 6d472376bba8f08f2e51186313f5cfc5151fd8e6 Mon Sep 17 00:00:00 2001 From: Randy Mackay Date: Thu, 30 Nov 2017 20:13:11 +0900 Subject: [PATCH] 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. --- APMrover2/AP_MotorsUGV.cpp | 11 ----------- 1 file changed, 11 deletions(-) diff --git a/APMrover2/AP_MotorsUGV.cpp b/APMrover2/AP_MotorsUGV.cpp index 331a72a634..3d53bda532 100644 --- a/APMrover2/AP_MotorsUGV.cpp +++ b/APMrover2/AP_MotorsUGV.cpp @@ -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