From b48ea53f60ccc8f4d467c0b15c621c528379365f Mon Sep 17 00:00:00 2001 From: murata Date: Fri, 9 Dec 2016 23:21:10 +0900 Subject: [PATCH] Revert "AC_Fence: Activate the create flag." This reverts commit c63a6a27380ebceabe4aabe0f730a6e92c67379d. --- libraries/AC_Fence/AC_Fence.cpp | 11 +++++------ 1 file changed, 5 insertions(+), 6 deletions(-) diff --git a/libraries/AC_Fence/AC_Fence.cpp b/libraries/AC_Fence/AC_Fence.cpp index bc41c66a5b..1fffaa7cdd 100644 --- a/libraries/AC_Fence/AC_Fence.cpp +++ b/libraries/AC_Fence/AC_Fence.cpp @@ -401,15 +401,14 @@ bool AC_Fence::load_polygon_from_eeprom(bool force_reload) // check if we need to create array if (!_boundary_create_attempted) { _boundary = (Vector2f *)_poly_loader.create_point_array(sizeof(Vector2f)); - - // exit if we could not allocate RAM for the boundary - if (_boundary == nullptr) { - return false; - } - _boundary_create_attempted = true; } + // exit if we could not allocate RAM for the boundary + if (_boundary == nullptr) { + return false; + } + // get current location from EKF Location temp_loc; if (!_inav.get_location(temp_loc)) {