From d6bda7362fe605a944dffcf5fe59e93f3acb8f5b Mon Sep 17 00:00:00 2001 From: Thomas Watson Date: Sun, 2 Mar 2025 13:39:07 -0600 Subject: [PATCH] AP_Filesystem: LittleFS: tune for JEDEC NOR Decreasing metadata size from the default of a full block reduces large pauses that cause log drops. --- .../AP_Filesystem/AP_Filesystem_FlashMemory_LittleFS.cpp | 7 +++++++ 1 file changed, 7 insertions(+) diff --git a/libraries/AP_Filesystem/AP_Filesystem_FlashMemory_LittleFS.cpp b/libraries/AP_Filesystem/AP_Filesystem_FlashMemory_LittleFS.cpp index 753fe3def0cfd..a97cb3c4867aa 100644 --- a/libraries/AP_Filesystem/AP_Filesystem_FlashMemory_LittleFS.cpp +++ b/libraries/AP_Filesystem/AP_Filesystem_FlashMemory_LittleFS.cpp @@ -806,6 +806,13 @@ uint32_t AP_Filesystem_FlashMemory_LittleFS::find_block_size_and_count() { fs_cfg.prog_size = page_size; fs_cfg.block_size = flash_block_size * LFS_FLASH_BLOCKS_PER_BLOCK; fs_cfg.block_count = flash_block_count / LFS_FLASH_BLOCKS_PER_BLOCK; + + // larger metadata blocks mean less frequent compaction operations, but each + // takes longer. however, the total time spent compacting for a given file + // size still goes down with larger metadata blocks. 4096 was chosen to + // minimize both frequency and log buffer utilization. + fs_cfg.metadata_max = 4096; + fs_cfg.compact_thresh = 4096*0.88f; #if AP_FILESYSTEM_LITTLEFS_FLASH_TYPE == AP_FILESYSTEM_FLASH_W25NXX fs_cfg.metadata_max = page_size * 2; fs_cfg.compact_thresh = fs_cfg.metadata_max * 0.88f;