From 683a2919d12b5a62ee09d50c30e98c2195b4f7a5 Mon Sep 17 00:00:00 2001 From: Andrew Tridgell Date: Tue, 2 Apr 2013 10:42:56 +1100 Subject: [PATCH] Plane: prevent stick mixing when throttle is below failsafe threshold this fixes issue #40 --- ArduPlane/Attitude.pde | 4 +++- 1 file changed, 3 insertions(+), 1 deletion(-) diff --git a/ArduPlane/Attitude.pde b/ArduPlane/Attitude.pde index 6c9c1d6037..b674045190 100644 --- a/ArduPlane/Attitude.pde +++ b/ArduPlane/Attitude.pde @@ -42,7 +42,9 @@ static bool stick_mixing_enabled(void) // we're in an auto mode. Check the stick mixing flag if (g.stick_mixing != STICK_MIXING_DISABLED && geofence_stickmixing() && - failsafe == FAILSAFE_NONE) { + failsafe == FAILSAFE_NONE && + (g.throttle_fs_enabled == 0 || + g.channel_throttle.radio_in >= g.throttle_fs_value)) { // we're in an auto mode, and haven't triggered failsafe return true; } else {