mirror of https://github.com/ArduPilot/ardupilot
AR_AttitudeControl: set-throttle-out-stop considered same as running speed controller
update the speed-last-ms time when set-throttle-out-stop runs or else the desired throttle will not be acceleration limited when the desired speed is next increased above zero
This commit is contained in:
parent
e846840a52
commit
a96c146758
|
@ -543,6 +543,8 @@ float AR_AttitudeControl::get_throttle_out_stop(bool motor_limit_low, bool motor
|
|||
if (stopped) {
|
||||
// update last time we thought we were stopped
|
||||
_stop_last_ms = now;
|
||||
// set last time speed controller was run so accelerations are limited
|
||||
_speed_last_ms = now;
|
||||
return 0.0f;
|
||||
}
|
||||
|
||||
|
|
Loading…
Reference in New Issue