Skip to content

Commit

Permalink
AP_Filesystem: LittleFS: tune for JEDEC NOR
Browse files Browse the repository at this point in the history
Decreasing metadata size from the default of a full block reduces large
pauses that cause log drops.
  • Loading branch information
tpwrules authored and tridge committed Mar 4, 2025
1 parent 7e90503 commit d6bda73
Showing 1 changed file with 7 additions and 0 deletions.
Original file line number Diff line number Diff line change
Expand Up @@ -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;
Expand Down

0 comments on commit d6bda73

Please sign in to comment.