mirror of https://github.com/ArduPilot/ardupilot
HAL_ChibiOS: use 16 byte lines for flash storage on H7
this halves the number of flash writes needed, and makes flash storage twice as space efficient on H7 On H7 we need to write 32 bytes at a time to flash, which corresponds to 30 bytes of data in AP_FlashStorage. By using a 16 byte storage line we don't waste as much space
This commit is contained in:
parent
0a3ca205eb
commit
e1c74ee6e5
|
@ -30,7 +30,11 @@
|
||||||
// when using flash storage we use a small line size to make storage
|
// when using flash storage we use a small line size to make storage
|
||||||
// compact and minimise the number of erase cycles needed
|
// compact and minimise the number of erase cycles needed
|
||||||
#ifdef STORAGE_FLASH_PAGE
|
#ifdef STORAGE_FLASH_PAGE
|
||||||
|
#if defined(STM32H7XX)
|
||||||
|
#define CH_STORAGE_LINE_SHIFT 4
|
||||||
|
#else
|
||||||
#define CH_STORAGE_LINE_SHIFT 3
|
#define CH_STORAGE_LINE_SHIFT 3
|
||||||
|
#endif
|
||||||
#elif defined(USE_POSIX) && !defined(HAL_WITH_RAMTRON)
|
#elif defined(USE_POSIX) && !defined(HAL_WITH_RAMTRON)
|
||||||
#define CH_STORAGE_LINE_SHIFT 9
|
#define CH_STORAGE_LINE_SHIFT 9
|
||||||
#else
|
#else
|
||||||
|
|
Loading…
Reference in New Issue