diff --git a/ArduPlane/radio.cpp b/ArduPlane/radio.cpp index eb5ea21dd2..65c735e9fb 100644 --- a/ArduPlane/radio.cpp +++ b/ArduPlane/radio.cpp @@ -430,7 +430,7 @@ bool Plane::throttle_at_zero(void) const to center stick area in conjunction with sprung throttle, cannot use in_trim, must use rc_min */ if (((!(g2.flight_options & FlightOptions::CENTER_THROTTLE_TRIM) && channel_throttle->in_trim_dz()) || - (g2.flight_options & FlightOptions::CENTER_THROTTLE_TRIM && channel_throttle->within_min_dz()))) { + (g2.flight_options & FlightOptions::CENTER_THROTTLE_TRIM && channel_throttle->in_min_dz()))) { return true; } return false;