Copter: fix auto-disarm check

Copters go to SHUT_DOWN when estop is engaged
This commit is contained in:
Randy Mackay 2019-04-12 13:53:34 +09:00
parent ac7e969aae
commit 403195d9d4

View File

@ -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;
}