AP_Common: use longitude scaling from definitions.h

This commit is contained in:
Andrew Tridgell 2021-06-29 16:21:43 +10:00
parent 0e37a44942
commit 937f316d14

View File

@ -132,7 +132,7 @@ private:
// scaling factor from 1e-7 degrees to meters at equator
// == 1.0e-7 * DEG_TO_RAD * RADIUS_OF_EARTH
static constexpr float LOCATION_SCALING_FACTOR = 0.011131884502145034f;
static constexpr float LOCATION_SCALING_FACTOR = LATLON_TO_M;
// inverse of LOCATION_SCALING_FACTOR
static constexpr float LOCATION_SCALING_FACTOR_INV = 89.83204953368922f;
static constexpr float LOCATION_SCALING_FACTOR_INV = LATLON_TO_M_INV;
};