From c7d16d2c3bbfe6df2b2014c7863b51f816bc22bc Mon Sep 17 00:00:00 2001 From: Randy Mackay Date: Thu, 24 Oct 2013 16:42:14 +0900 Subject: [PATCH] Copter: remove unnecessary check of flight mode from fence response --- ArduCopter/fence.pde | 8 +++----- 1 file changed, 3 insertions(+), 5 deletions(-) diff --git a/ArduCopter/fence.pde b/ArduCopter/fence.pde index 636c0bb9f7..3fa4cddcfb 100644 --- a/ArduCopter/fence.pde +++ b/ArduCopter/fence.pde @@ -39,14 +39,12 @@ void fence_check() if (GPS_ok()) { // if we are within 100m of the fence, RTL if( fence.get_breach_distance(new_breaches) <= AC_FENCE_GIVE_UP_DISTANCE) { - if(control_mode != RTL) { - set_mode(RTL); + if (!set_mode(RTL)) { + set_mode(LAND); } }else{ // if more than 100m outside the fence just force a land - if(control_mode != LAND) { - set_mode(LAND); - } + set_mode(LAND); } }else{ // we have no GPS so LAND