From 937f316d14b418ff77f110823670ac8c81226f36 Mon Sep 17 00:00:00 2001 From: Andrew Tridgell Date: Tue, 29 Jun 2021 16:21:43 +1000 Subject: [PATCH] AP_Common: use longitude scaling from definitions.h --- libraries/AP_Common/Location.h | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/libraries/AP_Common/Location.h b/libraries/AP_Common/Location.h index 552348218c..b083258e93 100644 --- a/libraries/AP_Common/Location.h +++ b/libraries/AP_Common/Location.h @@ -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; };