From b32ef40af76600e5cb00732acdf744492e65d76d Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?Igor=20Mi=C5=A1i=C4=87?= Date: Wed, 15 Feb 2023 16:50:47 +0100 Subject: [PATCH] mtd: update to 1-byte FRAM granularity --- boards/ark/fmu-v6x/nuttx-config/nsh/defconfig | 7 +++++++ boards/ark/fmu-v6x/src/mtd.cpp | 12 +++--------- boards/cuav/x7pro/nuttx-config/nsh/defconfig | 6 ++++++ .../cubepilot/cubeorange/nuttx-config/nsh/defconfig | 6 ++++++ boards/modalai/fc-v2/src/mtd.cpp | 2 +- boards/px4/fmu-v4/nuttx-config/nsh/defconfig | 6 ++++++ boards/px4/fmu-v4pro/nuttx-config/nsh/defconfig | 6 ++++++ boards/px4/fmu-v4pro/src/mtd.cpp | 2 +- boards/px4/fmu-v5/nuttx-config/nsh/defconfig | 6 ++++++ boards/px4/fmu-v5x/nuttx-config/nsh/defconfig | 6 ++++++ boards/px4/fmu-v5x/src/mtd.cpp | 4 ++-- boards/px4/fmu-v6c/nuttx-config/nsh/defconfig | 7 +++++++ boards/px4/fmu-v6c/src/mtd.cpp | 12 +++--------- boards/px4/fmu-v6u/nuttx-config/nsh/defconfig | 6 ++++++ boards/px4/fmu-v6u/src/mtd.cpp | 4 ++-- boards/px4/fmu-v6x/nuttx-config/nsh/defconfig | 6 ++++++ boards/px4/fmu-v6x/src/mtd.cpp | 4 ++-- platforms/nuttx/NuttX/nuttx | 2 +- platforms/nuttx/src/px4/common/px4_mtd.cpp | 4 ++-- 19 files changed, 79 insertions(+), 29 deletions(-) diff --git a/boards/ark/fmu-v6x/nuttx-config/nsh/defconfig b/boards/ark/fmu-v6x/nuttx-config/nsh/defconfig index 212213f994..65fb5642a3 100644 --- a/boards/ark/fmu-v6x/nuttx-config/nsh/defconfig +++ b/boards/ark/fmu-v6x/nuttx-config/nsh/defconfig @@ -105,6 +105,11 @@ CONFIG_FS_BINFS=y CONFIG_FS_CROMFS=y CONFIG_FS_FAT=y CONFIG_FS_FATTIME=y +CONFIG_FS_LITTLEFS=y +CONFIG_FS_LITTLEFS_BLOCK_CYCLE=-1 +CONFIG_FS_LITTLEFS_BLOCK_SIZE_FACTOR=128 +CONFIG_FS_LITTLEFS_LOOKAHEAD_SIZE=8 +CONFIG_FS_LITTLEFS_PROGRAM_SIZE_FACTOR=1 CONFIG_FS_PROCFS=y CONFIG_FS_PROCFS_INCLUDE_PROGMEM=y CONFIG_FS_PROCFS_MAX_TASKS=64 @@ -189,6 +194,8 @@ CONFIG_PREALLOC_TIMERS=50 CONFIG_PRIORITY_INHERITANCE=y CONFIG_PTHREAD_MUTEX_ROBUST=y CONFIG_PTHREAD_STACK_MIN=512 +CONFIG_RAMTRON_EMULATE_PAGE_SHIFT=0 +CONFIG_RAMTRON_EMULATE_SECTOR_SHIFT=0 CONFIG_RAMTRON_SETSPEED=y CONFIG_RAM_SIZE=245760 CONFIG_RAM_START=0x20010000 diff --git a/boards/ark/fmu-v6x/src/mtd.cpp b/boards/ark/fmu-v6x/src/mtd.cpp index 3ece10aeca..b02cfc05cc 100644 --- a/boards/ark/fmu-v6x/src/mtd.cpp +++ b/boards/ark/fmu-v6x/src/mtd.cpp @@ -34,7 +34,7 @@ #include #include // KiB BS nB -static const px4_mft_device_t spi5 = { // FM25V02A on FMUM 32K 512 X 64 +static const px4_mft_device_t spi5 = { // FM25V02A on FMUM 32K 1 x 32768 .bus_type = px4_mft_device_t::SPI, .devid = SPIDEV_FLASH(0) }; @@ -45,18 +45,12 @@ static const px4_mft_device_t i2c3 = { // 24LC64T on Base 8K 32 X 2 static const px4_mtd_entry_t fmum_fram = { .device = &spi5, - .npart = 2, + .npart = 1 .partd = { { .type = MTD_PARAMETERS, .path = "/fs/mtd_params", - .nblocks = 32 - }, - { - .type = MTD_WAYPOINTS, - .path = "/fs/mtd_waypoints", - .nblocks = 32 - + .nblocks = 32768 } }, }; diff --git a/boards/cuav/x7pro/nuttx-config/nsh/defconfig b/boards/cuav/x7pro/nuttx-config/nsh/defconfig index e2c1bffd68..5d92d332a4 100644 --- a/boards/cuav/x7pro/nuttx-config/nsh/defconfig +++ b/boards/cuav/x7pro/nuttx-config/nsh/defconfig @@ -100,6 +100,10 @@ CONFIG_FS_CROMFS=y CONFIG_FS_FAT=y CONFIG_FS_FATTIME=y CONFIG_FS_LITTLEFS=y +CONFIG_FS_LITTLEFS_BLOCK_CYCLE=-1 +CONFIG_FS_LITTLEFS_BLOCK_SIZE_FACTOR=128 +CONFIG_FS_LITTLEFS_LOOKAHEAD_SIZE=8 +CONFIG_FS_LITTLEFS_PROGRAM_SIZE_FACTOR=1 CONFIG_FS_PROCFS=y CONFIG_FS_PROCFS_INCLUDE_PROGMEM=y CONFIG_FS_PROCFS_MAX_TASKS=64 @@ -148,6 +152,8 @@ CONFIG_PREALLOC_TIMERS=50 CONFIG_PRIORITY_INHERITANCE=y CONFIG_PTHREAD_MUTEX_ROBUST=y CONFIG_PTHREAD_STACK_MIN=512 +CONFIG_RAMTRON_EMULATE_PAGE_SHIFT=0 +CONFIG_RAMTRON_EMULATE_SECTOR_SHIFT=0 CONFIG_RAMTRON_SETSPEED=y CONFIG_RAM_SIZE=245760 CONFIG_RAM_START=0x20010000 diff --git a/boards/cubepilot/cubeorange/nuttx-config/nsh/defconfig b/boards/cubepilot/cubeorange/nuttx-config/nsh/defconfig index 1523b12586..603af27ae5 100644 --- a/boards/cubepilot/cubeorange/nuttx-config/nsh/defconfig +++ b/boards/cubepilot/cubeorange/nuttx-config/nsh/defconfig @@ -100,6 +100,10 @@ CONFIG_FS_CROMFS=y CONFIG_FS_FAT=y CONFIG_FS_FATTIME=y CONFIG_FS_LITTLEFS=y +CONFIG_FS_LITTLEFS_BLOCK_CYCLE=-1 +CONFIG_FS_LITTLEFS_BLOCK_SIZE_FACTOR=128 +CONFIG_FS_LITTLEFS_LOOKAHEAD_SIZE=8 +CONFIG_FS_LITTLEFS_PROGRAM_SIZE_FACTOR=1 CONFIG_FS_PROCFS=y CONFIG_FS_PROCFS_INCLUDE_PROGMEM=y CONFIG_FS_PROCFS_MAX_TASKS=64 @@ -149,6 +153,8 @@ CONFIG_PREALLOC_TIMERS=50 CONFIG_PRIORITY_INHERITANCE=y CONFIG_PTHREAD_MUTEX_ROBUST=y CONFIG_PTHREAD_STACK_MIN=512 +CONFIG_RAMTRON_EMULATE_PAGE_SHIFT=0 +CONFIG_RAMTRON_EMULATE_SECTOR_SHIFT=0 CONFIG_RAMTRON_SETSPEED=y CONFIG_RAM_SIZE=245760 CONFIG_RAM_START=0x20010000 diff --git a/boards/modalai/fc-v2/src/mtd.cpp b/boards/modalai/fc-v2/src/mtd.cpp index 7bbe598987..3b18627860 100644 --- a/boards/modalai/fc-v2/src/mtd.cpp +++ b/boards/modalai/fc-v2/src/mtd.cpp @@ -46,7 +46,7 @@ static const px4_mtd_entry_t fmum_fram = { { .type = MTD_PARAMETERS, .path = "/fs/mtd_params", - .nblocks = 64 + .nblocks = 32768 } }, }; diff --git a/boards/px4/fmu-v4/nuttx-config/nsh/defconfig b/boards/px4/fmu-v4/nuttx-config/nsh/defconfig index 74c7e42fa8..50041d2c12 100644 --- a/boards/px4/fmu-v4/nuttx-config/nsh/defconfig +++ b/boards/px4/fmu-v4/nuttx-config/nsh/defconfig @@ -96,6 +96,10 @@ CONFIG_FS_CROMFS=y CONFIG_FS_FAT=y CONFIG_FS_FATTIME=y CONFIG_FS_LITTLEFS=y +CONFIG_FS_LITTLEFS_BLOCK_CYCLE=-1 +CONFIG_FS_LITTLEFS_BLOCK_SIZE_FACTOR=128 +CONFIG_FS_LITTLEFS_LOOKAHEAD_SIZE=8 +CONFIG_FS_LITTLEFS_PROGRAM_SIZE_FACTOR=1 CONFIG_FS_PROCFS=y CONFIG_FS_PROCFS_INCLUDE_PROGMEM=y CONFIG_FS_PROCFS_REGISTER=y @@ -141,6 +145,8 @@ CONFIG_PREALLOC_TIMERS=50 CONFIG_PRIORITY_INHERITANCE=y CONFIG_PTHREAD_MUTEX_ROBUST=y CONFIG_PTHREAD_STACK_MIN=512 +CONFIG_RAMTRON_EMULATE_PAGE_SHIFT=0 +CONFIG_RAMTRON_EMULATE_SECTOR_SHIFT=0 CONFIG_RAMTRON_SETSPEED=y CONFIG_RAM_SIZE=262144 CONFIG_RAM_START=0x20000000 diff --git a/boards/px4/fmu-v4pro/nuttx-config/nsh/defconfig b/boards/px4/fmu-v4pro/nuttx-config/nsh/defconfig index 6207639979..c7f71f92dd 100644 --- a/boards/px4/fmu-v4pro/nuttx-config/nsh/defconfig +++ b/boards/px4/fmu-v4pro/nuttx-config/nsh/defconfig @@ -96,6 +96,10 @@ CONFIG_FS_CROMFS=y CONFIG_FS_FAT=y CONFIG_FS_FATTIME=y CONFIG_FS_LITTLEFS=y +CONFIG_FS_LITTLEFS_BLOCK_CYCLE=-1 +CONFIG_FS_LITTLEFS_BLOCK_SIZE_FACTOR=128 +CONFIG_FS_LITTLEFS_LOOKAHEAD_SIZE=8 +CONFIG_FS_LITTLEFS_PROGRAM_SIZE_FACTOR=1 CONFIG_FS_PROCFS=y CONFIG_FS_PROCFS_INCLUDE_PROGMEM=y CONFIG_FS_PROCFS_REGISTER=y @@ -141,6 +145,8 @@ CONFIG_PREALLOC_TIMERS=50 CONFIG_PRIORITY_INHERITANCE=y CONFIG_PTHREAD_MUTEX_ROBUST=y CONFIG_PTHREAD_STACK_MIN=512 +CONFIG_RAMTRON_EMULATE_PAGE_SHIFT=0 +CONFIG_RAMTRON_EMULATE_SECTOR_SHIFT=0 CONFIG_RAMTRON_SETSPEED=y CONFIG_RAM_SIZE=393216 CONFIG_RAM_START=0x20000000 diff --git a/boards/px4/fmu-v4pro/src/mtd.cpp b/boards/px4/fmu-v4pro/src/mtd.cpp index 4bd93619db..eeb8dc1759 100644 --- a/boards/px4/fmu-v4pro/src/mtd.cpp +++ b/boards/px4/fmu-v4pro/src/mtd.cpp @@ -46,7 +46,7 @@ static const px4_mtd_entry_t fmum_fram = { { .type = MTD_PARAMETERS, .path = "/fs/mtd_params", - .nblocks = 32 + .nblocks = 16384 }, }, }; diff --git a/boards/px4/fmu-v5/nuttx-config/nsh/defconfig b/boards/px4/fmu-v5/nuttx-config/nsh/defconfig index 2ba99dfc37..d4173ff1ba 100644 --- a/boards/px4/fmu-v5/nuttx-config/nsh/defconfig +++ b/boards/px4/fmu-v5/nuttx-config/nsh/defconfig @@ -100,6 +100,10 @@ CONFIG_FS_CROMFS=y CONFIG_FS_FAT=y CONFIG_FS_FATTIME=y CONFIG_FS_LITTLEFS=y +CONFIG_FS_LITTLEFS_BLOCK_CYCLE=-1 +CONFIG_FS_LITTLEFS_BLOCK_SIZE_FACTOR=128 +CONFIG_FS_LITTLEFS_LOOKAHEAD_SIZE=8 +CONFIG_FS_LITTLEFS_PROGRAM_SIZE_FACTOR=1 CONFIG_FS_PROCFS=y CONFIG_FS_PROCFS_INCLUDE_PROGMEM=y CONFIG_FS_PROCFS_MAX_TASKS=64 @@ -147,6 +151,8 @@ CONFIG_PREALLOC_TIMERS=50 CONFIG_PRIORITY_INHERITANCE=y CONFIG_PTHREAD_MUTEX_ROBUST=y CONFIG_PTHREAD_STACK_MIN=512 +CONFIG_RAMTRON_EMULATE_PAGE_SHIFT=0 +CONFIG_RAMTRON_EMULATE_SECTOR_SHIFT=0 CONFIG_RAMTRON_SETSPEED=y CONFIG_RAM_SIZE=245760 CONFIG_RAM_START=0x20010000 diff --git a/boards/px4/fmu-v5x/nuttx-config/nsh/defconfig b/boards/px4/fmu-v5x/nuttx-config/nsh/defconfig index 4b049edf8a..ee0905ce68 100644 --- a/boards/px4/fmu-v5x/nuttx-config/nsh/defconfig +++ b/boards/px4/fmu-v5x/nuttx-config/nsh/defconfig @@ -105,6 +105,10 @@ CONFIG_FS_CROMFS=y CONFIG_FS_FAT=y CONFIG_FS_FATTIME=y CONFIG_FS_LITTLEFS=y +CONFIG_FS_LITTLEFS_BLOCK_CYCLE=-1 +CONFIG_FS_LITTLEFS_BLOCK_SIZE_FACTOR=128 +CONFIG_FS_LITTLEFS_LOOKAHEAD_SIZE=8 +CONFIG_FS_LITTLEFS_PROGRAM_SIZE_FACTOR=1 CONFIG_FS_PROCFS=y CONFIG_FS_PROCFS_INCLUDE_PROGMEM=y CONFIG_FS_PROCFS_MAX_TASKS=64 @@ -186,6 +190,8 @@ CONFIG_PREALLOC_TIMERS=50 CONFIG_PRIORITY_INHERITANCE=y CONFIG_PTHREAD_MUTEX_ROBUST=y CONFIG_PTHREAD_STACK_MIN=512 +CONFIG_RAMTRON_EMULATE_PAGE_SHIFT=0 +CONFIG_RAMTRON_EMULATE_SECTOR_SHIFT=0 CONFIG_RAMTRON_SETSPEED=y CONFIG_RAM_SIZE=245760 CONFIG_RAM_START=0x20010000 diff --git a/boards/px4/fmu-v5x/src/mtd.cpp b/boards/px4/fmu-v5x/src/mtd.cpp index 860b45b30e..c500ab5ce5 100644 --- a/boards/px4/fmu-v5x/src/mtd.cpp +++ b/boards/px4/fmu-v5x/src/mtd.cpp @@ -34,7 +34,7 @@ #include #include // KiB BS nB -static const px4_mft_device_t spi5 = { // FM25V02A on FMUM 32K 512 X 64 +static const px4_mft_device_t spi5 = { // FM25V02A on FMUM 32K 1 X 32768 .bus_type = px4_mft_device_t::SPI, .devid = SPIDEV_FLASH(0) }; @@ -55,7 +55,7 @@ static const px4_mtd_entry_t fmum_fram = { { .type = MTD_PARAMETERS, .path = "/fs/mtd_params", - .nblocks = 64 + .nblocks = 32768 } }, }; diff --git a/boards/px4/fmu-v6c/nuttx-config/nsh/defconfig b/boards/px4/fmu-v6c/nuttx-config/nsh/defconfig index 78963cf699..da91a93eae 100644 --- a/boards/px4/fmu-v6c/nuttx-config/nsh/defconfig +++ b/boards/px4/fmu-v6c/nuttx-config/nsh/defconfig @@ -99,6 +99,11 @@ CONFIG_FS_BINFS=y CONFIG_FS_CROMFS=y CONFIG_FS_FAT=y CONFIG_FS_FATTIME=y +CONFIG_FS_LITTLEFS=y +CONFIG_FS_LITTLEFS_BLOCK_CYCLE=-1 +CONFIG_FS_LITTLEFS_BLOCK_SIZE_FACTOR=128 +CONFIG_FS_LITTLEFS_LOOKAHEAD_SIZE=8 +CONFIG_FS_LITTLEFS_PROGRAM_SIZE_FACTOR=1 CONFIG_FS_PROCFS=y CONFIG_FS_PROCFS_INCLUDE_PROGMEM=y CONFIG_FS_PROCFS_MAX_TASKS=64 @@ -151,6 +156,8 @@ CONFIG_PREALLOC_TIMERS=50 CONFIG_PRIORITY_INHERITANCE=y CONFIG_PTHREAD_MUTEX_ROBUST=y CONFIG_PTHREAD_STACK_MIN=512 +CONFIG_RAMTRON_EMULATE_PAGE_SHIFT=0 +CONFIG_RAMTRON_EMULATE_SECTOR_SHIFT=0 CONFIG_RAMTRON_SETSPEED=y CONFIG_RAM_SIZE=245760 CONFIG_RAM_START=0x20010000 diff --git a/boards/px4/fmu-v6c/src/mtd.cpp b/boards/px4/fmu-v6c/src/mtd.cpp index b315ff399d..cff26768d1 100644 --- a/boards/px4/fmu-v6c/src/mtd.cpp +++ b/boards/px4/fmu-v6c/src/mtd.cpp @@ -34,7 +34,7 @@ #include #include // KiB BS nB -static const px4_mft_device_t spi2 = { // FM25V02A on FMUM 32K 512 X 64 +static const px4_mft_device_t spi2 = { // FM25V02A on FMUM 32K 1 x 32768 .bus_type = px4_mft_device_t::SPI, .devid = SPIDEV_FLASH(0) }; @@ -47,18 +47,12 @@ static const px4_mft_device_t i2c4 = { // 24LC64T on IMU 8K 32 X 2 static const px4_mtd_entry_t fmum_fram = { .device = &spi2, - .npart = 2, + .npart = 1, .partd = { { .type = MTD_PARAMETERS, .path = "/fs/mtd_params", - .nblocks = 32 - }, - { - .type = MTD_WAYPOINTS, - .path = "/fs/mtd_waypoints", - .nblocks = 32 - + .nblocks = 32768 } }, }; diff --git a/boards/px4/fmu-v6u/nuttx-config/nsh/defconfig b/boards/px4/fmu-v6u/nuttx-config/nsh/defconfig index 9c75ea3b76..a95fd3b395 100644 --- a/boards/px4/fmu-v6u/nuttx-config/nsh/defconfig +++ b/boards/px4/fmu-v6u/nuttx-config/nsh/defconfig @@ -100,6 +100,10 @@ CONFIG_FS_CROMFS=y CONFIG_FS_FAT=y CONFIG_FS_FATTIME=y CONFIG_FS_LITTLEFS=y +CONFIG_FS_LITTLEFS_BLOCK_CYCLE=-1 +CONFIG_FS_LITTLEFS_BLOCK_SIZE_FACTOR=128 +CONFIG_FS_LITTLEFS_LOOKAHEAD_SIZE=8 +CONFIG_FS_LITTLEFS_PROGRAM_SIZE_FACTOR=1 CONFIG_FS_PROCFS=y CONFIG_FS_PROCFS_INCLUDE_PROGMEM=y CONFIG_FS_PROCFS_MAX_TASKS=64 @@ -152,6 +156,8 @@ CONFIG_PREALLOC_TIMERS=50 CONFIG_PRIORITY_INHERITANCE=y CONFIG_PTHREAD_MUTEX_ROBUST=y CONFIG_PTHREAD_STACK_MIN=512 +CONFIG_RAMTRON_EMULATE_PAGE_SHIFT=0 +CONFIG_RAMTRON_EMULATE_SECTOR_SHIFT=0 CONFIG_RAMTRON_SETSPEED=y CONFIG_RAM_SIZE=245760 CONFIG_RAM_START=0x20010000 diff --git a/boards/px4/fmu-v6u/src/mtd.cpp b/boards/px4/fmu-v6u/src/mtd.cpp index 7bbe598987..7511f000d0 100644 --- a/boards/px4/fmu-v6u/src/mtd.cpp +++ b/boards/px4/fmu-v6u/src/mtd.cpp @@ -34,7 +34,7 @@ #include #include // KiB BS nB -static const px4_mft_device_t spi5 = { // FM25V02A on FMUM 32K 512 X 64 +static const px4_mft_device_t spi5 = { // FM25V02A on FMUM 32K 1 x 32768 .bus_type = px4_mft_device_t::SPI, .devid = SPIDEV_FLASH(0) }; @@ -46,7 +46,7 @@ static const px4_mtd_entry_t fmum_fram = { { .type = MTD_PARAMETERS, .path = "/fs/mtd_params", - .nblocks = 64 + .nblocks = 32768 } }, }; diff --git a/boards/px4/fmu-v6x/nuttx-config/nsh/defconfig b/boards/px4/fmu-v6x/nuttx-config/nsh/defconfig index 13d61e1f73..1f976b0bfc 100644 --- a/boards/px4/fmu-v6x/nuttx-config/nsh/defconfig +++ b/boards/px4/fmu-v6x/nuttx-config/nsh/defconfig @@ -106,6 +106,10 @@ CONFIG_FS_CROMFS=y CONFIG_FS_FAT=y CONFIG_FS_FATTIME=y CONFIG_FS_LITTLEFS=y +CONFIG_FS_LITTLEFS_BLOCK_CYCLE=-1 +CONFIG_FS_LITTLEFS_BLOCK_SIZE_FACTOR=128 +CONFIG_FS_LITTLEFS_LOOKAHEAD_SIZE=8 +CONFIG_FS_LITTLEFS_PROGRAM_SIZE_FACTOR=1 CONFIG_FS_PROCFS=y CONFIG_FS_PROCFS_INCLUDE_PROGMEM=y CONFIG_FS_PROCFS_MAX_TASKS=64 @@ -190,6 +194,8 @@ CONFIG_PREALLOC_TIMERS=50 CONFIG_PRIORITY_INHERITANCE=y CONFIG_PTHREAD_MUTEX_ROBUST=y CONFIG_PTHREAD_STACK_MIN=512 +CONFIG_RAMTRON_EMULATE_PAGE_SHIFT=0 +CONFIG_RAMTRON_EMULATE_SECTOR_SHIFT=0 CONFIG_RAMTRON_SETSPEED=y CONFIG_RAM_SIZE=245760 CONFIG_RAM_START=0x20010000 diff --git a/boards/px4/fmu-v6x/src/mtd.cpp b/boards/px4/fmu-v6x/src/mtd.cpp index 860b45b30e..5d94e2bfaa 100644 --- a/boards/px4/fmu-v6x/src/mtd.cpp +++ b/boards/px4/fmu-v6x/src/mtd.cpp @@ -34,7 +34,7 @@ #include #include // KiB BS nB -static const px4_mft_device_t spi5 = { // FM25V02A on FMUM 32K 512 X 64 +static const px4_mft_device_t spi5 = { // FM25V02A on FMUM 32K 1 x 32768 .bus_type = px4_mft_device_t::SPI, .devid = SPIDEV_FLASH(0) }; @@ -55,7 +55,7 @@ static const px4_mtd_entry_t fmum_fram = { { .type = MTD_PARAMETERS, .path = "/fs/mtd_params", - .nblocks = 64 + .nblocks = 32768 } }, }; diff --git a/platforms/nuttx/NuttX/nuttx b/platforms/nuttx/NuttX/nuttx index 35997053c5..43d5a11778 160000 --- a/platforms/nuttx/NuttX/nuttx +++ b/platforms/nuttx/NuttX/nuttx @@ -1 +1 @@ -Subproject commit 35997053c5f61039e542c01440feb10baba5049d +Subproject commit 43d5a11778ef7a589fe7e89ae77e78d7f494b615 diff --git a/platforms/nuttx/src/px4/common/px4_mtd.cpp b/platforms/nuttx/src/px4/common/px4_mtd.cpp index 459b680325..09ff15cf8e 100644 --- a/platforms/nuttx/src/px4/common/px4_mtd.cpp +++ b/platforms/nuttx/src/px4/common/px4_mtd.cpp @@ -247,7 +247,7 @@ static const px4_mtd_manifest_t default_mtd_config = { #else -const px4_mft_device_t spifram = { // FM25V02A on FMUM 32K 512 X 64 +const px4_mft_device_t spifram = { // FM25V02A on FMUM 32K 1 X 32768 .bus_type = px4_mft_device_t::SPI, .devid = SPIDEV_FLASH(0) }; @@ -259,7 +259,7 @@ const px4_mtd_entry_t fram = { { .type = MTD_PARAMETERS, .path = "/fs/mtd_params", - .nblocks = 64 + .nblocks = 32768 } }, };