From 43e06e9040238e7eeda06240856358b9a75e9fb6 Mon Sep 17 00:00:00 2001 From: James O'Shannessy <12959316+joshanne@users.noreply.github.com> Date: Thu, 4 Mar 2021 01:05:48 +1100 Subject: [PATCH] AC_Fence: Fix int32_t overflow with large longitude values --- libraries/AC_Fence/AC_PolyFence_loader.cpp | 7 +++++-- 1 file changed, 5 insertions(+), 2 deletions(-) diff --git a/libraries/AC_Fence/AC_PolyFence_loader.cpp b/libraries/AC_Fence/AC_PolyFence_loader.cpp index d7a1d1d897..c89833dd41 100644 --- a/libraries/AC_Fence/AC_PolyFence_loader.cpp +++ b/libraries/AC_Fence/AC_PolyFence_loader.cpp @@ -1186,8 +1186,11 @@ bool AC_PolyFence_loader::get_return_point(Vector2l &ret) } } - ret.x = ((min_loc.x+max_loc.x)/2); - ret.y = ((min_loc.y+max_loc.y)/2); + // Potential for int32_t overflow when longitudes are beyond [-107, 107]. + // As a result, the calculated return point's longitude is calculated using overflowed figure. + // Dividing first before adding avoids the potential overflow. + ret.x = (min_loc.x / 2) + (max_loc.x / 2); + ret.y = (min_loc.y / 2) + (max_loc.y / 2); return true; }