From 213472102c941ce53229c4dfb6c4b32e8e921cfa Mon Sep 17 00:00:00 2001 From: Randy Mackay Date: Sat, 13 Jul 2013 20:25:34 +0900 Subject: [PATCH] Copter: pre-arm check of throttle failsafe value Check throttle min is above throttle failsafe trigger and that trigger is above ppm encoder's loss-of-signal value of 900 --- ArduCopter/motors.pde | 11 +++++++++++ 1 file changed, 11 insertions(+) diff --git a/ArduCopter/motors.pde b/ArduCopter/motors.pde index c73860ee08..317e50c9f7 100644 --- a/ArduCopter/motors.pde +++ b/ArduCopter/motors.pde @@ -284,6 +284,17 @@ static void pre_arm_checks(bool display_failure) } #endif + // failsafe parameter checks + if (g.failsafe_throttle) { + // check throttle min is above throttle failsafe trigger and that the trigger is above ppm encoder's loss-of-signal value of 900 + if (g.rc_3.radio_min <= g.failsafe_throttle_value+10 || g.failsafe_throttle_value < 910) { + if (display_failure) { + gcs_send_text_P(SEVERITY_HIGH,PSTR("PreArm: Check FS_THR_VALUE")); + } + return; + } + } + // if we've gotten this far then pre arm checks have completed ap.pre_arm_check = true; }