From f9add59b58d9c8a959ac868340e2cda7b068b5e2 Mon Sep 17 00:00:00 2001 From: murata Date: Wed, 9 Nov 2016 00:51:07 +0900 Subject: [PATCH] Global: Aggregate the same definitions. Global: Aggregate the same definitions. --- libraries/AP_Common/AP_Common.h | 1 - libraries/AP_Common/Location.cpp | 4 ---- libraries/AP_Math/location.cpp | 6 ------ libraries/AP_Math/location.h | 5 +++++ 4 files changed, 5 insertions(+), 11 deletions(-) diff --git a/libraries/AP_Common/AP_Common.h b/libraries/AP_Common/AP_Common.h index 4928cdae00..8c7d9fe022 100644 --- a/libraries/AP_Common/AP_Common.h +++ b/libraries/AP_Common/AP_Common.h @@ -167,4 +167,3 @@ bool is_bounded_int32(int32_t value, int32_t lower_bound, int32_t upper_bound); #else #define SITL_printf(fmt, args ...) #endif - diff --git a/libraries/AP_Common/Location.cpp b/libraries/AP_Common/Location.cpp index 0190035495..7de5e3c97a 100644 --- a/libraries/AP_Common/Location.cpp +++ b/libraries/AP_Common/Location.cpp @@ -13,10 +13,6 @@ extern const AP_HAL::HAL& hal; const AP_AHRS_NavEKF *Location_Class::_ahrs = nullptr; AP_Terrain *Location_Class::_terrain = nullptr; -// scalers to convert latitude and longitude to meters. Duplicated from location.cpp -#define LOCATION_SCALING_FACTOR 0.011131884502145034f -#define LOCATION_SCALING_FACTOR_INV 89.83204953368922f - /// constructors Location_Class::Location_Class() { diff --git a/libraries/AP_Math/location.cpp b/libraries/AP_Math/location.cpp index d980674e7f..17dffdeb8b 100644 --- a/libraries/AP_Math/location.cpp +++ b/libraries/AP_Math/location.cpp @@ -24,12 +24,6 @@ #include "AP_Math.h" #include "location.h" -// scaling factor from 1e-7 degrees to meters at equater -// == 1.0e-7 * DEG_TO_RAD * RADIUS_OF_EARTH -#define LOCATION_SCALING_FACTOR 0.011131884502145034f -// inverse of LOCATION_SCALING_FACTOR -#define LOCATION_SCALING_FACTOR_INV 89.83204953368922f - float longitude_scale(const struct Location &loc) { #if HAL_CPU_CLASS < HAL_CPU_CLASS_150 diff --git a/libraries/AP_Math/location.h b/libraries/AP_Math/location.h index d96247c5f6..bf32e5484f 100644 --- a/libraries/AP_Math/location.h +++ b/libraries/AP_Math/location.h @@ -8,6 +8,11 @@ #include "vector2.h" #include "vector3.h" +// scaling factor from 1e-7 degrees to meters at equater +// == 1.0e-7 * DEG_TO_RAD * RADIUS_OF_EARTH +#define LOCATION_SCALING_FACTOR 0.011131884502145034f +// inverse of LOCATION_SCALING_FACTOR +#define LOCATION_SCALING_FACTOR_INV 89.83204953368922f /* * LOCATION