From 421524951f6b553d0b221acfe3ddaab042f8dae2 Mon Sep 17 00:00:00 2001 From: Pierre Kancir Date: Thu, 1 Dec 2016 16:53:25 +0100 Subject: [PATCH] AC_PosControl: remove unnecessary parentheses --- libraries/AC_AttitudeControl/AC_PosControl.cpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/libraries/AC_AttitudeControl/AC_PosControl.cpp b/libraries/AC_AttitudeControl/AC_PosControl.cpp index 03d5d20902..29149bb1b2 100644 --- a/libraries/AC_AttitudeControl/AC_PosControl.cpp +++ b/libraries/AC_AttitudeControl/AC_PosControl.cpp @@ -941,7 +941,7 @@ void AC_PosControl::rate_to_accel_xy(float dt, float ekfNavVelGainScaler) vel_xy_p = _pi_vel_xy.get_p(); // update i term if we have not hit the accel or throttle limits OR the i term will reduce - if ((!_limit.accel_xy && !_motors.limit.throttle_upper)) { + if (!_limit.accel_xy && !_motors.limit.throttle_upper) { vel_xy_i = _pi_vel_xy.get_i(); } else { vel_xy_i = _pi_vel_xy.get_i_shrink();