AP_Terrain: add static create method

This commit is contained in:
Lucas De Marchi 2017-08-29 17:02:24 -07:00 committed by Francisco Ferreira
parent 70d8a08626
commit 122f3d110b
1 changed files with 16 additions and 5 deletions

View File

@ -74,17 +74,26 @@
file: first entries increase east, then north
*/
class AP_Terrain
{
class AP_Terrain {
public:
AP_Terrain(AP_AHRS &_ahrs, const AP_Mission &_mission, const AP_Rally &_rally);
enum TerrainStatus {
TerrainStatusDisabled = 0, // not enabled
TerrainStatusUnhealthy = 1, // no terrain data for current location
TerrainStatusOK = 2 // terrain data available
};
static AP_Terrain create(AP_AHRS &_ahrs,
const AP_Mission &_mission,
const AP_Rally &_rally) {
return AP_Terrain{_ahrs, _mission, _rally};
}
constexpr AP_Terrain(AP_Terrain &&other) = default;
/* Do not allow copies */
AP_Terrain(const AP_Terrain &other) = delete;
AP_Terrain &operator=(const AP_Terrain&) = delete;
static const struct AP_Param::GroupInfo var_info[];
// update terrain state. Should be called at 1Hz or more
@ -175,6 +184,8 @@ public:
void get_statistics(uint16_t &pending, uint16_t &loaded);
private:
AP_Terrain(AP_AHRS &_ahrs, const AP_Mission &_mission, const AP_Rally &_rally);
// allocate the terrain subsystem data
bool allocate(void);