diff --git a/ArduCopter/system.cpp b/ArduCopter/system.cpp index c05006bd99..a60ae9f66f 100644 --- a/ArduCopter/system.cpp +++ b/ArduCopter/system.cpp @@ -369,6 +369,13 @@ void Copter::update_auto_armed() if(mode_has_manual_throttle(control_mode) && ap.throttle_zero && !failsafe.radio) { set_auto_armed(false); } +#if FRAME_CONFIG == HELI_FRAME + // if helicopters are on the ground, and the motor is switched off, auto-armed should be false + // so that rotor runup is checked again before attempting to take-off + if(ap.land_complete && !motors.rotor_runup_complete()) { + set_auto_armed(false); + } +#endif // HELI_FRAME }else{ // arm checks