Plane: Remove duplicated parameter check

This commit is contained in:
Paul Riseborough 2023-09-07 20:22:34 +10:00 committed by Andrew Tridgell
parent f834d4730b
commit 4993dcb814
1 changed files with 1 additions and 1 deletions

View File

@ -3613,7 +3613,7 @@ float QuadPlane::forward_throttle_pct()
#if QAUTOTUNE_ENABLED
if (is_positive(q_fwd_thr_gain) && plane.control_mode != &plane.mode_qautotune) {
#else
if (is_positive(q_fwd_thr_gain) && is_positive(q_fwd_thr_gain)) {
if (is_positive(q_fwd_thr_gain)) {
#endif
// handle special case where we are using forward throttle instead of forward tilt in Q modes
return 100.0f * q_fwd_throttle;