Global: Aggregate the same definitions.

Global: Aggregate the same definitions.
This commit is contained in:
murata 2016-11-09 00:51:07 +09:00 committed by Lucas De Marchi
parent c1647b13eb
commit f9add59b58
4 changed files with 5 additions and 11 deletions

View File

@ -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

View File

@ -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()
{

View File

@ -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

View File

@ -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