From 5cf2c2740ef3134bb9c4136405ee3bc0b88dedc8 Mon Sep 17 00:00:00 2001 From: Andrew Tridgell Date: Sun, 13 Nov 2022 10:27:37 +1100 Subject: [PATCH] AP_Terrain: added parameter for terrain cache size --- libraries/AP_Terrain/AP_Terrain.cpp | 13 ++++++++++--- libraries/AP_Terrain/AP_Terrain.h | 3 +++ 2 files changed, 13 insertions(+), 3 deletions(-) diff --git a/libraries/AP_Terrain/AP_Terrain.cpp b/libraries/AP_Terrain/AP_Terrain.cpp index d2aab8bf1d8ab..48966bfbe161c 100644 --- a/libraries/AP_Terrain/AP_Terrain.cpp +++ b/libraries/AP_Terrain/AP_Terrain.cpp @@ -77,7 +77,14 @@ const AP_Param::GroupInfo AP_Terrain::var_info[] = { // @Range: 0 50 // @User: Advanced AP_GROUPINFO("OFS_MAX", 4, AP_Terrain, offset_max, 30), - + + // @Param: CACHE_SZ + // @DisplayName: Terrain cache size + // @Description: The number of 32x28 cache blocks to keep in memory. Each block uses about 1800 bytes of memory + // @Range: 0 128 + // @User: Advanced + AP_GROUPINFO("CACHE_SZ", 5, AP_Terrain, config_cache_size, TERRAIN_GRID_BLOCK_CACHE_SIZE), + AP_GROUPEND }; @@ -488,13 +495,13 @@ bool AP_Terrain::allocate(void) if (cache != nullptr) { return true; } - cache = (struct grid_cache *)calloc(TERRAIN_GRID_BLOCK_CACHE_SIZE, sizeof(cache[0])); + cache = (struct grid_cache *)calloc(config_cache_size, sizeof(cache[0])); if (cache == nullptr) { GCS_SEND_TEXT(MAV_SEVERITY_CRITICAL, "Terrain: Allocation failed"); memory_alloc_failed = true; return false; } - cache_size = TERRAIN_GRID_BLOCK_CACHE_SIZE; + cache_size = config_cache_size; return true; } diff --git a/libraries/AP_Terrain/AP_Terrain.h b/libraries/AP_Terrain/AP_Terrain.h index 8a6be4579db06..7dfd2653d8475 100644 --- a/libraries/AP_Terrain/AP_Terrain.h +++ b/libraries/AP_Terrain/AP_Terrain.h @@ -51,7 +51,9 @@ #define TERRAIN_GRID_BLOCK_SIZE_Y (TERRAIN_GRID_MAVLINK_SIZE*TERRAIN_GRID_BLOCK_MUL_Y) // number of grid_blocks in the LRU memory cache +#ifndef TERRAIN_GRID_BLOCK_CACHE_SIZE #define TERRAIN_GRID_BLOCK_CACHE_SIZE 12 +#endif // format of grid on disk #define TERRAIN_GRID_FORMAT_VERSION 1 @@ -371,6 +373,7 @@ class AP_Terrain { AP_Int16 grid_spacing; // meters between grid points AP_Int16 options; // option bits AP_Float offset_max; + AP_Int16 config_cache_size; enum class Options { DisableDownload = (1U<<0),