mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-03 14:38:30 -04:00
Copter: fixed interlock check on helis
the motors check is always false when disarmed, so can't be used for arming check
This commit is contained in:
parent
25961b6d13
commit
b8d47f346e
@ -597,7 +597,7 @@ bool AP_Arming_Copter::arm_checks(bool display_failure, bool arming_from_gcs)
|
|||||||
|
|
||||||
// if we are using motor interlock switch and it's enabled, fail to arm
|
// if we are using motor interlock switch and it's enabled, fail to arm
|
||||||
// skip check in Throw mode which takes control of the motor interlock
|
// skip check in Throw mode which takes control of the motor interlock
|
||||||
if (copter.ap.using_interlock && copter.motors->get_interlock()) {
|
if (copter.ap.using_interlock && copter.ap.motor_interlock_switch) {
|
||||||
gcs().send_text(MAV_SEVERITY_CRITICAL,"Arm: Motor Interlock Enabled");
|
gcs().send_text(MAV_SEVERITY_CRITICAL,"Arm: Motor Interlock Enabled");
|
||||||
return false;
|
return false;
|
||||||
}
|
}
|
||||||
|
Loading…
Reference in New Issue
Block a user