From 1aade494fcddd9c88e87e9bcb9a50feb4ac6adad Mon Sep 17 00:00:00 2001 From: Paul Riseborough Date: Fri, 8 Jan 2016 18:34:16 +1100 Subject: [PATCH] AP_State: enable use of motor interlock during throw mode --- ArduCopter/AP_State.cpp | 5 +++-- 1 file changed, 3 insertions(+), 2 deletions(-) diff --git a/ArduCopter/AP_State.cpp b/ArduCopter/AP_State.cpp index 5c98ecdc88..bce42fa40c 100644 --- a/ArduCopter/AP_State.cpp +++ b/ArduCopter/AP_State.cpp @@ -120,8 +120,9 @@ void Copter::update_using_interlock() // helicopters are always using motor interlock ap.using_interlock = true; #else - // check if we are using motor interlock control on an aux switch - ap.using_interlock = check_if_auxsw_mode_used(AUXSW_MOTOR_INTERLOCK); + // check if we are using motor interlock control on an aux switch or are in throw mode + // which uses the interlock to stop motors while the copter is being thrown + ap.using_interlock = check_if_auxsw_mode_used(AUXSW_MOTOR_INTERLOCK) || (control_mode == THROW); #endif }