From c05d239069b133cf0594031ca37c700a5e563a20 Mon Sep 17 00:00:00 2001 From: Randy Mackay Date: Mon, 26 Mar 2018 19:07:31 +0900 Subject: [PATCH] Rover: remove throttle scaling dependency on throttle range --- APMrover2/AP_MotorsUGV.cpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/APMrover2/AP_MotorsUGV.cpp b/APMrover2/AP_MotorsUGV.cpp index c2e2d05c53..58fa713cb8 100644 --- a/APMrover2/AP_MotorsUGV.cpp +++ b/APMrover2/AP_MotorsUGV.cpp @@ -472,7 +472,7 @@ void AP_MotorsUGV::slew_limit_throttle(float dt) { if (_slew_rate > 0) { // slew throttle - const float throttle_change_max = MAX(1.0f, _slew_rate * dt * 0.01f * (_throttle_max - _throttle_min)); + const float throttle_change_max = MAX(1.0f, (float)_slew_rate * dt); if (_throttle > _throttle_prev + throttle_change_max) { _throttle = _throttle_prev + throttle_change_max; limit.throttle_upper = true;