mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-03 14:38:30 -04:00
AP_Common: clean includes up in Location.h
This commit is contained in:
parent
f66f36287e
commit
2352dd3f12
@ -7,8 +7,6 @@
|
|||||||
#include <AP_AHRS/AP_AHRS.h>
|
#include <AP_AHRS/AP_AHRS.h>
|
||||||
#include <AP_Terrain/AP_Terrain.h>
|
#include <AP_Terrain/AP_Terrain.h>
|
||||||
|
|
||||||
extern const AP_HAL::HAL& hal;
|
|
||||||
|
|
||||||
AP_Terrain *Location::_terrain = nullptr;
|
AP_Terrain *Location::_terrain = nullptr;
|
||||||
|
|
||||||
/// constructors
|
/// constructors
|
||||||
|
@ -1,17 +1,7 @@
|
|||||||
/*
|
#pragma once
|
||||||
* Location.h
|
|
||||||
*
|
|
||||||
*/
|
|
||||||
|
|
||||||
|
|
||||||
#ifndef LOCATION_H
|
|
||||||
#define LOCATION_H
|
|
||||||
|
|
||||||
#include <AP_Common/AP_Common.h>
|
|
||||||
#include <AP_Math/AP_Math.h>
|
#include <AP_Math/AP_Math.h>
|
||||||
#include <AP_HAL/AP_HAL.h>
|
|
||||||
|
|
||||||
class AP_AHRS_NavEKF;
|
|
||||||
class AP_Terrain;
|
class AP_Terrain;
|
||||||
|
|
||||||
#define LOCATION_ALT_MAX_M 83000 // maximum altitude (in meters) that can be fit into Location structure's alt field
|
#define LOCATION_ALT_MAX_M 83000 // maximum altitude (in meters) that can be fit into Location structure's alt field
|
||||||
@ -111,5 +101,3 @@ public:
|
|||||||
private:
|
private:
|
||||||
static AP_Terrain *_terrain;
|
static AP_Terrain *_terrain;
|
||||||
};
|
};
|
||||||
|
|
||||||
#endif /* LOCATION_H */
|
|
||||||
|
Loading…
Reference in New Issue
Block a user