From a0c6ff95e47cf17c39de0fa3b4ed4e5e2a3b51e3 Mon Sep 17 00:00:00 2001 From: Peter Barker Date: Mon, 16 Sep 2019 15:24:46 +1000 Subject: [PATCH] AP_Proximity: polyfence valid() has been renamed --- libraries/AP_Proximity/AP_Proximity_SITL.cpp | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/libraries/AP_Proximity/AP_Proximity_SITL.cpp b/libraries/AP_Proximity/AP_Proximity_SITL.cpp index d198a2b33d..0fc2af602f 100644 --- a/libraries/AP_Proximity/AP_Proximity_SITL.cpp +++ b/libraries/AP_Proximity/AP_Proximity_SITL.cpp @@ -51,7 +51,7 @@ void AP_Proximity_SITL::update(void) if (!AP::fence()->polyfence().breached()) { // only called to prompt polyfence to reload fence if required } - if (AP::fence()->polyfence().valid()) { + if (AP::fence()->polyfence().inclusion_boundary_available()) { // update distance in one sector if (get_distance_to_fence(_sector_middle_deg[last_sector], _distance[last_sector])) { set_status(AP_Proximity::Proximity_Good); @@ -73,7 +73,7 @@ void AP_Proximity_SITL::update(void) // get distance in meters to fence in a particular direction in degrees (0 is forward, angles increase in the clockwise direction) bool AP_Proximity_SITL::get_distance_to_fence(float angle_deg, float &distance) const { - if (!AP::fence()->polyfence().valid()) { + if (!AP::fence()->polyfence().inclusion_boundary_available()) { return false; }