mtd: update to 1-byte FRAM granularity

This commit is contained in:
Igor Mišić 2023-02-15 16:50:47 +01:00
parent fa31c128dd
commit b32ef40af7
No known key found for this signature in database
GPG Key ID: 2C4E2FD15C2B0E7D
19 changed files with 79 additions and 29 deletions

View File

@ -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

View File

@ -34,7 +34,7 @@
#include <nuttx/spi/spi.h>
#include <px4_platform_common/px4_manifest.h>
// 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
}
},
};

View File

@ -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

View File

@ -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

View File

@ -46,7 +46,7 @@ static const px4_mtd_entry_t fmum_fram = {
{
.type = MTD_PARAMETERS,
.path = "/fs/mtd_params",
.nblocks = 64
.nblocks = 32768
}
},
};

View File

@ -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

View File

@ -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

View File

@ -46,7 +46,7 @@ static const px4_mtd_entry_t fmum_fram = {
{
.type = MTD_PARAMETERS,
.path = "/fs/mtd_params",
.nblocks = 32
.nblocks = 16384
},
},
};

View File

@ -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

View File

@ -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

View File

@ -34,7 +34,7 @@
#include <nuttx/spi/spi.h>
#include <px4_platform_common/px4_manifest.h>
// 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
}
},
};

View File

@ -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

View File

@ -34,7 +34,7 @@
#include <nuttx/spi/spi.h>
#include <px4_platform_common/px4_manifest.h>
// 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
}
},
};

View File

@ -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

View File

@ -34,7 +34,7 @@
#include <nuttx/spi/spi.h>
#include <px4_platform_common/px4_manifest.h>
// 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
}
},
};

View File

@ -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

View File

@ -34,7 +34,7 @@
#include <nuttx/spi/spi.h>
#include <px4_platform_common/px4_manifest.h>
// 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
}
},
};

@ -1 +1 @@
Subproject commit 35997053c5f61039e542c01440feb10baba5049d
Subproject commit 43d5a11778ef7a589fe7e89ae77e78d7f494b615

View File

@ -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
}
},
};