diff --git a/ArduCopter/fence.pde b/ArduCopter/fence.pde index 0344d6a5014bc7b4785cd8b958d1357ed4e22df4..1eadc1f8e27d9dbcfcb6775be16865debb729bd4 100644 --- a/ArduCopter/fence.pde +++ b/ArduCopter/fence.pde @@ -36,7 +36,7 @@ void fence_check() init_disarm_motors(); }else{ // if we have a GPS - if( ap.home_is_set ) { + if( ap.home_is_set && g_gps->status() == GPS::GPS_OK_FIX_3D ) { // 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) {