Browse Source

Copter: fixed interlock check on helis

the motors check is always false when disarmed, so can't be used for
arming check
mission-4.1.18
Andrew Tridgell 7 years ago committed by Randy Mackay
parent
commit
b8d47f346e
  1. 2
      ArduCopter/AP_Arming.cpp

2
ArduCopter/AP_Arming.cpp

@ -597,7 +597,7 @@ bool AP_Arming_Copter::arm_checks(bool display_failure, bool arming_from_gcs) @@ -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;
}

Loading…
Cancel
Save