diff --git a/boards/airmind/mindpx-v2/nuttx-config/nsh/defconfig b/boards/airmind/mindpx-v2/nuttx-config/nsh/defconfig index 1e3a8a27d9..27ce829659 100644 --- a/boards/airmind/mindpx-v2/nuttx-config/nsh/defconfig +++ b/boards/airmind/mindpx-v2/nuttx-config/nsh/defconfig @@ -140,6 +140,8 @@ CONFIG_PREALLOC_TIMERS=50 CONFIG_PRIORITY_INHERITANCE=y CONFIG_PTHREAD_MUTEX_ROBUST=y CONFIG_PTHREAD_STACK_MIN=512 +CONFIG_RAMTRON_EMULATE_PAGE_SHIFT=5 +CONFIG_RAMTRON_EMULATE_SECTOR_SHIFT=5 CONFIG_RAMTRON_SETSPEED=y CONFIG_RAM_SIZE=262144 CONFIG_RAM_START=0x20000000 diff --git a/boards/ark/can-flow/nuttx-config/nsh/defconfig b/boards/ark/can-flow/nuttx-config/nsh/defconfig index 15d145881e..eb4cb5e929 100644 --- a/boards/ark/can-flow/nuttx-config/nsh/defconfig +++ b/boards/ark/can-flow/nuttx-config/nsh/defconfig @@ -115,6 +115,8 @@ CONFIG_PREALLOC_TIMERS=50 CONFIG_PRIORITY_INHERITANCE=y CONFIG_PTHREAD_MUTEX_ROBUST=y CONFIG_PTHREAD_STACK_MIN=512 +CONFIG_RAMTRON_EMULATE_PAGE_SHIFT=5 +CONFIG_RAMTRON_EMULATE_SECTOR_SHIFT=5 CONFIG_RAMTRON_SETSPEED=y CONFIG_RAM_SIZE=262144 CONFIG_RAM_START=0x20000000 diff --git a/boards/ark/can-gps/nuttx-config/nsh/defconfig b/boards/ark/can-gps/nuttx-config/nsh/defconfig index f734bc8168..8addad7c7d 100644 --- a/boards/ark/can-gps/nuttx-config/nsh/defconfig +++ b/boards/ark/can-gps/nuttx-config/nsh/defconfig @@ -117,6 +117,8 @@ CONFIG_PREALLOC_TIMERS=50 CONFIG_PRIORITY_INHERITANCE=y CONFIG_PTHREAD_MUTEX_ROBUST=y CONFIG_PTHREAD_STACK_MIN=512 +CONFIG_RAMTRON_EMULATE_PAGE_SHIFT=5 +CONFIG_RAMTRON_EMULATE_SECTOR_SHIFT=5 CONFIG_RAMTRON_SETSPEED=y CONFIG_RAM_SIZE=262144 CONFIG_RAM_START=0x20000000 diff --git a/boards/ark/can-rtk-gps/nuttx-config/nsh/defconfig b/boards/ark/can-rtk-gps/nuttx-config/nsh/defconfig index ba2d6f2143..34d42179c7 100644 --- a/boards/ark/can-rtk-gps/nuttx-config/nsh/defconfig +++ b/boards/ark/can-rtk-gps/nuttx-config/nsh/defconfig @@ -117,6 +117,8 @@ CONFIG_PREALLOC_TIMERS=50 CONFIG_PRIORITY_INHERITANCE=y CONFIG_PTHREAD_MUTEX_ROBUST=y CONFIG_PTHREAD_STACK_MIN=512 +CONFIG_RAMTRON_EMULATE_PAGE_SHIFT=5 +CONFIG_RAMTRON_EMULATE_SECTOR_SHIFT=5 CONFIG_RAMTRON_SETSPEED=y CONFIG_RAM_SIZE=262144 CONFIG_RAM_START=0x20000000 diff --git a/boards/ark/cannode/nuttx-config/nsh/defconfig b/boards/ark/cannode/nuttx-config/nsh/defconfig index a0882b71be..8ec02cc3dd 100644 --- a/boards/ark/cannode/nuttx-config/nsh/defconfig +++ b/boards/ark/cannode/nuttx-config/nsh/defconfig @@ -117,6 +117,8 @@ CONFIG_PREALLOC_TIMERS=50 CONFIG_PRIORITY_INHERITANCE=y CONFIG_PTHREAD_MUTEX_ROBUST=y CONFIG_PTHREAD_STACK_MIN=512 +CONFIG_RAMTRON_EMULATE_PAGE_SHIFT=5 +CONFIG_RAMTRON_EMULATE_SECTOR_SHIFT=5 CONFIG_RAMTRON_SETSPEED=y CONFIG_RAM_SIZE=262144 CONFIG_RAM_START=0x20000000 diff --git a/boards/ark/fmu-v6x/nuttx-config/nsh/defconfig b/boards/ark/fmu-v6x/nuttx-config/nsh/defconfig index 384726875d..1493783f1b 100644 --- a/boards/ark/fmu-v6x/nuttx-config/nsh/defconfig +++ b/boards/ark/fmu-v6x/nuttx-config/nsh/defconfig @@ -189,6 +189,8 @@ CONFIG_PREALLOC_TIMERS=50 CONFIG_PRIORITY_INHERITANCE=y CONFIG_PTHREAD_MUTEX_ROBUST=y CONFIG_PTHREAD_STACK_MIN=512 +CONFIG_RAMTRON_EMULATE_PAGE_SHIFT=5 +CONFIG_RAMTRON_EMULATE_SECTOR_SHIFT=5 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..80d41e0b78 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 native: 32K X 8, emulated as (1024 Blocks of 32) .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 / (1 << CONFIG_RAMTRON_EMULATE_SECTOR_SHIFT)) } }, }; diff --git a/boards/atl/mantis-edu/nuttx-config/nsh/defconfig b/boards/atl/mantis-edu/nuttx-config/nsh/defconfig index 3556e01746..3b5905a830 100644 --- a/boards/atl/mantis-edu/nuttx-config/nsh/defconfig +++ b/boards/atl/mantis-edu/nuttx-config/nsh/defconfig @@ -147,6 +147,8 @@ CONFIG_PREALLOC_TIMERS=50 CONFIG_PRIORITY_INHERITANCE=y CONFIG_PTHREAD_MUTEX_ROBUST=y CONFIG_PTHREAD_STACK_MIN=512 +CONFIG_RAMTRON_EMULATE_PAGE_SHIFT=5 +CONFIG_RAMTRON_EMULATE_SECTOR_SHIFT=5 CONFIG_RAMTRON_SETSPEED=y CONFIG_RAM_SIZE=245760 CONFIG_RAM_START=0x20010000 diff --git a/boards/bitcraze/crazyflie/src/mtd.cpp b/boards/bitcraze/crazyflie/src/mtd.cpp index 2b00e231b2..d81e3e4596 100644 --- a/boards/bitcraze/crazyflie/src/mtd.cpp +++ b/boards/bitcraze/crazyflie/src/mtd.cpp @@ -42,18 +42,12 @@ static const px4_mft_device_t i2c1 = { // 24AA64FT on Base 8K 32 X static const px4_mtd_entry_t fmu_eeprom = { .device = &i2c1, - .npart = 2, + .npart = 1, .partd = { { .type = MTD_PARAMETERS, .path = "/fs/mtd_params", .nblocks = 128 - }, - { - .type = MTD_WAYPOINTS, - .path = "/fs/mtd_waypoints", - .nblocks = 128 - } }, }; diff --git a/boards/cuav/can-gps-v1/nuttx-config/nsh/defconfig b/boards/cuav/can-gps-v1/nuttx-config/nsh/defconfig index 64f884c2db..aa13dbdb1e 100644 --- a/boards/cuav/can-gps-v1/nuttx-config/nsh/defconfig +++ b/boards/cuav/can-gps-v1/nuttx-config/nsh/defconfig @@ -119,6 +119,8 @@ CONFIG_PREALLOC_TIMERS=50 CONFIG_PRIORITY_INHERITANCE=y CONFIG_PTHREAD_MUTEX_ROBUST=y CONFIG_PTHREAD_STACK_MIN=512 +CONFIG_RAMTRON_EMULATE_PAGE_SHIFT=5 +CONFIG_RAMTRON_EMULATE_SECTOR_SHIFT=5 CONFIG_RAMTRON_SETSPEED=y CONFIG_RAM_SIZE=262144 CONFIG_RAM_START=0x20000000 diff --git a/boards/cuav/nora/nuttx-config/nsh/defconfig b/boards/cuav/nora/nuttx-config/nsh/defconfig index a99ceca7ce..2f6287a368 100644 --- a/boards/cuav/nora/nuttx-config/nsh/defconfig +++ b/boards/cuav/nora/nuttx-config/nsh/defconfig @@ -147,6 +147,8 @@ CONFIG_PREALLOC_TIMERS=50 CONFIG_PRIORITY_INHERITANCE=y CONFIG_PTHREAD_MUTEX_ROBUST=y CONFIG_PTHREAD_STACK_MIN=512 +CONFIG_RAMTRON_EMULATE_PAGE_SHIFT=5 +CONFIG_RAMTRON_EMULATE_SECTOR_SHIFT=5 CONFIG_RAMTRON_SETSPEED=y CONFIG_RAM_SIZE=245760 CONFIG_RAM_START=0x20010000 diff --git a/boards/cuav/x7pro/nuttx-config/nsh/defconfig b/boards/cuav/x7pro/nuttx-config/nsh/defconfig index 56405a89fe..f4b2ac6dbb 100644 --- a/boards/cuav/x7pro/nuttx-config/nsh/defconfig +++ b/boards/cuav/x7pro/nuttx-config/nsh/defconfig @@ -147,6 +147,8 @@ CONFIG_PREALLOC_TIMERS=50 CONFIG_PRIORITY_INHERITANCE=y CONFIG_PTHREAD_MUTEX_ROBUST=y CONFIG_PTHREAD_STACK_MIN=512 +CONFIG_RAMTRON_EMULATE_PAGE_SHIFT=5 +CONFIG_RAMTRON_EMULATE_SECTOR_SHIFT=5 CONFIG_RAMTRON_SETSPEED=y CONFIG_RAM_SIZE=245760 CONFIG_RAM_START=0x20010000 diff --git a/boards/cuav/x7pro/nuttx-config/test/defconfig b/boards/cuav/x7pro/nuttx-config/test/defconfig index 789a10b6c2..8ade766da6 100644 --- a/boards/cuav/x7pro/nuttx-config/test/defconfig +++ b/boards/cuav/x7pro/nuttx-config/test/defconfig @@ -147,6 +147,8 @@ CONFIG_PREALLOC_TIMERS=50 CONFIG_PRIORITY_INHERITANCE=y CONFIG_PTHREAD_MUTEX_ROBUST=y CONFIG_PTHREAD_STACK_MIN=512 +CONFIG_RAMTRON_EMULATE_PAGE_SHIFT=5 +CONFIG_RAMTRON_EMULATE_SECTOR_SHIFT=5 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 333702c251..5f881d7394 100644 --- a/boards/cubepilot/cubeorange/nuttx-config/nsh/defconfig +++ b/boards/cubepilot/cubeorange/nuttx-config/nsh/defconfig @@ -148,6 +148,8 @@ CONFIG_PREALLOC_TIMERS=50 CONFIG_PRIORITY_INHERITANCE=y CONFIG_PTHREAD_MUTEX_ROBUST=y CONFIG_PTHREAD_STACK_MIN=512 +CONFIG_RAMTRON_EMULATE_PAGE_SHIFT=5 +CONFIG_RAMTRON_EMULATE_SECTOR_SHIFT=5 CONFIG_RAMTRON_SETSPEED=y CONFIG_RAM_SIZE=245760 CONFIG_RAM_START=0x20010000 diff --git a/boards/cubepilot/cubeorange/nuttx-config/test/defconfig b/boards/cubepilot/cubeorange/nuttx-config/test/defconfig index 6def80af98..387d393f6b 100644 --- a/boards/cubepilot/cubeorange/nuttx-config/test/defconfig +++ b/boards/cubepilot/cubeorange/nuttx-config/test/defconfig @@ -148,6 +148,8 @@ CONFIG_PREALLOC_TIMERS=50 CONFIG_PRIORITY_INHERITANCE=y CONFIG_PTHREAD_MUTEX_ROBUST=y CONFIG_PTHREAD_STACK_MIN=512 +CONFIG_RAMTRON_EMULATE_PAGE_SHIFT=5 +CONFIG_RAMTRON_EMULATE_SECTOR_SHIFT=5 CONFIG_RAMTRON_SETSPEED=y CONFIG_RAM_SIZE=245760 CONFIG_RAM_START=0x20010000 diff --git a/boards/cubepilot/cubeorangeplus/nuttx-config/nsh/defconfig b/boards/cubepilot/cubeorangeplus/nuttx-config/nsh/defconfig index 367658878f..439a5eb93c 100644 --- a/boards/cubepilot/cubeorangeplus/nuttx-config/nsh/defconfig +++ b/boards/cubepilot/cubeorangeplus/nuttx-config/nsh/defconfig @@ -148,6 +148,8 @@ CONFIG_PREALLOC_TIMERS=50 CONFIG_PRIORITY_INHERITANCE=y CONFIG_PTHREAD_MUTEX_ROBUST=y CONFIG_PTHREAD_STACK_MIN=512 +CONFIG_RAMTRON_EMULATE_PAGE_SHIFT=5 +CONFIG_RAMTRON_EMULATE_SECTOR_SHIFT=5 CONFIG_RAMTRON_SETSPEED=y CONFIG_RAM_SIZE=245760 CONFIG_RAM_START=0x20010000 diff --git a/boards/cubepilot/cubeorangeplus/nuttx-config/test/defconfig b/boards/cubepilot/cubeorangeplus/nuttx-config/test/defconfig index 8161de188a..62a9b86689 100644 --- a/boards/cubepilot/cubeorangeplus/nuttx-config/test/defconfig +++ b/boards/cubepilot/cubeorangeplus/nuttx-config/test/defconfig @@ -148,6 +148,8 @@ CONFIG_PREALLOC_TIMERS=50 CONFIG_PRIORITY_INHERITANCE=y CONFIG_PTHREAD_MUTEX_ROBUST=y CONFIG_PTHREAD_STACK_MIN=512 +CONFIG_RAMTRON_EMULATE_PAGE_SHIFT=5 +CONFIG_RAMTRON_EMULATE_SECTOR_SHIFT=5 CONFIG_RAMTRON_SETSPEED=y CONFIG_RAM_SIZE=245760 CONFIG_RAM_START=0x20010000 diff --git a/boards/cubepilot/cubeyellow/nuttx-config/nsh/defconfig b/boards/cubepilot/cubeyellow/nuttx-config/nsh/defconfig index be2bd9abc5..2dcf0c9dd7 100644 --- a/boards/cubepilot/cubeyellow/nuttx-config/nsh/defconfig +++ b/boards/cubepilot/cubeyellow/nuttx-config/nsh/defconfig @@ -147,6 +147,8 @@ CONFIG_PREALLOC_TIMERS=50 CONFIG_PRIORITY_INHERITANCE=y CONFIG_PTHREAD_MUTEX_ROBUST=y CONFIG_PTHREAD_STACK_MIN=512 +CONFIG_RAMTRON_EMULATE_PAGE_SHIFT=5 +CONFIG_RAMTRON_EMULATE_SECTOR_SHIFT=5 CONFIG_RAMTRON_SETSPEED=y CONFIG_RAM_SIZE=245760 CONFIG_RAM_START=0x20010000 diff --git a/boards/freefly/can-rtk-gps/nuttx-config/nsh/defconfig b/boards/freefly/can-rtk-gps/nuttx-config/nsh/defconfig index 3ea9c492e6..d295254d69 100644 --- a/boards/freefly/can-rtk-gps/nuttx-config/nsh/defconfig +++ b/boards/freefly/can-rtk-gps/nuttx-config/nsh/defconfig @@ -132,6 +132,8 @@ CONFIG_PREALLOC_TIMERS=50 CONFIG_PRIORITY_INHERITANCE=y CONFIG_PTHREAD_MUTEX_ROBUST=y CONFIG_PTHREAD_STACK_MIN=512 +CONFIG_RAMTRON_EMULATE_PAGE_SHIFT=5 +CONFIG_RAMTRON_EMULATE_SECTOR_SHIFT=5 CONFIG_RAMTRON_SETSPEED=y CONFIG_RAM_SIZE=245760 CONFIG_RAM_START=0x20010000 diff --git a/boards/holybro/can-gps-v1/nuttx-config/nsh/defconfig b/boards/holybro/can-gps-v1/nuttx-config/nsh/defconfig index 4dcee619f1..f95e8f5c0c 100644 --- a/boards/holybro/can-gps-v1/nuttx-config/nsh/defconfig +++ b/boards/holybro/can-gps-v1/nuttx-config/nsh/defconfig @@ -120,6 +120,8 @@ CONFIG_PREALLOC_TIMERS=50 CONFIG_PRIORITY_INHERITANCE=y CONFIG_PTHREAD_MUTEX_ROBUST=y CONFIG_PTHREAD_STACK_MIN=512 +CONFIG_RAMTRON_EMULATE_PAGE_SHIFT=5 +CONFIG_RAMTRON_EMULATE_SECTOR_SHIFT=5 CONFIG_RAMTRON_SETSPEED=y CONFIG_RAM_SIZE=262144 CONFIG_RAM_START=0x20000000 diff --git a/boards/holybro/durandal-v1/nuttx-config/nsh/defconfig b/boards/holybro/durandal-v1/nuttx-config/nsh/defconfig index 4464f881d1..2be97e6b00 100644 --- a/boards/holybro/durandal-v1/nuttx-config/nsh/defconfig +++ b/boards/holybro/durandal-v1/nuttx-config/nsh/defconfig @@ -149,6 +149,8 @@ CONFIG_PREALLOC_TIMERS=50 CONFIG_PRIORITY_INHERITANCE=y CONFIG_PTHREAD_MUTEX_ROBUST=y CONFIG_PTHREAD_STACK_MIN=512 +CONFIG_RAMTRON_EMULATE_PAGE_SHIFT=5 +CONFIG_RAMTRON_EMULATE_SECTOR_SHIFT=5 CONFIG_RAMTRON_SETSPEED=y CONFIG_RAM_SIZE=245760 CONFIG_RAM_START=0x20010000 diff --git a/boards/holybro/kakutef7/nuttx-config/nsh/defconfig b/boards/holybro/kakutef7/nuttx-config/nsh/defconfig index 3410f97087..c4bc8b2ab8 100644 --- a/boards/holybro/kakutef7/nuttx-config/nsh/defconfig +++ b/boards/holybro/kakutef7/nuttx-config/nsh/defconfig @@ -150,6 +150,8 @@ CONFIG_PREALLOC_TIMERS=50 CONFIG_PRIORITY_INHERITANCE=y CONFIG_PTHREAD_MUTEX_ROBUST=y CONFIG_PTHREAD_STACK_MIN=512 +CONFIG_RAMTRON_EMULATE_PAGE_SHIFT=5 +CONFIG_RAMTRON_EMULATE_SECTOR_SHIFT=5 CONFIG_RAMTRON_SETSPEED=y CONFIG_RAM_SIZE=245760 CONFIG_RAM_START=0x20010000 diff --git a/boards/holybro/kakuteh7/nuttx-config/nsh/defconfig b/boards/holybro/kakuteh7/nuttx-config/nsh/defconfig index a716028e20..330eedecc4 100644 --- a/boards/holybro/kakuteh7/nuttx-config/nsh/defconfig +++ b/boards/holybro/kakuteh7/nuttx-config/nsh/defconfig @@ -149,6 +149,8 @@ CONFIG_PREALLOC_TIMERS=50 CONFIG_PRIORITY_INHERITANCE=y CONFIG_PTHREAD_MUTEX_ROBUST=y CONFIG_PTHREAD_STACK_MIN=512 +CONFIG_RAMTRON_EMULATE_PAGE_SHIFT=5 +CONFIG_RAMTRON_EMULATE_SECTOR_SHIFT=5 CONFIG_RAMTRON_SETSPEED=y CONFIG_RAM_SIZE=245760 CONFIG_RAM_START=0x20010000 diff --git a/boards/holybro/kakuteh7mini/nuttx-config/nsh/defconfig b/boards/holybro/kakuteh7mini/nuttx-config/nsh/defconfig index bff4b99ca0..7f0fe7af9d 100644 --- a/boards/holybro/kakuteh7mini/nuttx-config/nsh/defconfig +++ b/boards/holybro/kakuteh7mini/nuttx-config/nsh/defconfig @@ -148,6 +148,8 @@ CONFIG_PREALLOC_TIMERS=50 CONFIG_PRIORITY_INHERITANCE=y CONFIG_PTHREAD_MUTEX_ROBUST=y CONFIG_PTHREAD_STACK_MIN=512 +CONFIG_RAMTRON_EMULATE_PAGE_SHIFT=5 +CONFIG_RAMTRON_EMULATE_SECTOR_SHIFT=5 CONFIG_RAMTRON_SETSPEED=y CONFIG_RAM_SIZE=245760 CONFIG_RAM_START=0x20010000 diff --git a/boards/holybro/kakuteh7v2/nuttx-config/nsh/defconfig b/boards/holybro/kakuteh7v2/nuttx-config/nsh/defconfig index 338df71016..8994309e20 100644 --- a/boards/holybro/kakuteh7v2/nuttx-config/nsh/defconfig +++ b/boards/holybro/kakuteh7v2/nuttx-config/nsh/defconfig @@ -148,6 +148,8 @@ CONFIG_PREALLOC_TIMERS=50 CONFIG_PRIORITY_INHERITANCE=y CONFIG_PTHREAD_MUTEX_ROBUST=y CONFIG_PTHREAD_STACK_MIN=512 +CONFIG_RAMTRON_EMULATE_PAGE_SHIFT=5 +CONFIG_RAMTRON_EMULATE_SECTOR_SHIFT=5 CONFIG_RAMTRON_SETSPEED=y CONFIG_RAM_SIZE=245760 CONFIG_RAM_START=0x20010000 diff --git a/boards/holybro/pix32v5/nuttx-config/nsh/defconfig b/boards/holybro/pix32v5/nuttx-config/nsh/defconfig index 3a834b3eec..257f8695bf 100644 --- a/boards/holybro/pix32v5/nuttx-config/nsh/defconfig +++ b/boards/holybro/pix32v5/nuttx-config/nsh/defconfig @@ -147,6 +147,8 @@ CONFIG_PREALLOC_TIMERS=50 CONFIG_PRIORITY_INHERITANCE=y CONFIG_PTHREAD_MUTEX_ROBUST=y CONFIG_PTHREAD_STACK_MIN=512 +CONFIG_RAMTRON_EMULATE_PAGE_SHIFT=5 +CONFIG_RAMTRON_EMULATE_SECTOR_SHIFT=5 CONFIG_RAMTRON_SETSPEED=y CONFIG_RAM_SIZE=245760 CONFIG_RAM_START=0x20010000 diff --git a/boards/matek/gnss-m9n-f4/nuttx-config/nsh/defconfig b/boards/matek/gnss-m9n-f4/nuttx-config/nsh/defconfig index 266c0e3666..102525dca3 100644 --- a/boards/matek/gnss-m9n-f4/nuttx-config/nsh/defconfig +++ b/boards/matek/gnss-m9n-f4/nuttx-config/nsh/defconfig @@ -138,6 +138,8 @@ CONFIG_PREALLOC_TIMERS=50 CONFIG_PRIORITY_INHERITANCE=y CONFIG_PTHREAD_MUTEX_ROBUST=y CONFIG_PTHREAD_STACK_MIN=512 +CONFIG_RAMTRON_EMULATE_PAGE_SHIFT=5 +CONFIG_RAMTRON_EMULATE_SECTOR_SHIFT=5 CONFIG_RAMTRON_SETSPEED=y CONFIG_RAM_SIZE=131072 CONFIG_RAM_START=0x20000000 diff --git a/boards/modalai/fc-v1/nuttx-config/nsh/defconfig b/boards/modalai/fc-v1/nuttx-config/nsh/defconfig index e53609c01d..f116d40e2e 100644 --- a/boards/modalai/fc-v1/nuttx-config/nsh/defconfig +++ b/boards/modalai/fc-v1/nuttx-config/nsh/defconfig @@ -146,6 +146,8 @@ CONFIG_PREALLOC_TIMERS=50 CONFIG_PRIORITY_INHERITANCE=y CONFIG_PTHREAD_MUTEX_ROBUST=y CONFIG_PTHREAD_STACK_MIN=512 +CONFIG_RAMTRON_EMULATE_PAGE_SHIFT=5 +CONFIG_RAMTRON_EMULATE_SECTOR_SHIFT=5 CONFIG_RAMTRON_SETSPEED=y CONFIG_RAM_SIZE=245760 CONFIG_RAM_START=0x20010000 diff --git a/boards/modalai/fc-v2/nuttx-config/nsh/defconfig b/boards/modalai/fc-v2/nuttx-config/nsh/defconfig index f35aba9035..0c799b496e 100644 --- a/boards/modalai/fc-v2/nuttx-config/nsh/defconfig +++ b/boards/modalai/fc-v2/nuttx-config/nsh/defconfig @@ -152,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=5 +CONFIG_RAMTRON_EMULATE_SECTOR_SHIFT=5 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 644b96581d..48a5bd334c 100644 --- a/boards/modalai/fc-v2/src/mtd.cpp +++ b/boards/modalai/fc-v2/src/mtd.cpp @@ -34,25 +34,19 @@ #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 native: 32K X 8, emulated as (1024 Blocks of 32) .bus_type = px4_mft_device_t::SPI, .devid = SPIDEV_FLASH(0) }; 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 / (1 << CONFIG_RAMTRON_EMULATE_SECTOR_SHIFT)) } }, }; diff --git a/boards/mro/ctrl-zero-classic/nuttx-config/nsh/defconfig b/boards/mro/ctrl-zero-classic/nuttx-config/nsh/defconfig index b8a6f0e779..9bd8b8fd00 100644 --- a/boards/mro/ctrl-zero-classic/nuttx-config/nsh/defconfig +++ b/boards/mro/ctrl-zero-classic/nuttx-config/nsh/defconfig @@ -149,6 +149,8 @@ CONFIG_PREALLOC_TIMERS=50 CONFIG_PRIORITY_INHERITANCE=y CONFIG_PTHREAD_MUTEX_ROBUST=y CONFIG_PTHREAD_STACK_MIN=512 +CONFIG_RAMTRON_EMULATE_PAGE_SHIFT=5 +CONFIG_RAMTRON_EMULATE_SECTOR_SHIFT=5 CONFIG_RAMTRON_SETSPEED=y CONFIG_RAM_SIZE=245760 CONFIG_RAM_START=0x20010000 diff --git a/boards/mro/ctrl-zero-f7-oem/nuttx-config/nsh/defconfig b/boards/mro/ctrl-zero-f7-oem/nuttx-config/nsh/defconfig index 41d6586235..b9551c20e5 100644 --- a/boards/mro/ctrl-zero-f7-oem/nuttx-config/nsh/defconfig +++ b/boards/mro/ctrl-zero-f7-oem/nuttx-config/nsh/defconfig @@ -146,6 +146,8 @@ CONFIG_PREALLOC_TIMERS=50 CONFIG_PRIORITY_INHERITANCE=y CONFIG_PTHREAD_MUTEX_ROBUST=y CONFIG_PTHREAD_STACK_MIN=512 +CONFIG_RAMTRON_EMULATE_PAGE_SHIFT=5 +CONFIG_RAMTRON_EMULATE_SECTOR_SHIFT=5 CONFIG_RAMTRON_SETSPEED=y CONFIG_RAM_SIZE=245760 CONFIG_RAM_START=0x20010000 diff --git a/boards/mro/ctrl-zero-f7/nuttx-config/nsh/defconfig b/boards/mro/ctrl-zero-f7/nuttx-config/nsh/defconfig index 764c0f3d5a..553cc8187f 100644 --- a/boards/mro/ctrl-zero-f7/nuttx-config/nsh/defconfig +++ b/boards/mro/ctrl-zero-f7/nuttx-config/nsh/defconfig @@ -146,6 +146,8 @@ CONFIG_PREALLOC_TIMERS=50 CONFIG_PRIORITY_INHERITANCE=y CONFIG_PTHREAD_MUTEX_ROBUST=y CONFIG_PTHREAD_STACK_MIN=512 +CONFIG_RAMTRON_EMULATE_PAGE_SHIFT=5 +CONFIG_RAMTRON_EMULATE_SECTOR_SHIFT=5 CONFIG_RAMTRON_SETSPEED=y CONFIG_RAM_SIZE=245760 CONFIG_RAM_START=0x20010000 diff --git a/boards/mro/ctrl-zero-h7-oem/nuttx-config/nsh/defconfig b/boards/mro/ctrl-zero-h7-oem/nuttx-config/nsh/defconfig index e169c24027..7223031aa8 100644 --- a/boards/mro/ctrl-zero-h7-oem/nuttx-config/nsh/defconfig +++ b/boards/mro/ctrl-zero-h7-oem/nuttx-config/nsh/defconfig @@ -147,6 +147,8 @@ CONFIG_PREALLOC_TIMERS=50 CONFIG_PRIORITY_INHERITANCE=y CONFIG_PTHREAD_MUTEX_ROBUST=y CONFIG_PTHREAD_STACK_MIN=512 +CONFIG_RAMTRON_EMULATE_PAGE_SHIFT=5 +CONFIG_RAMTRON_EMULATE_SECTOR_SHIFT=5 CONFIG_RAMTRON_SETSPEED=y CONFIG_RAM_SIZE=245760 CONFIG_RAM_START=0x20010000 diff --git a/boards/mro/ctrl-zero-h7/nuttx-config/nsh/defconfig b/boards/mro/ctrl-zero-h7/nuttx-config/nsh/defconfig index c533863957..51a503c418 100644 --- a/boards/mro/ctrl-zero-h7/nuttx-config/nsh/defconfig +++ b/boards/mro/ctrl-zero-h7/nuttx-config/nsh/defconfig @@ -147,6 +147,8 @@ CONFIG_PREALLOC_TIMERS=50 CONFIG_PRIORITY_INHERITANCE=y CONFIG_PTHREAD_MUTEX_ROBUST=y CONFIG_PTHREAD_STACK_MIN=512 +CONFIG_RAMTRON_EMULATE_PAGE_SHIFT=5 +CONFIG_RAMTRON_EMULATE_SECTOR_SHIFT=5 CONFIG_RAMTRON_SETSPEED=y CONFIG_RAM_SIZE=245760 CONFIG_RAM_START=0x20010000 diff --git a/boards/mro/pixracerpro/nuttx-config/nsh/defconfig b/boards/mro/pixracerpro/nuttx-config/nsh/defconfig index f309a3fe3f..7cbf355d40 100644 --- a/boards/mro/pixracerpro/nuttx-config/nsh/defconfig +++ b/boards/mro/pixracerpro/nuttx-config/nsh/defconfig @@ -148,6 +148,8 @@ CONFIG_PREALLOC_TIMERS=50 CONFIG_PRIORITY_INHERITANCE=y CONFIG_PTHREAD_MUTEX_ROBUST=y CONFIG_PTHREAD_STACK_MIN=512 +CONFIG_RAMTRON_EMULATE_PAGE_SHIFT=5 +CONFIG_RAMTRON_EMULATE_SECTOR_SHIFT=5 CONFIG_RAMTRON_SETSPEED=y CONFIG_RAM_SIZE=245760 CONFIG_RAM_START=0x20010000 diff --git a/boards/mro/x21-777/nuttx-config/nsh/defconfig b/boards/mro/x21-777/nuttx-config/nsh/defconfig index 8774af0687..b61d8a33e3 100644 --- a/boards/mro/x21-777/nuttx-config/nsh/defconfig +++ b/boards/mro/x21-777/nuttx-config/nsh/defconfig @@ -146,6 +146,8 @@ CONFIG_PREALLOC_TIMERS=50 CONFIG_PRIORITY_INHERITANCE=y CONFIG_PTHREAD_MUTEX_ROBUST=y CONFIG_PTHREAD_STACK_MIN=512 +CONFIG_RAMTRON_EMULATE_PAGE_SHIFT=5 +CONFIG_RAMTRON_EMULATE_SECTOR_SHIFT=5 CONFIG_RAMTRON_SETSPEED=y CONFIG_RAM_SIZE=245760 CONFIG_RAM_START=0x20010000 diff --git a/boards/mro/x21/nuttx-config/nsh/defconfig b/boards/mro/x21/nuttx-config/nsh/defconfig index 60e71b3c9e..b5b5614c51 100644 --- a/boards/mro/x21/nuttx-config/nsh/defconfig +++ b/boards/mro/x21/nuttx-config/nsh/defconfig @@ -141,6 +141,8 @@ CONFIG_PREALLOC_TIMERS=50 CONFIG_PRIORITY_INHERITANCE=y CONFIG_PTHREAD_MUTEX_ROBUST=y CONFIG_PTHREAD_STACK_MIN=512 +CONFIG_RAMTRON_EMULATE_PAGE_SHIFT=5 +CONFIG_RAMTRON_EMULATE_SECTOR_SHIFT=5 CONFIG_RAMTRON_SETSPEED=y CONFIG_RAM_SIZE=262144 CONFIG_RAM_START=0x20000000 diff --git a/boards/nxp/fmuk66-e/nuttx-config/nsh/defconfig b/boards/nxp/fmuk66-e/nuttx-config/nsh/defconfig index c6f55f90ce..9d591289b7 100644 --- a/boards/nxp/fmuk66-e/nuttx-config/nsh/defconfig +++ b/boards/nxp/fmuk66-e/nuttx-config/nsh/defconfig @@ -168,6 +168,8 @@ CONFIG_PIPES=y CONFIG_PREALLOC_TIMERS=50 CONFIG_PRIORITY_INHERITANCE=y CONFIG_PTHREAD_STACK_MIN=512 +CONFIG_RAMTRON_EMULATE_PAGE_SHIFT=5 +CONFIG_RAMTRON_EMULATE_SECTOR_SHIFT=5 CONFIG_RAMTRON_SETSPEED=y CONFIG_RAM_SIZE=262144 CONFIG_RAM_START=0x1fff0000 diff --git a/boards/nxp/fmuk66-e/nuttx-config/socketcan/defconfig b/boards/nxp/fmuk66-e/nuttx-config/socketcan/defconfig index 947e059674..9b5559eaf6 100644 --- a/boards/nxp/fmuk66-e/nuttx-config/socketcan/defconfig +++ b/boards/nxp/fmuk66-e/nuttx-config/socketcan/defconfig @@ -171,6 +171,8 @@ CONFIG_PIPES=y CONFIG_PREALLOC_TIMERS=50 CONFIG_PRIORITY_INHERITANCE=y CONFIG_PTHREAD_STACK_MIN=512 +CONFIG_RAMTRON_EMULATE_PAGE_SHIFT=5 +CONFIG_RAMTRON_EMULATE_SECTOR_SHIFT=5 CONFIG_RAMTRON_SETSPEED=y CONFIG_RAM_SIZE=262144 CONFIG_RAM_START=0x1fff0000 diff --git a/boards/nxp/fmuk66-v3/nuttx-config/nsh/defconfig b/boards/nxp/fmuk66-v3/nuttx-config/nsh/defconfig index 31c4b33b66..6bd106b415 100644 --- a/boards/nxp/fmuk66-v3/nuttx-config/nsh/defconfig +++ b/boards/nxp/fmuk66-v3/nuttx-config/nsh/defconfig @@ -171,6 +171,8 @@ CONFIG_PIPES=y CONFIG_PREALLOC_TIMERS=50 CONFIG_PRIORITY_INHERITANCE=y CONFIG_PTHREAD_STACK_MIN=512 +CONFIG_RAMTRON_EMULATE_PAGE_SHIFT=5 +CONFIG_RAMTRON_EMULATE_SECTOR_SHIFT=5 CONFIG_RAMTRON_SETSPEED=y CONFIG_RAM_SIZE=262144 CONFIG_RAM_START=0x1fff0000 diff --git a/boards/nxp/fmuk66-v3/nuttx-config/socketcan/defconfig b/boards/nxp/fmuk66-v3/nuttx-config/socketcan/defconfig index adcfcee49f..cff2a6be8f 100644 --- a/boards/nxp/fmuk66-v3/nuttx-config/socketcan/defconfig +++ b/boards/nxp/fmuk66-v3/nuttx-config/socketcan/defconfig @@ -170,6 +170,8 @@ CONFIG_PIPES=y CONFIG_PREALLOC_TIMERS=50 CONFIG_PRIORITY_INHERITANCE=y CONFIG_PTHREAD_STACK_MIN=512 +CONFIG_RAMTRON_EMULATE_PAGE_SHIFT=5 +CONFIG_RAMTRON_EMULATE_SECTOR_SHIFT=5 CONFIG_RAMTRON_SETSPEED=y CONFIG_RAM_SIZE=262144 CONFIG_RAM_START=0x1fff0000 diff --git a/boards/nxp/fmuk66-v3/nuttx-config/test/defconfig b/boards/nxp/fmuk66-v3/nuttx-config/test/defconfig index 83ac893d6c..d340e15847 100644 --- a/boards/nxp/fmuk66-v3/nuttx-config/test/defconfig +++ b/boards/nxp/fmuk66-v3/nuttx-config/test/defconfig @@ -171,6 +171,8 @@ CONFIG_PIPES=y CONFIG_PREALLOC_TIMERS=50 CONFIG_PRIORITY_INHERITANCE=y CONFIG_PTHREAD_STACK_MIN=512 +CONFIG_RAMTRON_EMULATE_PAGE_SHIFT=5 +CONFIG_RAMTRON_EMULATE_SECTOR_SHIFT=5 CONFIG_RAMTRON_SETSPEED=y CONFIG_RAM_SIZE=262144 CONFIG_RAM_START=0x1fff0000 diff --git a/boards/nxp/fmurt1062-v1/nuttx-config/nsh/defconfig b/boards/nxp/fmurt1062-v1/nuttx-config/nsh/defconfig index 66968d1d24..5c945c7355 100644 --- a/boards/nxp/fmurt1062-v1/nuttx-config/nsh/defconfig +++ b/boards/nxp/fmurt1062-v1/nuttx-config/nsh/defconfig @@ -184,6 +184,8 @@ CONFIG_PIPES=y CONFIG_PREALLOC_TIMERS=50 CONFIG_PRIORITY_INHERITANCE=y CONFIG_PTHREAD_STACK_MIN=512 +CONFIG_RAMTRON_EMULATE_PAGE_SHIFT=5 +CONFIG_RAMTRON_EMULATE_SECTOR_SHIFT=5 CONFIG_RAMTRON_SETSPEED=y CONFIG_RAM_SIZE=1048576 CONFIG_RAM_START=0x20200000 diff --git a/boards/px4/fmu-v2/nuttx-config/nsh/defconfig b/boards/px4/fmu-v2/nuttx-config/nsh/defconfig index 221553a723..086587205a 100644 --- a/boards/px4/fmu-v2/nuttx-config/nsh/defconfig +++ b/boards/px4/fmu-v2/nuttx-config/nsh/defconfig @@ -136,6 +136,8 @@ CONFIG_PRIORITY_INHERITANCE=y CONFIG_PTHREAD_MUTEX_DEFAULT_PRIO_INHERIT=y CONFIG_PTHREAD_MUTEX_ROBUST=y CONFIG_PTHREAD_STACK_MIN=512 +CONFIG_RAMTRON_EMULATE_PAGE_SHIFT=5 +CONFIG_RAMTRON_EMULATE_SECTOR_SHIFT=5 CONFIG_RAMTRON_SETSPEED=y CONFIG_RAM_SIZE=262144 CONFIG_RAM_START=0x20000000 diff --git a/boards/px4/fmu-v3/nuttx-config/nsh/defconfig b/boards/px4/fmu-v3/nuttx-config/nsh/defconfig index bbf056f6a3..7cda8cfcaf 100644 --- a/boards/px4/fmu-v3/nuttx-config/nsh/defconfig +++ b/boards/px4/fmu-v3/nuttx-config/nsh/defconfig @@ -141,6 +141,8 @@ CONFIG_PREALLOC_TIMERS=50 CONFIG_PRIORITY_INHERITANCE=y CONFIG_PTHREAD_MUTEX_ROBUST=y CONFIG_PTHREAD_STACK_MIN=512 +CONFIG_RAMTRON_EMULATE_PAGE_SHIFT=5 +CONFIG_RAMTRON_EMULATE_SECTOR_SHIFT=5 CONFIG_RAMTRON_SETSPEED=y CONFIG_RAM_SIZE=262144 CONFIG_RAM_START=0x20000000 diff --git a/boards/px4/fmu-v4/nuttx-config/nsh/defconfig b/boards/px4/fmu-v4/nuttx-config/nsh/defconfig index 8ac74111e4..543fb546bf 100644 --- a/boards/px4/fmu-v4/nuttx-config/nsh/defconfig +++ b/boards/px4/fmu-v4/nuttx-config/nsh/defconfig @@ -140,6 +140,8 @@ CONFIG_PREALLOC_TIMERS=50 CONFIG_PRIORITY_INHERITANCE=y CONFIG_PTHREAD_MUTEX_ROBUST=y CONFIG_PTHREAD_STACK_MIN=512 +CONFIG_RAMTRON_EMULATE_PAGE_SHIFT=5 +CONFIG_RAMTRON_EMULATE_SECTOR_SHIFT=5 CONFIG_RAMTRON_SETSPEED=y CONFIG_RAM_SIZE=262144 CONFIG_RAM_START=0x20000000 diff --git a/boards/px4/fmu-v4/nuttx-config/test/defconfig b/boards/px4/fmu-v4/nuttx-config/test/defconfig index 2a09e687bf..9a02cef6e0 100644 --- a/boards/px4/fmu-v4/nuttx-config/test/defconfig +++ b/boards/px4/fmu-v4/nuttx-config/test/defconfig @@ -141,6 +141,8 @@ CONFIG_PREALLOC_TIMERS=50 CONFIG_PRIORITY_INHERITANCE=y CONFIG_PTHREAD_MUTEX_ROBUST=y CONFIG_PTHREAD_STACK_MIN=512 +CONFIG_RAMTRON_EMULATE_PAGE_SHIFT=5 +CONFIG_RAMTRON_EMULATE_SECTOR_SHIFT=5 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 6dad97af68..25089317ed 100644 --- a/boards/px4/fmu-v4pro/nuttx-config/nsh/defconfig +++ b/boards/px4/fmu-v4pro/nuttx-config/nsh/defconfig @@ -140,6 +140,8 @@ CONFIG_PREALLOC_TIMERS=50 CONFIG_PRIORITY_INHERITANCE=y CONFIG_PTHREAD_MUTEX_ROBUST=y CONFIG_PTHREAD_STACK_MIN=512 +CONFIG_RAMTRON_EMULATE_PAGE_SHIFT=5 +CONFIG_RAMTRON_EMULATE_SECTOR_SHIFT=5 CONFIG_RAMTRON_SETSPEED=y CONFIG_RAM_SIZE=393216 CONFIG_RAM_START=0x20000000 diff --git a/boards/px4/fmu-v4pro/nuttx-config/test/defconfig b/boards/px4/fmu-v4pro/nuttx-config/test/defconfig index ff337efc27..b24350d06e 100644 --- a/boards/px4/fmu-v4pro/nuttx-config/test/defconfig +++ b/boards/px4/fmu-v4pro/nuttx-config/test/defconfig @@ -141,6 +141,8 @@ CONFIG_PREALLOC_TIMERS=50 CONFIG_PRIORITY_INHERITANCE=y CONFIG_PTHREAD_MUTEX_ROBUST=y CONFIG_PTHREAD_STACK_MIN=512 +CONFIG_RAMTRON_EMULATE_PAGE_SHIFT=5 +CONFIG_RAMTRON_EMULATE_SECTOR_SHIFT=5 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..f32f1dee1d 100644 --- a/boards/px4/fmu-v4pro/src/mtd.cpp +++ b/boards/px4/fmu-v4pro/src/mtd.cpp @@ -34,7 +34,7 @@ #include #include // KiB BS nB -static const px4_mft_device_t spi2 = { // FM25V01A on FMUM 16K +static const px4_mft_device_t spi2 = { // FM25V01A on FMUM native: 16K X 8, emulated as (512 Blocks of 32) .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 = 32 + .nblocks = (16384 / (1 << CONFIG_RAMTRON_EMULATE_PAGE_SHIFT)) }, }, }; diff --git a/boards/px4/fmu-v5/nuttx-config/cryptotest/defconfig b/boards/px4/fmu-v5/nuttx-config/cryptotest/defconfig index cfa3c56802..f5e9ec7dee 100644 --- a/boards/px4/fmu-v5/nuttx-config/cryptotest/defconfig +++ b/boards/px4/fmu-v5/nuttx-config/cryptotest/defconfig @@ -148,6 +148,8 @@ CONFIG_PREALLOC_TIMERS=50 CONFIG_PRIORITY_INHERITANCE=y CONFIG_PTHREAD_MUTEX_ROBUST=y CONFIG_PTHREAD_STACK_MIN=512 +CONFIG_RAMTRON_EMULATE_PAGE_SHIFT=5 +CONFIG_RAMTRON_EMULATE_SECTOR_SHIFT=5 CONFIG_RAMTRON_SETSPEED=y CONFIG_RAM_SIZE=245760 CONFIG_RAM_START=0x20010000 diff --git a/boards/px4/fmu-v5/nuttx-config/cyphal/defconfig b/boards/px4/fmu-v5/nuttx-config/cyphal/defconfig index 3f40bfd397..1f4256f27b 100644 --- a/boards/px4/fmu-v5/nuttx-config/cyphal/defconfig +++ b/boards/px4/fmu-v5/nuttx-config/cyphal/defconfig @@ -148,6 +148,8 @@ CONFIG_PREALLOC_TIMERS=50 CONFIG_PRIORITY_INHERITANCE=y CONFIG_PTHREAD_MUTEX_ROBUST=y CONFIG_PTHREAD_STACK_MIN=512 +CONFIG_RAMTRON_EMULATE_PAGE_SHIFT=5 +CONFIG_RAMTRON_EMULATE_SECTOR_SHIFT=5 CONFIG_RAMTRON_SETSPEED=y CONFIG_RAM_SIZE=245760 CONFIG_RAM_START=0x20010000 diff --git a/boards/px4/fmu-v5/nuttx-config/debug/defconfig b/boards/px4/fmu-v5/nuttx-config/debug/defconfig index 52cd3e1c70..fdf2d4a9a0 100644 --- a/boards/px4/fmu-v5/nuttx-config/debug/defconfig +++ b/boards/px4/fmu-v5/nuttx-config/debug/defconfig @@ -192,6 +192,8 @@ CONFIG_PREALLOC_TIMERS=50 CONFIG_PRIORITY_INHERITANCE=y CONFIG_PTHREAD_MUTEX_ROBUST=y CONFIG_PTHREAD_STACK_MIN=512 +CONFIG_RAMTRON_EMULATE_PAGE_SHIFT=5 +CONFIG_RAMTRON_EMULATE_SECTOR_SHIFT=5 CONFIG_RAMTRON_SETSPEED=y CONFIG_RAM_SIZE=245760 CONFIG_RAM_START=0x20010000 diff --git a/boards/px4/fmu-v5/nuttx-config/nsh/defconfig b/boards/px4/fmu-v5/nuttx-config/nsh/defconfig index ba372ae3ec..81aa1bec53 100644 --- a/boards/px4/fmu-v5/nuttx-config/nsh/defconfig +++ b/boards/px4/fmu-v5/nuttx-config/nsh/defconfig @@ -146,6 +146,8 @@ CONFIG_PREALLOC_TIMERS=50 CONFIG_PRIORITY_INHERITANCE=y CONFIG_PTHREAD_MUTEX_ROBUST=y CONFIG_PTHREAD_STACK_MIN=512 +CONFIG_RAMTRON_EMULATE_PAGE_SHIFT=5 +CONFIG_RAMTRON_EMULATE_SECTOR_SHIFT=5 CONFIG_RAMTRON_SETSPEED=y CONFIG_RAM_SIZE=245760 CONFIG_RAM_START=0x20010000 diff --git a/boards/px4/fmu-v5/nuttx-config/protected/defconfig b/boards/px4/fmu-v5/nuttx-config/protected/defconfig index bba4ab5b26..f82eaf8cf6 100644 --- a/boards/px4/fmu-v5/nuttx-config/protected/defconfig +++ b/boards/px4/fmu-v5/nuttx-config/protected/defconfig @@ -152,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=5 +CONFIG_RAMTRON_EMULATE_SECTOR_SHIFT=5 CONFIG_RAMTRON_SETSPEED=y CONFIG_RAM_SIZE=245760 CONFIG_RAM_START=0x20010000 diff --git a/boards/px4/fmu-v5/nuttx-config/stackcheck/defconfig b/boards/px4/fmu-v5/nuttx-config/stackcheck/defconfig index 334e594a27..efec10a978 100644 --- a/boards/px4/fmu-v5/nuttx-config/stackcheck/defconfig +++ b/boards/px4/fmu-v5/nuttx-config/stackcheck/defconfig @@ -147,6 +147,8 @@ CONFIG_PREALLOC_TIMERS=50 CONFIG_PRIORITY_INHERITANCE=y CONFIG_PTHREAD_MUTEX_ROBUST=y CONFIG_PTHREAD_STACK_MIN=512 +CONFIG_RAMTRON_EMULATE_PAGE_SHIFT=5 +CONFIG_RAMTRON_EMULATE_SECTOR_SHIFT=5 CONFIG_RAMTRON_SETSPEED=y CONFIG_RAM_SIZE=245760 CONFIG_RAM_START=0x20010000 diff --git a/boards/px4/fmu-v5/nuttx-config/test/defconfig b/boards/px4/fmu-v5/nuttx-config/test/defconfig index 4e653c46ee..8e67566725 100644 --- a/boards/px4/fmu-v5/nuttx-config/test/defconfig +++ b/boards/px4/fmu-v5/nuttx-config/test/defconfig @@ -146,6 +146,8 @@ CONFIG_PREALLOC_TIMERS=50 CONFIG_PRIORITY_INHERITANCE=y CONFIG_PTHREAD_MUTEX_ROBUST=y CONFIG_PTHREAD_STACK_MIN=512 +CONFIG_RAMTRON_EMULATE_PAGE_SHIFT=5 +CONFIG_RAMTRON_EMULATE_SECTOR_SHIFT=5 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 d72ba45c6d..d27c259ee5 100644 --- a/boards/px4/fmu-v5x/nuttx-config/nsh/defconfig +++ b/boards/px4/fmu-v5x/nuttx-config/nsh/defconfig @@ -185,6 +185,8 @@ CONFIG_PREALLOC_TIMERS=50 CONFIG_PRIORITY_INHERITANCE=y CONFIG_PTHREAD_MUTEX_ROBUST=y CONFIG_PTHREAD_STACK_MIN=512 +CONFIG_RAMTRON_EMULATE_PAGE_SHIFT=5 +CONFIG_RAMTRON_EMULATE_SECTOR_SHIFT=5 CONFIG_RAMTRON_SETSPEED=y CONFIG_RAM_SIZE=245760 CONFIG_RAM_START=0x20010000 diff --git a/boards/px4/fmu-v5x/nuttx-config/test/defconfig b/boards/px4/fmu-v5x/nuttx-config/test/defconfig index e5b66b466a..f3254fb7c8 100644 --- a/boards/px4/fmu-v5x/nuttx-config/test/defconfig +++ b/boards/px4/fmu-v5x/nuttx-config/test/defconfig @@ -183,6 +183,8 @@ CONFIG_PREALLOC_TIMERS=50 CONFIG_PRIORITY_INHERITANCE=y CONFIG_PTHREAD_MUTEX_ROBUST=y CONFIG_PTHREAD_STACK_MIN=512 +CONFIG_RAMTRON_EMULATE_PAGE_SHIFT=5 +CONFIG_RAMTRON_EMULATE_SECTOR_SHIFT=5 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 fc1e97d2c8..c0139d1232 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 native: 32K X 8, emulated as (1024 Blocks of 32) .bus_type = px4_mft_device_t::SPI, .devid = SPIDEV_FLASH(0) }; @@ -50,18 +50,12 @@ static const px4_mft_device_t i2c4 = { // 24LC64T on IMU 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 / (1 << CONFIG_RAMTRON_EMULATE_SECTOR_SHIFT)) } }, }; diff --git a/boards/px4/fmu-v6c/nuttx-config/nsh/defconfig b/boards/px4/fmu-v6c/nuttx-config/nsh/defconfig index b527b9a2a6..02ac045e13 100644 --- a/boards/px4/fmu-v6c/nuttx-config/nsh/defconfig +++ b/boards/px4/fmu-v6c/nuttx-config/nsh/defconfig @@ -151,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=5 +CONFIG_RAMTRON_EMULATE_SECTOR_SHIFT=5 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..5efe7bac64 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 native: 32K X 8, emulated as (1024 Blocks of 32) .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 / (1 << CONFIG_RAMTRON_EMULATE_SECTOR_SHIFT)) } }, }; diff --git a/boards/px4/fmu-v6u/nuttx-config/nsh/defconfig b/boards/px4/fmu-v6u/nuttx-config/nsh/defconfig index fa9b81078c..19376fdc87 100644 --- a/boards/px4/fmu-v6u/nuttx-config/nsh/defconfig +++ b/boards/px4/fmu-v6u/nuttx-config/nsh/defconfig @@ -151,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=5 +CONFIG_RAMTRON_EMULATE_SECTOR_SHIFT=5 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 644b96581d..48a5bd334c 100644 --- a/boards/px4/fmu-v6u/src/mtd.cpp +++ b/boards/px4/fmu-v6u/src/mtd.cpp @@ -34,25 +34,19 @@ #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 native: 32K X 8, emulated as (1024 Blocks of 32) .bus_type = px4_mft_device_t::SPI, .devid = SPIDEV_FLASH(0) }; 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 / (1 << CONFIG_RAMTRON_EMULATE_SECTOR_SHIFT)) } }, }; diff --git a/boards/px4/fmu-v6x/nuttx-config/nsh/defconfig b/boards/px4/fmu-v6x/nuttx-config/nsh/defconfig index 13191fc716..c355dbfd36 100644 --- a/boards/px4/fmu-v6x/nuttx-config/nsh/defconfig +++ b/boards/px4/fmu-v6x/nuttx-config/nsh/defconfig @@ -189,6 +189,8 @@ CONFIG_PREALLOC_TIMERS=50 CONFIG_PRIORITY_INHERITANCE=y CONFIG_PTHREAD_MUTEX_ROBUST=y CONFIG_PTHREAD_STACK_MIN=512 +CONFIG_RAMTRON_EMULATE_PAGE_SHIFT=5 +CONFIG_RAMTRON_EMULATE_SECTOR_SHIFT=5 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 fc1e97d2c8..c0139d1232 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 native: 32K X 8, emulated as (1024 Blocks of 32) .bus_type = px4_mft_device_t::SPI, .devid = SPIDEV_FLASH(0) }; @@ -50,18 +50,12 @@ static const px4_mft_device_t i2c4 = { // 24LC64T on IMU 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 / (1 << CONFIG_RAMTRON_EMULATE_SECTOR_SHIFT)) } }, }; diff --git a/boards/siyi/n7/nuttx-config/nsh/defconfig b/boards/siyi/n7/nuttx-config/nsh/defconfig index 766d2b554f..c06b04d176 100644 --- a/boards/siyi/n7/nuttx-config/nsh/defconfig +++ b/boards/siyi/n7/nuttx-config/nsh/defconfig @@ -148,6 +148,8 @@ CONFIG_PREALLOC_TIMERS=50 CONFIG_PRIORITY_INHERITANCE=y CONFIG_PTHREAD_MUTEX_ROBUST=y CONFIG_PTHREAD_STACK_MIN=512 +CONFIG_RAMTRON_EMULATE_PAGE_SHIFT=5 +CONFIG_RAMTRON_EMULATE_SECTOR_SHIFT=5 CONFIG_RAMTRON_SETSPEED=y CONFIG_RAM_SIZE=245760 CONFIG_RAM_START=0x20010000 diff --git a/boards/sky-drones/smartap-airlink/nuttx-config/nsh/defconfig b/boards/sky-drones/smartap-airlink/nuttx-config/nsh/defconfig index edce2f773a..c3df909ceb 100644 --- a/boards/sky-drones/smartap-airlink/nuttx-config/nsh/defconfig +++ b/boards/sky-drones/smartap-airlink/nuttx-config/nsh/defconfig @@ -181,6 +181,8 @@ CONFIG_PREALLOC_TIMERS=50 CONFIG_PRIORITY_INHERITANCE=y CONFIG_PTHREAD_MUTEX_ROBUST=y CONFIG_PTHREAD_STACK_MIN=512 +CONFIG_RAMTRON_EMULATE_PAGE_SHIFT=5 +CONFIG_RAMTRON_EMULATE_SECTOR_SHIFT=5 CONFIG_RAMTRON_SETSPEED=y CONFIG_RAM_SIZE=245760 CONFIG_RAM_START=0x20010000 diff --git a/boards/sky-drones/smartap-airlink/src/mtd.cpp b/boards/sky-drones/smartap-airlink/src/mtd.cpp index 8b74a4617c..742b463041 100644 --- a/boards/sky-drones/smartap-airlink/src/mtd.cpp +++ b/boards/sky-drones/smartap-airlink/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 native: 32K X 8, emulated as (1024 Blocks of 32) .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 / (1 << CONFIG_RAMTRON_EMULATE_SECTOR_SHIFT)) } }, }; diff --git a/boards/thepeach/k1/nuttx-config/nsh/defconfig b/boards/thepeach/k1/nuttx-config/nsh/defconfig index 7d565b71aa..04ea6197a0 100644 --- a/boards/thepeach/k1/nuttx-config/nsh/defconfig +++ b/boards/thepeach/k1/nuttx-config/nsh/defconfig @@ -141,6 +141,8 @@ CONFIG_PREALLOC_TIMERS=50 CONFIG_PRIORITY_INHERITANCE=y CONFIG_PTHREAD_MUTEX_ROBUST=y CONFIG_PTHREAD_STACK_MIN=512 +CONFIG_RAMTRON_EMULATE_PAGE_SHIFT=5 +CONFIG_RAMTRON_EMULATE_SECTOR_SHIFT=5 CONFIG_RAMTRON_SETSPEED=y CONFIG_RAM_SIZE=262144 CONFIG_RAM_START=0x20000000 diff --git a/boards/thepeach/r1/nuttx-config/nsh/defconfig b/boards/thepeach/r1/nuttx-config/nsh/defconfig index 4903f2754f..cd0486b09e 100644 --- a/boards/thepeach/r1/nuttx-config/nsh/defconfig +++ b/boards/thepeach/r1/nuttx-config/nsh/defconfig @@ -141,6 +141,8 @@ CONFIG_PREALLOC_TIMERS=50 CONFIG_PRIORITY_INHERITANCE=y CONFIG_PTHREAD_MUTEX_ROBUST=y CONFIG_PTHREAD_STACK_MIN=512 +CONFIG_RAMTRON_EMULATE_PAGE_SHIFT=5 +CONFIG_RAMTRON_EMULATE_SECTOR_SHIFT=5 CONFIG_RAMTRON_SETSPEED=y CONFIG_RAM_SIZE=262144 CONFIG_RAM_START=0x20000000 diff --git a/boards/uvify/core/nuttx-config/nsh/defconfig b/boards/uvify/core/nuttx-config/nsh/defconfig index d2ffa4f1a9..3870bebea9 100644 --- a/boards/uvify/core/nuttx-config/nsh/defconfig +++ b/boards/uvify/core/nuttx-config/nsh/defconfig @@ -140,6 +140,8 @@ CONFIG_PREALLOC_TIMERS=50 CONFIG_PRIORITY_INHERITANCE=y CONFIG_PTHREAD_MUTEX_ROBUST=y CONFIG_PTHREAD_STACK_MIN=512 +CONFIG_RAMTRON_EMULATE_PAGE_SHIFT=5 +CONFIG_RAMTRON_EMULATE_SECTOR_SHIFT=5 CONFIG_RAMTRON_SETSPEED=y CONFIG_RAM_SIZE=262144 CONFIG_RAM_START=0x20000000 diff --git a/platforms/nuttx/src/px4/common/px4_mtd.cpp b/platforms/nuttx/src/px4/common/px4_mtd.cpp index 8f45bd58e3..f4b3476722 100644 --- a/platforms/nuttx/src/px4/common/px4_mtd.cpp +++ b/platforms/nuttx/src/px4/common/px4_mtd.cpp @@ -249,25 +249,19 @@ 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 native: 32K X 8, emulated as (1024 Blocks of 32) .bus_type = px4_mft_device_t::SPI, .devid = SPIDEV_FLASH(0) }; const px4_mtd_entry_t fram = { .device = &spifram, - .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 / (1 << CONFIG_RAMTRON_EMULATE_SECTOR_SHIFT)) } }, };