mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-02 05:58:30 -04:00
Rover: Fix slew rate range
This commit is contained in:
parent
2986d3eb7d
commit
74d5767e25
@ -354,7 +354,7 @@ void AP_MotorsUGV::output_throttle(SRV_Channel::Aux_servo_function_t function, f
|
|||||||
void AP_MotorsUGV::slew_limit_throttle(float dt)
|
void AP_MotorsUGV::slew_limit_throttle(float dt)
|
||||||
{
|
{
|
||||||
if (_use_slew_rate && (_slew_rate > 0)) {
|
if (_use_slew_rate && (_slew_rate > 0)) {
|
||||||
float temp = _slew_rate * dt * 0.01f * 100.0f; // TODO : get THROTTLE MIN and THROTTLE MAX
|
float temp = _slew_rate * dt * 0.01f * (_throttle_max - _throttle_min);
|
||||||
if (temp < 1.0f) {
|
if (temp < 1.0f) {
|
||||||
temp = 1.0f;
|
temp = 1.0f;
|
||||||
}
|
}
|
||||||
|
Loading…
Reference in New Issue
Block a user