mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-03-13 18:14:19 -03:00
AP_Filesystem: LittleFS: tune for JEDEC NOR
Decreasing metadata size from the default of a full block reduces large pauses that cause log drops.
This commit is contained in:
parent
7e90503245
commit
d6bda7362f
@ -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;
|
||||
|
Loading…
Reference in New Issue
Block a user