AR_AttitudeControl: brake fix to set limit in only one direction

This commit is contained in:
Randy Mackay 2018-07-19 07:55:26 +08:00
parent fdd111a24d
commit 9eebb6225a
1 changed files with 1 additions and 2 deletions

View File

@ -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)) {
throttle_out = 0.0f;
_throttle_limit_low = true;
}
if ((desired_speed <= 0.0f) && (throttle_out >= 0.0f)) {
} else if ((desired_speed <= 0.0f) && (throttle_out >= 0.0f)) {
throttle_out = 0.0f;
_throttle_limit_high = true;
}