From a685e5b5758270d1da4003ff6f032cb16c383b1b Mon Sep 17 00:00:00 2001 From: Jason Short Date: Sun, 11 Dec 2011 09:44:45 -0800 Subject: [PATCH] fix for navigation scaleLongUp --- ArduCopter/commands.pde | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/ArduCopter/commands.pde b/ArduCopter/commands.pde index 3fcc5d1f97..1f2baa1207 100644 --- a/ArduCopter/commands.pde +++ b/ArduCopter/commands.pde @@ -167,7 +167,7 @@ static void set_next_WP(struct Location *wp) target_altitude = current_loc.alt; // this is used to offset the shrinking longitude as we go towards the poles - float rads = (abs(next_WP.lat)/t7) * 0.0174532925; + float rads = (fabs((float)next_WP.lat)/t7) * 0.0174532925; scaleLongDown = cos(rads); scaleLongUp = 1.0f/cos(rads);