From 062ee71135e844a048b0b2a15d14fdbb5629c743 Mon Sep 17 00:00:00 2001 From: Peter Barker Date: Thu, 30 May 2019 14:25:22 +1000 Subject: [PATCH] AC_Fence: simplify fence loading There's only one caller to this, who didn't force loading - so remove the unused parameter. Also remove the _boundary_loaded boolean; it was only set to true in one place - just before the sole caller called the function! --- libraries/AC_Fence/AC_Fence.cpp | 9 +-------- libraries/AC_Fence/AC_Fence.h | 3 +-- 2 files changed, 2 insertions(+), 10 deletions(-) diff --git a/libraries/AC_Fence/AC_Fence.cpp b/libraries/AC_Fence/AC_Fence.cpp index d99c52312b..e973c38932 100644 --- a/libraries/AC_Fence/AC_Fence.cpp +++ b/libraries/AC_Fence/AC_Fence.cpp @@ -261,7 +261,6 @@ bool AC_Fence::polygon_fence_is_breached() // check consistency of number of points if (_boundary_num_points != _total) { // Fence is currently not completely loaded. Can't breach it?! - _boundary_loaded = false; load_polygon_from_eeprom(); return false; } @@ -535,13 +534,8 @@ void AC_Fence::handle_msg(GCS_MAVLINK &link, mavlink_message_t* msg) } /// load polygon points stored in eeprom into boundary array and perform validation -bool AC_Fence::load_polygon_from_eeprom(bool force_reload) +bool AC_Fence::load_polygon_from_eeprom() { - // exit immediately if already loaded - if (_boundary_loaded && !force_reload) { - return true; - } - // check if we need to create array if (!_boundary_create_attempted) { _boundary = (Vector2f *)_poly_loader.create_point_array(sizeof(Vector2f)); @@ -579,7 +573,6 @@ bool AC_Fence::load_polygon_from_eeprom(bool force_reload) _boundary[index] = ekf_origin.get_distance_NE(temp_loc) * 100.0f; } _boundary_num_points = _total; - _boundary_loaded = true; // update validity of polygon _boundary_valid = _poly_loader.boundary_valid(_boundary_num_points, _boundary); diff --git a/libraries/AC_Fence/AC_Fence.h b/libraries/AC_Fence/AC_Fence.h index f8537b4588..946a780f95 100644 --- a/libraries/AC_Fence/AC_Fence.h +++ b/libraries/AC_Fence/AC_Fence.h @@ -142,7 +142,7 @@ private: bool pre_arm_check_alt(const char* &fail_msg) const; /// load polygon points stored in eeprom into boundary array and perform validation. returns true if load successfully completed - bool load_polygon_from_eeprom(bool force_reload = false); + bool load_polygon_from_eeprom(); // returns true if we have breached the fence: bool polygon_fence_is_breached(); @@ -182,7 +182,6 @@ private: Vector2f *_boundary = nullptr; // array of boundary points. Note: point 0 is the return point uint8_t _boundary_num_points = 0; // number of points in the boundary array (should equal _total parameter after load has completed) bool _boundary_create_attempted = false; // true if we have attempted to create the boundary array - bool _boundary_loaded = false; // true if boundary array has been loaded from eeprom bool _boundary_valid = false; // true if boundary forms a closed polygon };