From a6d2e0d4dfb775488f1a0e2ad59ebc4c14073c03 Mon Sep 17 00:00:00 2001 From: Fredrik Hedberg Date: Fri, 6 Nov 2015 23:36:56 +0100 Subject: [PATCH] Copter: Don't auto-disarm helicopters if rotor is still spinning. --- ArduCopter/motors.cpp | 8 ++++++++ 1 file changed, 8 insertions(+) diff --git a/ArduCopter/motors.cpp b/ArduCopter/motors.cpp index 03a40fe4b1..ed41f1b070 100644 --- a/ArduCopter/motors.cpp +++ b/ArduCopter/motors.cpp @@ -82,6 +82,14 @@ void Copter::auto_disarm_check() return; } +#if FRAME_CONFIG == HELI_FRAME + // if the rotor is still spinning, don't initiate auto disarm + if (motors.rotor_speed_above_critical()) { + auto_disarming_counter = 0; + return; + } +#endif + // always allow auto disarm if using interlock switch or motors are Emergency Stopped if ((ap.using_interlock && !motors.get_interlock()) || ap.motor_emergency_stop) { #if FRAME_CONFIG != HELI_FRAME