AP_Terrain: removed create() method for objects

See discussion here:

  https://github.com/ArduPilot/ardupilot/issues/7331

we were getting some uninitialised variables. While it only showed up in
AP_SbusOut, it means we can't be sure it won't happen on other objects,
so safest to remove the approach

Thanks to assistance from Lucas, Peter and Francisco
This commit is contained in:
Andrew Tridgell 2017-12-13 12:06:14 +11:00
parent b6ecce8329
commit d175fb2f18
1 changed files with 6 additions and 14 deletions

View File

@ -76,24 +76,18 @@
class AP_Terrain {
public:
AP_Terrain(AP_AHRS &_ahrs, const AP_Mission &_mission, const AP_Rally &_rally);
/* Do not allow copies */
AP_Terrain(const AP_Terrain &other) = delete;
AP_Terrain &operator=(const AP_Terrain&) = delete;
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
@ -184,8 +178,6 @@ 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);