From c5b119288da6461f6fac7fe3370e12a9c02ad2ab Mon Sep 17 00:00:00 2001 From: Robert Lefebvre Date: Fri, 19 Jul 2013 16:16:37 -0400 Subject: [PATCH] TradHeli: Add Motor Runup check to the auto_arming check. --- ArduCopter/system.pde | 6 ++++++ 1 file changed, 6 insertions(+) diff --git a/ArduCopter/system.pde b/ArduCopter/system.pde index d493146baf..4f7cb4957c 100644 --- a/ArduCopter/system.pde +++ b/ArduCopter/system.pde @@ -495,8 +495,14 @@ static void update_auto_armed() } }else{ // arm checks + +#if FRAME_CONFIG == HELI_FRAME + // for tradheli if motors are armed and throttle is above zero and the motor is started, auto_armed should be true + if(motors.armed() && g.rc_3.control_in != 0 && motors.motor_runup_complete) { +#else // if motors are armed and throttle is above zero auto_armed should be true if(motors.armed() && g.rc_3.control_in != 0) { +#endif // HELI_FRAME set_auto_armed(true); } }