mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-02 05:58:30 -04:00
fix for navigation scaleLongUp
This commit is contained in:
parent
26705111e1
commit
4ff5d5016a
@ -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);
|
||||
|
||||
|
Loading…
Reference in New Issue
Block a user