Skip to content
Snippets Groups Projects
Commit dbbfba36 authored by Randy Mackay's avatar Randy Mackay
Browse files

Copter: use home position for scaling Longitude

parent 5a3c7b2d
No related branches found
No related tags found
No related merge requests found
...@@ -188,7 +188,7 @@ static void init_home() ...@@ -188,7 +188,7 @@ static void init_home()
Log_Write_Cmd(0, &home); Log_Write_Cmd(0, &home);
// update navigation scalers. used to offset the shrinking longitude as we go towards the poles // 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); scaleLongDown = cos(rads);
scaleLongUp = 1.0f/cos(rads); scaleLongUp = 1.0f/cos(rads);
......
0% Loading or .
You are about to add 0 people to the discussion. Proceed with caution.
Finish editing this message first!
Please register or to comment