mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-09 01:18:29 -04:00
AR_AttitudeControl: brake fix to set limit in only one direction
This commit is contained in:
parent
fdd111a24d
commit
9eebb6225a
@ -434,8 +434,7 @@ float AR_AttitudeControl::get_throttle_out_speed(float desired_speed, bool motor
|
|||||||
if ((desired_speed >= 0.0f) && (throttle_out <= 0.0f)) {
|
if ((desired_speed >= 0.0f) && (throttle_out <= 0.0f)) {
|
||||||
throttle_out = 0.0f;
|
throttle_out = 0.0f;
|
||||||
_throttle_limit_low = true;
|
_throttle_limit_low = true;
|
||||||
}
|
} else if ((desired_speed <= 0.0f) && (throttle_out >= 0.0f)) {
|
||||||
if ((desired_speed <= 0.0f) && (throttle_out >= 0.0f)) {
|
|
||||||
throttle_out = 0.0f;
|
throttle_out = 0.0f;
|
||||||
_throttle_limit_high = true;
|
_throttle_limit_high = true;
|
||||||
}
|
}
|
||||||
|
Loading…
Reference in New Issue
Block a user