From 403195d9d4847ed882bf8fdadfcb5399746808a7 Mon Sep 17 00:00:00 2001 From: Randy Mackay Date: Fri, 12 Apr 2019 13:53:34 +0900 Subject: [PATCH] Copter: fix auto-disarm check Copters go to SHUT_DOWN when estop is engaged --- ArduCopter/motors.cpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/ArduCopter/motors.cpp b/ArduCopter/motors.cpp index c41dd0423c..9bb0185b3c 100644 --- a/ArduCopter/motors.cpp +++ b/ArduCopter/motors.cpp @@ -94,7 +94,7 @@ void Copter::auto_disarm_check() } // if the rotor is still spinning, don't initiate auto disarm - if (motors->get_spool_state() != AP_Motors::SpoolState::GROUND_IDLE) { + if (motors->get_spool_state() > AP_Motors::SpoolState::GROUND_IDLE) { auto_disarm_begin = tnow_ms; return; }