From dbbfba3686fab5f58b15178c50900a43e9525cf0 Mon Sep 17 00:00:00 2001
From: Randy Mackay <rmackay9@yahoo.com>
Date: Thu, 31 Jan 2013 21:39:26 +0900
Subject: [PATCH] Copter: use home position for scaling Longitude

---
 ArduCopter/commands.pde | 2 +-
 1 file changed, 1 insertion(+), 1 deletion(-)

diff --git a/ArduCopter/commands.pde b/ArduCopter/commands.pde
index 185e52fff..e1c2d3828 100644
--- a/ArduCopter/commands.pde
+++ b/ArduCopter/commands.pde
@@ -188,7 +188,7 @@ static void init_home()
         Log_Write_Cmd(0, &home);
 
     // update navigation scalers.  used to offset the shrinking longitude as we go towards the poles
-    float rads              = (fabs((float)next_WP.lat)/t7) * 0.0174532925;
+    float rads              = (fabs((float)home.lat)/t7) * 0.0174532925;
     scaleLongDown           = cos(rads);
     scaleLongUp             = 1.0f/cos(rads);
 
-- 
GitLab