Copter: use AP_Math's longitude_scale

bug fix to base scaling on home location instead of next_WP which may
not have been initialised
This commit is contained in:
Randy Mackay 2013-01-27 23:35:12 +09:00
parent 7729ec950e
commit 70371be4a1
1 changed files with 2 additions and 3 deletions

View File

@ -188,9 +188,8 @@ 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 = (fabsf((float)next_WP.lat)/t7) * 0.0174532925f; scaleLongDown = longitude_scale(&home);
scaleLongDown = cosf(rads); scaleLongUp = 1.0f/scaleLongDown;
scaleLongUp = 1.0f/cosf(rads);
// Save prev loc this makes the calcs look better before commands are loaded // Save prev loc this makes the calcs look better before commands are loaded
prev_WP = home; prev_WP = home;