From f369899509cf8cb7179506c59907d91e3735513c Mon Sep 17 00:00:00 2001 From: Tom Pittenger Date: Wed, 10 Feb 2016 20:59:00 -0800 Subject: [PATCH] Plane: restrict rudder arming where reverse_thrust is enabled and commanding negative --- ArduPlane/arming_checks.cpp | 2 +- ArduPlane/radio.cpp | 2 +- 2 files changed, 2 insertions(+), 2 deletions(-) diff --git a/ArduPlane/arming_checks.cpp b/ArduPlane/arming_checks.cpp index f22be6f78d..19ae6d1291 100644 --- a/ArduPlane/arming_checks.cpp +++ b/ArduPlane/arming_checks.cpp @@ -10,7 +10,7 @@ const AP_Param::GroupInfo AP_Arming_Plane::var_info[] = { // @Param: RUDDER // @DisplayName: Rudder Arming - // @Description: Control arm/disarm by rudder input. When enabled arming is done with right rudder, disarming with left rudder. Rudder arming only works in manual throttle modes with throttle at zero + // @Description: Control arm/disarm by rudder input. When enabled arming is done with right rudder, disarming with left rudder. Rudder arming only works in manual throttle modes with throttle at zero +- deadzone (RCx_DZ) // @Values: 0:Disabled,1:ArmingOnly,2:ArmOrDisarm // @User: Advanced AP_GROUPINFO("RUDDER", 3, AP_Arming_Plane, rudder_arming_value, ARMING_RUDDER_ARMONLY), diff --git a/ArduPlane/radio.cpp b/ArduPlane/radio.cpp index a79b01bc71..bcdc9eda41 100644 --- a/ArduPlane/radio.cpp +++ b/ArduPlane/radio.cpp @@ -102,7 +102,7 @@ void Plane::rudder_arm_disarm_check() } // if throttle is not down, then pilot cannot rudder arm/disarm - if (channel_throttle->control_in > 0) { + if (channel_throttle->control_in != 0){ rudder_arm_timer = 0; return; }