diff --git a/ArduPlane/radio.cpp b/ArduPlane/radio.cpp index c80205d2b3..dafa8cce73 100644 --- a/ArduPlane/radio.cpp +++ b/ArduPlane/radio.cpp @@ -188,7 +188,7 @@ void Plane::read_radio() channel_throttle->servo_out = channel_throttle->control_in; - if (g.throttle_nudge && channel_throttle->servo_out > 50) { + if (g.throttle_nudge && channel_throttle->servo_out > 50 && geofence_stickmixing()) { float nudge = (channel_throttle->servo_out - 50) * 0.02f; if (ahrs.airspeed_sensor_enabled()) { airspeed_nudge_cm = (aparm.airspeed_max * 100 - g.airspeed_cruise_cm) * nudge;