mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-29 20:18:31 -04:00
AP_Math: move location define to Location class
This commit is contained in:
parent
65b4ba0539
commit
ff4587a33a
@ -114,4 +114,10 @@ public:
|
||||
|
||||
private:
|
||||
static AP_Terrain *_terrain;
|
||||
|
||||
// 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;
|
||||
// inverse of LOCATION_SCALING_FACTOR
|
||||
static constexpr float LOCATION_SCALING_FACTOR_INV = 89.83204953368922f;
|
||||
};
|
||||
|
@ -4,13 +4,6 @@
|
||||
|
||||
#include "vector2.h"
|
||||
#include "vector3.h"
|
||||
#include <AP_Common/Location.h>
|
||||
|
||||
// scaling factor from 1e-7 degrees to meters at equator
|
||||
// == 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
|
||||
|
Loading…
Reference in New Issue
Block a user