From 9d0e24c17b35dd5f25e52f65962db812e61283ca Mon Sep 17 00:00:00 2001 From: Randy Mackay Date: Thu, 7 Nov 2019 11:03:40 +0900 Subject: [PATCH] AP_Terrain: add init_failed allows external caller to determine if terrain database failed to initialise --- libraries/AP_Terrain/AP_Terrain.cpp | 2 ++ libraries/AP_Terrain/AP_Terrain.h | 8 ++++++++ 2 files changed, 10 insertions(+) diff --git a/libraries/AP_Terrain/AP_Terrain.cpp b/libraries/AP_Terrain/AP_Terrain.cpp index 7ee56a08f6..4ef7a537f1 100644 --- a/libraries/AP_Terrain/AP_Terrain.cpp +++ b/libraries/AP_Terrain/AP_Terrain.cpp @@ -386,9 +386,11 @@ bool AP_Terrain::allocate(void) if (cache == nullptr) { enable.set(0); gcs().send_text(MAV_SEVERITY_CRITICAL, "Terrain: Allocation failed"); + memory_alloc_failed = true; return false; } cache_size = TERRAIN_GRID_BLOCK_CACHE_SIZE; + memory_alloc_failed = false; return true; } diff --git a/libraries/AP_Terrain/AP_Terrain.h b/libraries/AP_Terrain/AP_Terrain.h index 82a0f44e1e..10ca5aadcd 100644 --- a/libraries/AP_Terrain/AP_Terrain.h +++ b/libraries/AP_Terrain/AP_Terrain.h @@ -179,6 +179,11 @@ public: */ 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: // allocate the terrain subsystem data bool allocate(void); @@ -414,6 +419,9 @@ private: // status enum TerrainStatus system_status = TerrainStatusDisabled; + // memory allocation status + bool memory_alloc_failed; + static AP_Terrain *singleton; }; #endif // AP_TERRAIN_AVAILABLE