From b8d47f346eb968b0d329035f72fc09a46f7116e6 Mon Sep 17 00:00:00 2001 From: Andrew Tridgell Date: Fri, 1 Jun 2018 10:32:44 +1000 Subject: [PATCH] Copter: fixed interlock check on helis the motors check is always false when disarmed, so can't be used for arming check --- ArduCopter/AP_Arming.cpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/ArduCopter/AP_Arming.cpp b/ArduCopter/AP_Arming.cpp index 1732ed3c0f..14b7846239 100644 --- a/ArduCopter/AP_Arming.cpp +++ b/ArduCopter/AP_Arming.cpp @@ -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 // 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"); return false; }