From da41d854336257b99c02e737b386fec3200f1002 Mon Sep 17 00:00:00 2001 From: pepevalbe Date: Thu, 16 Jul 2015 19:47:08 +0200 Subject: [PATCH] Plane: It is possible to disarm with left rudder. Using is_flying() avoid accidentally disarming while flying. --- ArduPlane/Plane.h | 2 +- ArduPlane/radio.cpp | 67 +++++++++++++++++++++++++++------------------ 2 files changed, 42 insertions(+), 27 deletions(-) diff --git a/ArduPlane/Plane.h b/ArduPlane/Plane.h index 1dcc32cf1a..077b29d9e4 100644 --- a/ArduPlane/Plane.h +++ b/ArduPlane/Plane.h @@ -786,7 +786,7 @@ private: void set_control_channels(void); void init_rc_in(); void init_rc_out(); - void rudder_arm_check(); + void rudder_arm_disarm_check(); void read_radio(); void control_failsafe(uint16_t pwm); void trim_control_surfaces(); diff --git a/ArduPlane/radio.cpp b/ArduPlane/radio.cpp index 3ddba07a2a..614955b21e 100644 --- a/ArduPlane/radio.cpp +++ b/ArduPlane/radio.cpp @@ -76,8 +76,8 @@ void Plane::init_rc_out() } } -// check for pilot input on rudder stick for arming -void Plane::rudder_arm_check() +// check for pilot input on rudder stick for arming/disarming +void Plane::rudder_arm_disarm_check() { //TODO: ensure rudder arming disallowed during radio calibration @@ -85,45 +85,60 @@ void Plane::rudder_arm_check() static uint32_t rudder_arm_timer; - if (arming.is_armed()) { - //already armed, no need to run remainder of this function - rudder_arm_timer = 0; - return; - } - if (! arming.rudder_arming_enabled()) { - //parameter disallows rudder arming + //parameter disallows rudder arming/disabling return; } - //if throttle is not down, then pilot cannot rudder arm + //if throttle is not down, then pilot cannot rudder arm/disarm if (channel_throttle->control_in > 0) { rudder_arm_timer = 0; return; } - //if not in a 'manual' mode then disallow rudder arming + //if not in a 'manual' mode then disallow rudder arming/disarming if (auto_throttle_mode ) { rudder_arm_timer = 0; return; } - // full right rudder starts arming counter - if (channel_rudder->control_in > 4000) { - uint32_t now = millis(); + if (!arming.is_armed()) { + // when not armed, full right rudder starts arming counter + if (channel_rudder->control_in > 4000) { + uint32_t now = millis(); - if (rudder_arm_timer == 0 || - now - rudder_arm_timer < 3000) { + if (rudder_arm_timer == 0 || + now - rudder_arm_timer < 3000) { - if (rudder_arm_timer == 0) rudder_arm_timer = now; - } else { - //time to arm! - arm_motors(AP_Arming::RUDDER); - } - } else { - // not at full right rudder - rudder_arm_timer = 0; - } + if (rudder_arm_timer == 0) rudder_arm_timer = now; + } else { + //time to arm! + arm_motors(AP_Arming::RUDDER); + rudder_arm_timer = 0; + } + } else { + // not at full right rudder + rudder_arm_timer = 0; + } + } else if (!is_flying()) { + // when armed and not flying, full left rudder starts disarming counter + if (channel_rudder->control_in < -4000) { + uint32_t now = millis(); + + if (rudder_arm_timer == 0 || + now - rudder_arm_timer < 3000) { + + if (rudder_arm_timer == 0) rudder_arm_timer = now; + } else { + //time to disarm! + disarm_motors(); + rudder_arm_timer = 0; + } + } else { + // not at full left rudder + rudder_arm_timer = 0; + } + } } void Plane::read_radio() @@ -177,7 +192,7 @@ void Plane::read_radio() throttle_nudge = 0; } - rudder_arm_check(); + rudder_arm_disarm_check(); if (g.rudder_only != 0) { // in rudder only mode we discard rudder input and get target