mirror of https://github.com/ArduPilot/ardupilot
Rover: remove throttle scaling dependency on throttle range
This commit is contained in:
parent
fa20fd695f
commit
c05d239069
|
@ -472,7 +472,7 @@ void AP_MotorsUGV::slew_limit_throttle(float dt)
|
||||||
{
|
{
|
||||||
if (_slew_rate > 0) {
|
if (_slew_rate > 0) {
|
||||||
// slew throttle
|
// 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) {
|
if (_throttle > _throttle_prev + throttle_change_max) {
|
||||||
_throttle = _throttle_prev + throttle_change_max;
|
_throttle = _throttle_prev + throttle_change_max;
|
||||||
limit.throttle_upper = true;
|
limit.throttle_upper = true;
|
||||||
|
|
Loading…
Reference in New Issue