AP_Common: Move LOCATION_ALT_MAX_M declaration from AP_Common.h to Location.h
This reduces the scope of this constant, and moves it to the file that actually depends on it
This commit is contained in:
parent
e23809fd59
commit
8b54b6a5cf
@ -62,8 +62,6 @@
|
||||
inline uint8_t &operator[](size_t i) { return reinterpret_cast<uint8_t *>(this)[i]; } \
|
||||
inline uint8_t operator[](size_t i) const { return reinterpret_cast<const uint8_t *>(this)[i]; }
|
||||
|
||||
#define LOCATION_ALT_MAX_M 83000 // maximum altitude (in meters) that can be fit into Location structure's alt field
|
||||
|
||||
/*
|
||||
check if bit bitnumber is set in value, returned as a
|
||||
bool. Bitnumber starts at 0 for the first bit
|
||||
|
@ -14,6 +14,8 @@
|
||||
class AP_AHRS_NavEKF;
|
||||
class AP_Terrain;
|
||||
|
||||
#define LOCATION_ALT_MAX_M 83000 // maximum altitude (in meters) that can be fit into Location structure's alt field
|
||||
|
||||
class Location
|
||||
{
|
||||
public:
|
||||
|
Loading…
Reference in New Issue
Block a user