diff --git a/ArduCopter/commands.pde b/ArduCopter/commands.pde index 185e52fff3b0117cf641e85247475dde52945586..e1c2d3828f3c73d0e29711de3afa0aa0c5ed8919 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);