From 73a3b5f83226b991013cb7107dc1f3ddec95f53c Mon Sep 17 00:00:00 2001 From: chobitsfan <chobits@itri.org.tw> Date: Tue, 23 Mar 2021 17:01:27 +0800 Subject: [PATCH] AC_Fence: remove unused declaration --- libraries/AC_Fence/AC_PolyFence_loader.h | 10 +--------- 1 file changed, 1 insertion(+), 9 deletions(-) diff --git a/libraries/AC_Fence/AC_PolyFence_loader.h b/libraries/AC_Fence/AC_PolyFence_loader.h index bc12e2499a..29dc7595a8 100644 --- a/libraries/AC_Fence/AC_PolyFence_loader.h +++ b/libraries/AC_Fence/AC_PolyFence_loader.h @@ -330,15 +330,7 @@ private: bool scale_latlon_from_origin(const Location &origin, const Vector2l &point, Vector2f &pos_cm) WARN_IF_UNUSED; - - // read_scaled_latlon_from_storage - reads a latitude/longitude - // from offset in permanent storage, transforms them into an - // offset-from-origin and deposits the result into pos_cm. - // read_offset is increased by the storage space used by the - // latitude/longitude - bool read_scaled_latlon_from_storage(const Location &origin, - uint16_t &read_offset, - Vector2f &pos_cm) WARN_IF_UNUSED; + // read_polygon_from_storage - reads vertex_count // latitude/longitude points from offset in permanent storage, // transforms them into an offset-from-origin and deposits the