From 85332ff85b0a58c3d11bef4248c888e11efbd635 Mon Sep 17 00:00:00 2001 From: Andrew Tridgell Date: Thu, 5 Jul 2012 15:04:42 +1000 Subject: [PATCH] GeoFence: fixed default return altitude units off by 100x! --- ArduPlane/geofence.pde | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/ArduPlane/geofence.pde b/ArduPlane/geofence.pde index 41223ae1e5..1de05e5aed 100644 --- a/ArduPlane/geofence.pde +++ b/ArduPlane/geofence.pde @@ -261,7 +261,7 @@ static void geofence_check(bool altitude_check_only) // min and max if (g.fence_minalt >= g.fence_maxalt) { // invalid min/max, use RTL_altitude - guided_WP.alt = home.alt + (g.RTL_altitude * 100); + guided_WP.alt = home.alt + g.RTL_altitude; } else { guided_WP.alt = home.alt + 100*(g.fence_minalt + g.fence_maxalt)/2; }