From 9eebb6225ad7f2c8807215b4e8cc09aed9718eb4 Mon Sep 17 00:00:00 2001 From: Randy Mackay Date: Thu, 19 Jul 2018 07:55:26 +0800 Subject: [PATCH] AR_AttitudeControl: brake fix to set limit in only one direction --- libraries/APM_Control/AR_AttitudeControl.cpp | 3 +-- 1 file changed, 1 insertion(+), 2 deletions(-) diff --git a/libraries/APM_Control/AR_AttitudeControl.cpp b/libraries/APM_Control/AR_AttitudeControl.cpp index 4de6c06071..6d1ba11d9d 100644 --- a/libraries/APM_Control/AR_AttitudeControl.cpp +++ b/libraries/APM_Control/AR_AttitudeControl.cpp @@ -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; }