From 05a37dd54d433eff344d75a0fb02c4ff2ed03f6d Mon Sep 17 00:00:00 2001 From: Randy Mackay Date: Thu, 4 Sep 2014 12:37:26 +0900 Subject: [PATCH] Copter: add short delay to arming to allow RC input The short delay gives time for the RC inputs to be processed which removes the chance of a false-positive on the "late frame" radio check. A false positive could lead to an immediate disarm right after arming. --- ArduCopter/motors.pde | 3 +++ 1 file changed, 3 insertions(+) diff --git a/ArduCopter/motors.pde b/ArduCopter/motors.pde index f0feadafdf..f6c63442f7 100644 --- a/ArduCopter/motors.pde +++ b/ArduCopter/motors.pde @@ -197,6 +197,9 @@ static void init_arm_motors() sprayer.test_pump(false); #endif + // short delay to allow reading of rc inputs + delay(30); + // enable output to motors output_min();