From 7bd8d4880961dbc9fa4df6187ddf108f0cdeccc2 Mon Sep 17 00:00:00 2001 From: Randy Mackay Date: Thu, 16 Oct 2014 14:09:02 +0900 Subject: [PATCH] Copter: fence breach causes disarm if landed Previously it would only disarm if the throttle was also at zero. Pair programmed with Tridge --- ArduCopter/fence.pde | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/ArduCopter/fence.pde b/ArduCopter/fence.pde index e1eacf54b5..2285a349d4 100644 --- a/ArduCopter/fence.pde +++ b/ArduCopter/fence.pde @@ -28,9 +28,9 @@ void fence_check() // if the user wants some kind of response and motors are armed if(fence.get_action() != AC_FENCE_ACTION_REPORT_ONLY ) { - // disarm immediately if we think we are on the ground + // disarm immediately if we think we are on the ground or in a manual flight mode with zero throttle // don't disarm if the high-altitude fence has been broken because it's likely the user has pulled their throttle to zero to bring it down - if(ap.land_complete || manual_flight_mode(control_mode) && ap.throttle_zero && !failsafe.radio && ((fence.get_breaches() & AC_FENCE_TYPE_ALT_MAX)== 0)){ + if (ap.land_complete || (manual_flight_mode(control_mode) && ap.throttle_zero && !failsafe.radio && ((fence.get_breaches() & AC_FENCE_TYPE_ALT_MAX)== 0))){ init_disarm_motors(); }else{ // if we are within 100m of the fence, RTL