Browse Source

AP_Terrain: leave ENABLE as 1 if memory alloc fails

c415-sdk
Randy Mackay 5 years ago committed by Andrew Tridgell
parent
commit
d18432adaa
  1. 4
      libraries/AP_Terrain/AP_Terrain.cpp

4
libraries/AP_Terrain/AP_Terrain.cpp

@ -376,7 +376,7 @@ void AP_Terrain::log_terrain_data()
*/ */
bool AP_Terrain::allocate(void) bool AP_Terrain::allocate(void)
{ {
if (enable == 0) { if (enable == 0 || memory_alloc_failed) {
return false; return false;
} }
if (cache != nullptr) { if (cache != nullptr) {
@ -384,13 +384,11 @@ bool AP_Terrain::allocate(void)
} }
cache = (struct grid_cache *)calloc(TERRAIN_GRID_BLOCK_CACHE_SIZE, sizeof(cache[0])); cache = (struct grid_cache *)calloc(TERRAIN_GRID_BLOCK_CACHE_SIZE, sizeof(cache[0]));
if (cache == nullptr) { if (cache == nullptr) {
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; 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;
} }

Loading…
Cancel
Save