mirror of https://github.com/ArduPilot/ardupilot
AP_HAL_ESP32: change storage sector size to 128K
Signed-off-by: Rhys Mainwaring <rhys.mainwaring@me.com>
This commit is contained in:
parent
ad19321d89
commit
fa70a56a65
|
@ -23,7 +23,7 @@
|
||||||
#include "esp_partition.h"
|
#include "esp_partition.h"
|
||||||
|
|
||||||
#define STORAGE_SIZE HAL_STORAGE_SIZE
|
#define STORAGE_SIZE HAL_STORAGE_SIZE
|
||||||
#define STORAGE_SECTOR_SIZE (64*1024)
|
#define STORAGE_SECTOR_SIZE (128*1024)
|
||||||
|
|
||||||
#define STORAGE_LINE_SHIFT 3
|
#define STORAGE_LINE_SHIFT 3
|
||||||
|
|
||||||
|
|
|
@ -2,4 +2,4 @@
|
||||||
nvs, data, nvs, , 0x6000
|
nvs, data, nvs, , 0x6000
|
||||||
phy_init, data, phy, , 0x1000
|
phy_init, data, phy, , 0x1000
|
||||||
factory, app, factory, , 3M
|
factory, app, factory, , 3M
|
||||||
storage, 0x45, 0x0, , 128K
|
storage, 0x45, 0x0, , 256K
|
||||||
|
|
|
Loading…
Reference in New Issue