mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-03 06:28:27 -04:00
Copter: fix auto-disarm check
Copters go to SHUT_DOWN when estop is engaged
This commit is contained in:
parent
ac7e969aae
commit
403195d9d4
@ -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;
|
||||
}
|
||||
|
Loading…
Reference in New Issue
Block a user