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:
Andrew Tridgell 2018-06-01 10:32:44 +10:00 committed by Randy Mackay
parent 25961b6d13
commit b8d47f346e

View File

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