mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-23 09:08:30 -04:00
Copter: Don't auto-disarm helicopters if rotor is still spinning.
This commit is contained in:
parent
5ff67a41a1
commit
a6d2e0d4df
@ -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
|
||||
|
Loading…
Reference in New Issue
Block a user