mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-08 17:08:28 -04:00
AP_Math: use DEG_TO_RAD in longitude_scale
Also increased accuracy of RadiansToCentiDegrees although it is like the compiler will throw away the extra digits anyway.
This commit is contained in:
parent
ae2ad8e819
commit
7c9d9b9800
@ -25,7 +25,7 @@
|
||||
#define DEG_TO_RAD 0.017453292519943295769236907684886f
|
||||
#define RAD_TO_DEG 57.295779513082320876798154814105f
|
||||
|
||||
#define RadiansToCentiDegrees(x) ((x) * 5729.578f)
|
||||
#define RadiansToCentiDegrees(x) ((x) * 5729.5779513082320876798154814105f)
|
||||
|
||||
// acceleration due to gravity in m/s/s
|
||||
#define GRAVITY_MSS 9.80665f
|
||||
|
@ -36,7 +36,7 @@ float longitude_scale(const struct Location *loc)
|
||||
// the same scale factor.
|
||||
return scale;
|
||||
}
|
||||
scale = cosf((fabsf((float)loc->lat)/1.0e7f) * 0.0174532925f);
|
||||
scale = cosf((fabsf((float)loc->lat)/1.0e7f) * DEG_TO_RAD);
|
||||
last_lat = loc->lat;
|
||||
return scale;
|
||||
}
|
||||
|
Loading…
Reference in New Issue
Block a user