AP_Terrain: add init_failed

allows external caller to determine if terrain database failed to initialise
This commit is contained in:
Randy Mackay 2019-11-07 11:03:40 +09:00 committed by Andrew Tridgell
parent cffdec131f
commit 9d0e24c17b
2 changed files with 10 additions and 0 deletions

View File

@ -386,9 +386,11 @@ bool AP_Terrain::allocate(void)
if (cache == nullptr) { if (cache == nullptr) {
enable.set(0); enable.set(0);
gcs().send_text(MAV_SEVERITY_CRITICAL, "Terrain: Allocation failed"); gcs().send_text(MAV_SEVERITY_CRITICAL, "Terrain: Allocation failed");
memory_alloc_failed = true;
return false; return false;
} }
cache_size = TERRAIN_GRID_BLOCK_CACHE_SIZE; cache_size = TERRAIN_GRID_BLOCK_CACHE_SIZE;
memory_alloc_failed = false;
return true; return true;
} }

View File

@ -179,6 +179,11 @@ public:
*/ */
void get_statistics(uint16_t &pending, uint16_t &loaded) const; void get_statistics(uint16_t &pending, uint16_t &loaded) const;
/*
returns true if initialisation failed because out-of-memory
*/
bool init_failed() const { return memory_alloc_failed; }
private: private:
// allocate the terrain subsystem data // allocate the terrain subsystem data
bool allocate(void); bool allocate(void);
@ -414,6 +419,9 @@ private:
// status // status
enum TerrainStatus system_status = TerrainStatusDisabled; enum TerrainStatus system_status = TerrainStatusDisabled;
// memory allocation status
bool memory_alloc_failed;
static AP_Terrain *singleton; static AP_Terrain *singleton;
}; };
#endif // AP_TERRAIN_AVAILABLE #endif // AP_TERRAIN_AVAILABLE