mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-22 07:44:03 -04:00
AP_Math: fixed the value LATLON_TO_CM
it didn't have enough digits of precision, and was inconsistent with LOCATION_SCALING_FACTOR
This commit is contained in:
parent
982b044d00
commit
0e37a44942
@ -51,8 +51,9 @@ static const double RAD_TO_DEG_DOUBLE = 1 / DEG_TO_RAD_DOUBLE;
|
||||
|
||||
// convert a longitude or latitude point to meters or centimeters.
|
||||
// Note: this does not include the longitude scaling which is dependent upon location
|
||||
#define LATLON_TO_M 0.01113195f
|
||||
#define LATLON_TO_CM 1.113195f
|
||||
#define LATLON_TO_M 0.011131884502145034
|
||||
#define LATLON_TO_M_INV 89.83204953368922
|
||||
#define LATLON_TO_CM 1.1131884502145034
|
||||
|
||||
// Semi-major axis of the Earth, in meters.
|
||||
static const double WGS84_A = 6378137.0;
|
||||
|
Loading…
Reference in New Issue
Block a user