From 0b49ac0ed02e40a5c0e042a2e969bae162ae8810 Mon Sep 17 00:00:00 2001 From: Andrew Tridgell Date: Tue, 31 Jul 2012 15:46:47 +1000 Subject: [PATCH] APM: fixed overflow in geofence code for altitudes above 327 meters --- ArduPlane/geofence.pde | 6 +++--- 1 file changed, 3 insertions(+), 3 deletions(-) diff --git a/ArduPlane/geofence.pde b/ArduPlane/geofence.pde index ab5329e847..6f5469155f 100644 --- a/ArduPlane/geofence.pde +++ b/ArduPlane/geofence.pde @@ -151,7 +151,7 @@ static bool geofence_check_minalt(void) if (g.fence_minalt == 0) { return false; } - return (current_loc.alt < (g.fence_minalt*100) + home.alt); + return (current_loc.alt < (g.fence_minalt*100.0) + home.alt); } /* @@ -165,7 +165,7 @@ static bool geofence_check_maxalt(void) if (g.fence_maxalt == 0) { return false; } - return (current_loc.alt > (g.fence_maxalt*100) + home.alt); + return (current_loc.alt > (g.fence_maxalt*100.0) + home.alt); } @@ -263,7 +263,7 @@ static void geofence_check(bool altitude_check_only) // invalid min/max, use RTL_altitude guided_WP.alt = home.alt + g.RTL_altitude; } else { - guided_WP.alt = home.alt + 100*(g.fence_minalt + g.fence_maxalt)/2; + guided_WP.alt = home.alt + 100.0*(g.fence_minalt + g.fence_maxalt)/2; } guided_WP.id = 0; guided_WP.p1 = 0;