Compare commits

...

1 Commits

Author SHA1 Message Date
Daniel Agar 7667b3a782 boards: use littlefs for parameter storage
Co-authored-by: Igor Mišić <igy1000mb@gmail.com>
Co-authored-by: Daniel Agar <daniel@agar.ca>
2023-09-20 19:13:54 -04:00
73 changed files with 528 additions and 54 deletions

View File

@ -684,7 +684,7 @@ void checkStatus() {
sh './Tools/HIL/run_nsh_cmd.py --device `find /dev/serial -name *usb-*` --cmd "param save"'
sh './Tools/HIL/run_nsh_cmd.py --device `find /dev/serial -name *usb-*` --cmd "param status"'
sh './Tools/HIL/run_nsh_cmd.py --device `find /dev/serial -name *usb-*` --cmd "param show SYS*"'
sh './Tools/HIL/run_nsh_cmd.py --device `find /dev/serial -name *usb-*` --cmd "bsondump /fs/mtd_params"'
sh './Tools/HIL/run_nsh_cmd.py --device `find /dev/serial -name *usb-*` --cmd "bsondump /fs/mtd_params/parameters.bson"'
// status commands
sh './Tools/HIL/run_nsh_cmd.py --device `find /dev/serial -name *usb-*` --cmd "cat /proc/fs/blocks"'
@ -715,7 +715,7 @@ void checkStatus() {
sh './Tools/HIL/run_nsh_cmd.py --device `find /dev/serial -name *usb-*` --cmd "mavlink status" || true'
sh './Tools/HIL/run_nsh_cmd.py --device `find /dev/serial -name *usb-*` --cmd "mount"'
sh './Tools/HIL/run_nsh_cmd.py --device `find /dev/serial -name *usb-*` --cmd "mtd status"'
sh './Tools/HIL/run_nsh_cmd.py --device `find /dev/serial -name *usb-*` --cmd "bsondump /fs/mtd_params"'
sh './Tools/HIL/run_nsh_cmd.py --device `find /dev/serial -name *usb-*` --cmd "bsondump /fs/mtd_params/parameters.bson"'
sh './Tools/HIL/run_nsh_cmd.py --device `find /dev/serial -name *usb-*` --cmd "param show" || true'
sh './Tools/HIL/run_nsh_cmd.py --device `find /dev/serial -name *usb-*` --cmd "param status"'
sh './Tools/HIL/run_nsh_cmd.py --device `find /dev/serial -name *usb-*` --cmd "perf latency"'
@ -769,13 +769,7 @@ void runTests() {
sh './Tools/HIL/run_nsh_cmd.py --device `find /dev/serial -name *usb-*` --cmd "tests file" || true'
sh './Tools/HIL/run_nsh_cmd.py --device `find /dev/serial -name *usb-*` --cmd "bsondump /fs/mtd_params"'
sh './Tools/HIL/run_nsh_cmd.py --device `find /dev/serial -name *usb-*` --cmd "mtd readtest"'
sh './Tools/HIL/run_nsh_cmd.py --device `find /dev/serial -name *usb-*` --cmd "bsondump /fs/mtd_params"'
sh './Tools/HIL/run_nsh_cmd.py --device `find /dev/serial -name *usb-*` --cmd "mtd rwtest"'
sh './Tools/HIL/run_nsh_cmd.py --device `find /dev/serial -name *usb-*` --cmd "bsondump /fs/mtd_params"'
sh './Tools/HIL/run_nsh_cmd.py --device `find /dev/serial -name *usb-*` --cmd "mtd erase"'
sh './Tools/HIL/run_nsh_cmd.py --device `find /dev/serial -name *usb-*` --cmd "bsondump /fs/mtd_params" || true' // expected to fail after erase
sh './Tools/HIL/run_nsh_cmd.py --device `find /dev/serial -name *usb-*` --cmd "bsondump /fs/mtd_params/parameters.bson"'
sh './Tools/HIL/run_nsh_cmd.py --device `find /dev/serial -name *usb-*` --cmd "sd_bench"'
sh './Tools/HIL/run_nsh_cmd.py --device `find /dev/serial -name *usb-*` --cmd "sd_bench -v"'

View File

@ -112,7 +112,21 @@ else
#
if mft query -q -k MTD -s MTD_PARAMETERS -v /fs/mtd_params
then
set PARAM_FILE /fs/mtd_params
set PARAM_FILE /fs/mtd_params/parameters.bson
else
# TODO: This code shall be reverted after the BCH->LittleFS param transition time is completed
set PARAM_FILE /fs/mtd_params/parameters.bson
param select $PARAM_FILE
echo "Start parameter transition to LittleFS"
if ! param transition
then
echo "ERROR [init] param transition"
else
echo "The system will reboot!"
# Wait for UART to send messages
usleep 200000
reboot
fi
fi
#

View File

@ -43,13 +43,13 @@ do
${DIR}/run_nsh_cmd.py --device ${SERIAL_DEVICE} --cmd 'param reset SYS_HITL'
${DIR}/run_nsh_cmd.py --device ${SERIAL_DEVICE} --cmd 'param status'
${DIR}/run_nsh_cmd.py --device ${SERIAL_DEVICE} --cmd 'param save'
${DIR}/run_nsh_cmd.py --device ${SERIAL_DEVICE} --cmd 'bsondump /fs/mtd_params'
${DIR}/run_nsh_cmd.py --device ${SERIAL_DEVICE} --cmd 'bsondump /fs/mtd_params/parameters.bson'
${DIR}/reboot.py --device ${SERIAL_DEVICE}
${DIR}/run_nsh_cmd.py --device ${SERIAL_DEVICE} --cmd 'param status'
${DIR}/run_nsh_cmd.py --device ${SERIAL_DEVICE} --cmd 'bsondump /fs/mtd_params' || true
${DIR}/run_nsh_cmd.py --device ${SERIAL_DEVICE} --cmd 'bsondump /fs/microsd/parameters_backup.bson' || true
${DIR}/run_nsh_cmd.py --device ${SERIAL_DEVICE} --cmd 'bsondump /fs/mtd_params/parameters.bson'
${DIR}/run_nsh_cmd.py --device ${SERIAL_DEVICE} --cmd 'bsondump /fs/microsd/parameters_backup.bson'
${DIR}/run_nsh_cmd.py --device ${SERIAL_DEVICE} --cmd 'ps'
${DIR}/run_nsh_cmd.py --device ${SERIAL_DEVICE} --cmd 'work_queue status'

View File

@ -94,6 +94,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=4
CONFIG_FS_LITTLEFS_LOOKAHEAD_SIZE=128
CONFIG_FS_LITTLEFS_PROGRAM_SIZE_FACTOR=1
CONFIG_FS_PROCFS=y
CONFIG_FS_PROCFS_INCLUDE_PROGMEM=y
CONFIG_FS_PROCFS_REGISTER=y

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=4
CONFIG_FS_LITTLEFS_LOOKAHEAD_SIZE=128
CONFIG_FS_LITTLEFS_PROGRAM_SIZE_FACTOR=1
CONFIG_FS_PROCFS=y
CONFIG_FS_PROCFS_INCLUDE_PROGMEM=y
CONFIG_FS_PROCFS_MAX_TASKS=64

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=4
CONFIG_FS_LITTLEFS_LOOKAHEAD_SIZE=128
CONFIG_FS_LITTLEFS_PROGRAM_SIZE_FACTOR=1
CONFIG_FS_PROCFS=y
CONFIG_FS_PROCFS_INCLUDE_PROGMEM=y
CONFIG_FS_PROCFS_MAX_TASKS=64

View File

@ -94,6 +94,7 @@ CONFIG_FS_BINFS=y
CONFIG_FS_CROMFS=y
CONFIG_FS_FAT=y
CONFIG_FS_FATTIME=y
CONFIG_FS_LITTLEFS=y
CONFIG_FS_PROCFS=y
CONFIG_FS_PROCFS_INCLUDE_PROGMEM=y
CONFIG_FS_PROCFS_REGISTER=y

View File

@ -47,7 +47,7 @@ static const px4_mtd_entry_t fmu_eeprom = {
{
.type = MTD_PARAMETERS,
.path = "/fs/mtd_params",
.nblocks = 128
.nblocks = 256
}
},
};

View File

@ -73,8 +73,8 @@ CONFIG_CDCACM=y
CONFIG_CDCACM_IFLOWCONTROL=y
CONFIG_CDCACM_PRODUCTID=0x0016
CONFIG_CDCACM_PRODUCTSTR="PX4 Crazyflie v2.0"
CONFIG_CDCACM_RXBUFSIZE=300
CONFIG_CDCACM_TXBUFSIZE=1000
CONFIG_CDCACM_RXBUFSIZE=600
CONFIG_CDCACM_TXBUFSIZE=2000
CONFIG_CDCACM_VENDORID=0x26ac
CONFIG_CDCACM_VENDORSTR="Bitcraze AB"
CONFIG_DEBUG_FULLOPT=y
@ -93,11 +93,11 @@ CONFIG_FDCLONE_STDIO=y
CONFIG_FS_BINFS=y
CONFIG_FS_CROMFS=y
CONFIG_FS_FAT=y
CONFIG_FS_FATTIME=y
CONFIG_FS_LITTLEFS=y
CONFIG_FS_PROCFS=y
CONFIG_FS_PROCFS_EXCLUDE_BLOCKS=y
CONFIG_FS_PROCFS_EXCLUDE_MEMINFO=y
CONFIG_FS_PROCFS_EXCLUDE_MOUNT=y
CONFIG_FS_PROCFS_EXCLUDE_USAGE=y
CONFIG_FS_PROCFS_INCLUDE_PROGMEM=y
CONFIG_FS_PROCFS_REGISTER=y
CONFIG_FS_ROMFS=y
CONFIG_GRAN=y
CONFIG_GRAN_INTR=y

View File

@ -98,6 +98,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=4
CONFIG_FS_LITTLEFS_LOOKAHEAD_SIZE=128
CONFIG_FS_LITTLEFS_PROGRAM_SIZE_FACTOR=1
CONFIG_FS_PROCFS=y
CONFIG_FS_PROCFS_INCLUDE_PROGMEM=y
CONFIG_FS_PROCFS_MAX_TASKS=64

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=4
CONFIG_FS_LITTLEFS_LOOKAHEAD_SIZE=128
CONFIG_FS_LITTLEFS_PROGRAM_SIZE_FACTOR=1
CONFIG_FS_PROCFS=y
CONFIG_FS_PROCFS_INCLUDE_PROGMEM=y
CONFIG_FS_PROCFS_MAX_TASKS=64

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=4
CONFIG_FS_LITTLEFS_LOOKAHEAD_SIZE=128
CONFIG_FS_LITTLEFS_PROGRAM_SIZE_FACTOR=1
CONFIG_FS_PROCFS=y
CONFIG_FS_PROCFS_INCLUDE_PROGMEM=y
CONFIG_FS_PROCFS_MAX_TASKS=64

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=4
CONFIG_FS_LITTLEFS_LOOKAHEAD_SIZE=128
CONFIG_FS_LITTLEFS_PROGRAM_SIZE_FACTOR=1
CONFIG_FS_PROCFS=y
CONFIG_FS_PROCFS_INCLUDE_PROGMEM=y
CONFIG_FS_PROCFS_MAX_TASKS=64

View File

@ -100,6 +100,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=4
CONFIG_FS_LITTLEFS_LOOKAHEAD_SIZE=128
CONFIG_FS_LITTLEFS_PROGRAM_SIZE_FACTOR=1
CONFIG_FS_PROCFS=y
CONFIG_FS_PROCFS_INCLUDE_PROGMEM=y
CONFIG_FS_PROCFS_MAX_TASKS=64

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=4
CONFIG_FS_LITTLEFS_LOOKAHEAD_SIZE=128
CONFIG_FS_LITTLEFS_PROGRAM_SIZE_FACTOR=1
CONFIG_FS_PROCFS=y
CONFIG_FS_PROCFS_INCLUDE_PROGMEM=y
CONFIG_FS_PROCFS_MAX_TASKS=64

View File

@ -100,6 +100,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=4
CONFIG_FS_LITTLEFS_LOOKAHEAD_SIZE=128
CONFIG_FS_LITTLEFS_PROGRAM_SIZE_FACTOR=1
CONFIG_FS_PROCFS=y
CONFIG_FS_PROCFS_INCLUDE_PROGMEM=y
CONFIG_FS_PROCFS_MAX_TASKS=64

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=4
CONFIG_FS_LITTLEFS_LOOKAHEAD_SIZE=128
CONFIG_FS_LITTLEFS_PROGRAM_SIZE_FACTOR=1
CONFIG_FS_PROCFS=y
CONFIG_FS_PROCFS_INCLUDE_PROGMEM=y
CONFIG_FS_PROCFS_MAX_TASKS=64

View File

@ -100,6 +100,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=4
CONFIG_FS_LITTLEFS_LOOKAHEAD_SIZE=128
CONFIG_FS_LITTLEFS_PROGRAM_SIZE_FACTOR=1
CONFIG_FS_PROCFS=y
CONFIG_FS_PROCFS_INCLUDE_PROGMEM=y
CONFIG_FS_PROCFS_MAX_TASKS=64

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=4
CONFIG_FS_LITTLEFS_LOOKAHEAD_SIZE=128
CONFIG_FS_LITTLEFS_PROGRAM_SIZE_FACTOR=1
CONFIG_FS_PROCFS=y
CONFIG_FS_PROCFS_INCLUDE_PROGMEM=y
CONFIG_FS_PROCFS_MAX_TASKS=64

View File

@ -98,6 +98,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=4
CONFIG_FS_LITTLEFS_LOOKAHEAD_SIZE=128
CONFIG_FS_LITTLEFS_PROGRAM_SIZE_FACTOR=1
CONFIG_FS_PROCFS=y
CONFIG_FS_PROCFS_INCLUDE_PROGMEM=y
CONFIG_FS_PROCFS_MAX_TASKS=64

View File

@ -59,9 +59,7 @@ CONFIG_MODULES_MC_POS_CONTROL=y
CONFIG_MODULES_MC_RATE_CONTROL=y
CONFIG_MODULES_NAVIGATOR=y
CONFIG_MODULES_RC_UPDATE=y
CONFIG_MODULES_ROVER_POS_CONTROL=y
CONFIG_MODULES_SENSORS=y
CONFIG_MODULES_SIMULATION_SIMULATOR_SIH=y
CONFIG_MODULES_TEMPERATURE_COMPENSATION=y
CONFIG_MODULES_UXRCE_DDS_CLIENT=y
CONFIG_MODULES_VTOL_ATT_CONTROL=y

View File

@ -100,6 +100,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=4
CONFIG_FS_LITTLEFS_LOOKAHEAD_SIZE=128
CONFIG_FS_LITTLEFS_PROGRAM_SIZE_FACTOR=1
CONFIG_FS_PROCFS=y
CONFIG_FS_PROCFS_INCLUDE_PROGMEM=y
CONFIG_FS_PROCFS_MAX_TASKS=64

View File

@ -100,6 +100,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=4
CONFIG_FS_LITTLEFS_LOOKAHEAD_SIZE=128
CONFIG_FS_LITTLEFS_PROGRAM_SIZE_FACTOR=1
CONFIG_FS_PROCFS=y
CONFIG_FS_PROCFS_INCLUDE_PROGMEM=y
CONFIG_FS_PROCFS_MAX_TASKS=64

View File

@ -98,6 +98,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=4
CONFIG_FS_LITTLEFS_LOOKAHEAD_SIZE=128
CONFIG_FS_LITTLEFS_PROGRAM_SIZE_FACTOR=1
CONFIG_FS_PROCFS=y
CONFIG_FS_PROCFS_INCLUDE_PROGMEM=y
CONFIG_FS_PROCFS_MAX_TASKS=64

View File

@ -98,6 +98,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=4
CONFIG_FS_LITTLEFS_LOOKAHEAD_SIZE=128
CONFIG_FS_LITTLEFS_PROGRAM_SIZE_FACTOR=1
CONFIG_FS_PROCFS=y
CONFIG_FS_PROCFS_INCLUDE_PROGMEM=y
CONFIG_FS_PROCFS_MAX_TASKS=64

View File

@ -98,6 +98,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=4
CONFIG_FS_LITTLEFS_LOOKAHEAD_SIZE=128
CONFIG_FS_LITTLEFS_PROGRAM_SIZE_FACTOR=1
CONFIG_FS_PROCFS=y
CONFIG_FS_PROCFS_INCLUDE_PROGMEM=y
CONFIG_FS_PROCFS_MAX_TASKS=64

View File

@ -98,6 +98,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=4
CONFIG_FS_LITTLEFS_LOOKAHEAD_SIZE=128
CONFIG_FS_LITTLEFS_PROGRAM_SIZE_FACTOR=1
CONFIG_FS_PROCFS=y
CONFIG_FS_PROCFS_INCLUDE_PROGMEM=y
CONFIG_FS_PROCFS_MAX_TASKS=64

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=4
CONFIG_FS_LITTLEFS_LOOKAHEAD_SIZE=128
CONFIG_FS_LITTLEFS_PROGRAM_SIZE_FACTOR=1
CONFIG_FS_PROCFS=y
CONFIG_FS_PROCFS_INCLUDE_PROGMEM=y
CONFIG_FS_PROCFS_MAX_TASKS=64

View File

@ -98,6 +98,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=4
CONFIG_FS_LITTLEFS_LOOKAHEAD_SIZE=128
CONFIG_FS_LITTLEFS_PROGRAM_SIZE_FACTOR=1
CONFIG_FS_PROCFS=y
CONFIG_FS_PROCFS_INCLUDE_PROGMEM=y
CONFIG_FS_PROCFS_MAX_TASKS=64

View File

@ -95,6 +95,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=4
CONFIG_FS_LITTLEFS_LOOKAHEAD_SIZE=128
CONFIG_FS_LITTLEFS_PROGRAM_SIZE_FACTOR=1
CONFIG_FS_PROCFS=y
CONFIG_FS_PROCFS_INCLUDE_PROGMEM=y
CONFIG_FS_PROCFS_REGISTER=y

View File

@ -51,6 +51,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=4
CONFIG_FS_LITTLEFS_LOOKAHEAD_SIZE=128
CONFIG_FS_LITTLEFS_PROGRAM_SIZE_FACTOR=1
CONFIG_FS_PROCFS=y
CONFIG_FS_PROCFS_REGISTER=y
CONFIG_FS_ROMFS=y

View File

@ -52,6 +52,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=4
CONFIG_FS_LITTLEFS_LOOKAHEAD_SIZE=128
CONFIG_FS_LITTLEFS_PROGRAM_SIZE_FACTOR=1
CONFIG_FS_PROCFS=y
CONFIG_FS_PROCFS_REGISTER=y
CONFIG_FS_ROMFS=y

View File

@ -55,6 +55,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=4
CONFIG_FS_LITTLEFS_LOOKAHEAD_SIZE=128
CONFIG_FS_LITTLEFS_PROGRAM_SIZE_FACTOR=1
CONFIG_FS_PROCFS=y
CONFIG_FS_PROCFS_REGISTER=y
CONFIG_FS_ROMFS=y

View File

@ -53,6 +53,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=4
CONFIG_FS_LITTLEFS_LOOKAHEAD_SIZE=128
CONFIG_FS_LITTLEFS_PROGRAM_SIZE_FACTOR=1
CONFIG_FS_PROCFS=y
CONFIG_FS_PROCFS_REGISTER=y
CONFIG_FS_ROMFS=y

View File

@ -53,6 +53,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=4
CONFIG_FS_LITTLEFS_LOOKAHEAD_SIZE=128
CONFIG_FS_LITTLEFS_PROGRAM_SIZE_FACTOR=1
CONFIG_FS_PROCFS=y
CONFIG_FS_PROCFS_REGISTER=y
CONFIG_FS_ROMFS=y

View File

@ -58,6 +58,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=4
CONFIG_FS_LITTLEFS_LOOKAHEAD_SIZE=128
CONFIG_FS_LITTLEFS_PROGRAM_SIZE_FACTOR=1
CONFIG_FS_PROCFS=y
CONFIG_FS_PROCFS_REGISTER=y
CONFIG_FS_ROMFS=y

View File

@ -96,7 +96,6 @@ CONFIG_FSUTILS_IPCFG=y
CONFIG_FS_CROMFS=y
CONFIG_FS_FAT=y
CONFIG_FS_FATTIME=y
CONFIG_FS_LITTLEFS=y
CONFIG_FS_PROCFS=y
CONFIG_FS_PROCFS_MAX_TASKS=64
CONFIG_FS_PROCFS_REGISTER=y

View File

@ -97,7 +97,6 @@ CONFIG_FSUTILS_IPCFG=y
CONFIG_FS_CROMFS=y
CONFIG_FS_FAT=y
CONFIG_FS_FATTIME=y
CONFIG_FS_LITTLEFS=y
CONFIG_FS_PROCFS=y
CONFIG_FS_PROCFS_MAX_TASKS=64
CONFIG_FS_PROCFS_REGISTER=y

View File

@ -34,6 +34,7 @@ CONFIG_DEBUG_TCBINFO=y
CONFIG_DISABLE_MQUEUE=y
CONFIG_DISABLE_POSIX_TIMERS=y
CONFIG_EXAMPLES_HELLO=y
CONFIG_FS_LITTLEFS=y
CONFIG_FS_CROMFS=y
CONFIG_FS_PROCFS=y
CONFIG_FS_PROCFS_MAX_TASKS=16

View File

@ -94,6 +94,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=4
CONFIG_FS_LITTLEFS_LOOKAHEAD_SIZE=128
CONFIG_FS_LITTLEFS_PROGRAM_SIZE_FACTOR=1
CONFIG_FS_ROMFS=y
CONFIG_GRAN=y
CONFIG_GRAN_INTR=y

View File

@ -96,6 +96,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=4
CONFIG_FS_LITTLEFS_LOOKAHEAD_SIZE=128
CONFIG_FS_LITTLEFS_PROGRAM_SIZE_FACTOR=1
CONFIG_FS_PROCFS=y
CONFIG_FS_PROCFS_INCLUDE_PROGMEM=y
CONFIG_FS_PROCFS_REGISTER=y

View File

@ -95,6 +95,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=4
CONFIG_FS_LITTLEFS_LOOKAHEAD_SIZE=128
CONFIG_FS_LITTLEFS_PROGRAM_SIZE_FACTOR=1
CONFIG_FS_PROCFS=y
CONFIG_FS_PROCFS_INCLUDE_PROGMEM=y
CONFIG_FS_PROCFS_REGISTER=y

View File

@ -96,6 +96,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=4
CONFIG_FS_LITTLEFS_LOOKAHEAD_SIZE=128
CONFIG_FS_LITTLEFS_PROGRAM_SIZE_FACTOR=1
CONFIG_FS_PROCFS=y
CONFIG_FS_PROCFS_INCLUDE_PROGMEM=y
CONFIG_FS_PROCFS_REGISTER=y

View File

@ -50,7 +50,6 @@ CONFIG_MODULES_FW_POS_CONTROL=y
CONFIG_MODULES_FW_RATE_CONTROL=y
CONFIG_MODULES_GIMBAL=y
CONFIG_MODULES_GYRO_CALIBRATION=y
CONFIG_MODULES_GYRO_FFT=y
CONFIG_MODULES_LAND_DETECTOR=y
CONFIG_MODULES_LANDING_TARGET_ESTIMATOR=y
CONFIG_MODULES_LOAD_MON=y

View File

@ -95,6 +95,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=4
CONFIG_FS_LITTLEFS_LOOKAHEAD_SIZE=128
CONFIG_FS_LITTLEFS_PROGRAM_SIZE_FACTOR=1
CONFIG_FS_PROCFS=y
CONFIG_FS_PROCFS_INCLUDE_PROGMEM=y
CONFIG_FS_PROCFS_REGISTER=y

View File

@ -96,6 +96,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=4
CONFIG_FS_LITTLEFS_LOOKAHEAD_SIZE=128
CONFIG_FS_LITTLEFS_PROGRAM_SIZE_FACTOR=1
CONFIG_FS_PROCFS=y
CONFIG_FS_PROCFS_INCLUDE_PROGMEM=y
CONFIG_FS_PROCFS_REGISTER=y

View File

@ -3,8 +3,9 @@ CONFIG_DRIVERS_IMU_ANALOG_DEVICES_ADIS16448=n
CONFIG_DRIVERS_IRLOCK=n
CONFIG_DRIVERS_PCA9685_PWM_OUT=n
CONFIG_MODULES_ATTITUDE_ESTIMATOR_Q=n
CONFIG_MODULES_GYRO_FFT=n
CONFIG_MODULES_LOCAL_POSITION_ESTIMATOR=n
CONFIG_MODULES_UUV_ATT_CONTROL=n
CONFIG_MODULES_UUV_POS_CONTROL=n
CONFIG_BOARD_TESTING=y
CONFIG_DRIVERS_TEST_PPM=y
CONFIG_SYSTEMCMDS_MICROBENCH=y

View File

@ -100,6 +100,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=4
CONFIG_FS_LITTLEFS_LOOKAHEAD_SIZE=128
CONFIG_FS_LITTLEFS_PROGRAM_SIZE_FACTOR=1
CONFIG_FS_PROCFS=y
CONFIG_FS_PROCFS_INCLUDE_PROGMEM=y
CONFIG_FS_PROCFS_MAX_TASKS=64

View File

@ -100,6 +100,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=4
CONFIG_FS_LITTLEFS_LOOKAHEAD_SIZE=128
CONFIG_FS_LITTLEFS_PROGRAM_SIZE_FACTOR=1
CONFIG_FS_PROCFS=y
CONFIG_FS_PROCFS_INCLUDE_PROGMEM=y
CONFIG_FS_PROCFS_MAX_TASKS=64

View File

@ -144,6 +144,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=4
CONFIG_FS_LITTLEFS_LOOKAHEAD_SIZE=128
CONFIG_FS_LITTLEFS_PROGRAM_SIZE_FACTOR=1
CONFIG_FS_PROCFS=y
CONFIG_FS_PROCFS_INCLUDE_PROGMEM=y
CONFIG_FS_PROCFS_MAX_TASKS=64

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=4
CONFIG_FS_LITTLEFS_LOOKAHEAD_SIZE=128
CONFIG_FS_LITTLEFS_PROGRAM_SIZE_FACTOR=1
CONFIG_FS_PROCFS=y
CONFIG_FS_PROCFS_INCLUDE_PROGMEM=y
CONFIG_FS_PROCFS_MAX_TASKS=64

View File

@ -102,6 +102,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=4
CONFIG_FS_LITTLEFS_LOOKAHEAD_SIZE=128
CONFIG_FS_LITTLEFS_PROGRAM_SIZE_FACTOR=1
CONFIG_FS_PROCFS=y
CONFIG_FS_PROCFS_INCLUDE_PROGMEM=y
CONFIG_FS_PROCFS_MAX_TASKS=64

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=4
CONFIG_FS_LITTLEFS_LOOKAHEAD_SIZE=128
CONFIG_FS_LITTLEFS_PROGRAM_SIZE_FACTOR=1
CONFIG_FS_PROCFS=y
CONFIG_FS_PROCFS_INCLUDE_PROGMEM=y
CONFIG_FS_PROCFS_MAX_TASKS=64

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=4
CONFIG_FS_LITTLEFS_LOOKAHEAD_SIZE=128
CONFIG_FS_LITTLEFS_PROGRAM_SIZE_FACTOR=1
CONFIG_FS_PROCFS=y
CONFIG_FS_PROCFS_INCLUDE_PROGMEM=y
CONFIG_FS_PROCFS_MAX_TASKS=64

View File

@ -3,6 +3,9 @@ CONFIG_COMMON_BAROMETERS=n
CONFIG_COMMON_DIFFERENTIAL_PRESSURE=n
CONFIG_COMMON_DISTANCE_SENSOR=n
CONFIG_COMMON_HYGROMETERS=n
CONFIG_COMMON_MAGNETOMETER=n
CONFIG_COMMON_OPTICAL_FLOW=n
CONFIG_COMMON_OSD=n
CONFIG_COMMON_TELEMETRY=n
CONFIG_DRIVERS_ADC_ADS1115=n
CONFIG_DRIVERS_BATT_SMBUS=n
@ -23,12 +26,15 @@ CONFIG_EXAMPLES_FAKE_GPS=n
CONFIG_MODULES_ATTITUDE_ESTIMATOR_Q=n
CONFIG_MODULES_CAMERA_FEEDBACK=n
CONFIG_MODULES_ESC_BATTERY=n
CONFIG_MODULES_EVENTS=n
CONFIG_MODULES_FW_AUTOTUNE_ATTITUDE_CONTROL=n
CONFIG_MODULES_GIMBAL=n
CONFIG_MODULES_GYRO_CALIBRATION=n
CONFIG_MODULES_LANDING_TARGET_ESTIMATOR=n
CONFIG_MODULES_LOCAL_POSITION_ESTIMATOR=n
CONFIG_MODULES_MAG_BIAS_ESTIMATOR=n
CONFIG_MODULES_MC_AUTOTUNE_ATTITUDE_CONTROL=n
CONFIG_MODULES_MC_HOVER_THRUST_ESTIMATOR=n
CONFIG_MODULES_ROVER_POS_CONTROL=n
CONFIG_MODULES_SIMULATION_SIMULATOR_SIH=n
CONFIG_MODULES_TEMPERATURE_COMPENSATION=n
@ -38,3 +44,8 @@ CONFIG_SYSTEMCMDS_REFLECT=n
CONFIG_BOARD_CONSTRAINED_FLASH=y
CONFIG_BOARD_TESTING=y
CONFIG_DRIVERS_BAROMETER_MS5611=y
CONFIG_DRIVERS_MAGNETOMETER_AKM_AK09916=y
CONFIG_DRIVERS_MAGNETOMETER_AKM_AK8963=y
CONFIG_DRIVERS_MAGNETOMETER_BOSCH_BMM150=y
CONFIG_DRIVERS_MAGNETOMETER_ISENTEK_IST8308=y
CONFIG_DRIVERS_MAGNETOMETER_ISENTEK_IST8310=y

View File

@ -104,6 +104,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=4
CONFIG_FS_LITTLEFS_LOOKAHEAD_SIZE=128
CONFIG_FS_LITTLEFS_PROGRAM_SIZE_FACTOR=1
CONFIG_FS_PROCFS=y
CONFIG_FS_PROCFS_INCLUDE_PROGMEM=y
CONFIG_FS_PROCFS_MAX_TASKS=64

View File

@ -103,6 +103,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=4
CONFIG_FS_LITTLEFS_LOOKAHEAD_SIZE=128
CONFIG_FS_LITTLEFS_PROGRAM_SIZE_FACTOR=1
CONFIG_FS_PROCFS=y
CONFIG_FS_PROCFS_INCLUDE_PROGMEM=y
CONFIG_FS_PROCFS_MAX_TASKS=64

View File

@ -61,9 +61,7 @@ CONFIG_MODULES_MC_POS_CONTROL=y
CONFIG_MODULES_MC_RATE_CONTROL=y
CONFIG_MODULES_NAVIGATOR=y
CONFIG_MODULES_RC_UPDATE=y
CONFIG_MODULES_ROVER_POS_CONTROL=y
CONFIG_MODULES_SENSORS=y
CONFIG_MODULES_SIMULATION_SIMULATOR_SIH=y
CONFIG_MODULES_TEMPERATURE_COMPENSATION=y
CONFIG_MODULES_UXRCE_DDS_CLIENT=y
CONFIG_MODULES_VTOL_ATT_CONTROL=y

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=4
CONFIG_FS_LITTLEFS_LOOKAHEAD_SIZE=128
CONFIG_FS_LITTLEFS_PROGRAM_SIZE_FACTOR=1
CONFIG_FS_PROCFS=y
CONFIG_FS_PROCFS_INCLUDE_PROGMEM=y
CONFIG_FS_PROCFS_MAX_TASKS=64

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=4
CONFIG_FS_LITTLEFS_LOOKAHEAD_SIZE=128
CONFIG_FS_LITTLEFS_PROGRAM_SIZE_FACTOR=1
CONFIG_FS_PROCFS=y
CONFIG_FS_PROCFS_INCLUDE_PROGMEM=y
CONFIG_FS_PROCFS_MAX_TASKS=64

View File

@ -28,8 +28,6 @@ CONFIG_DRIVERS_IMU_INVENSENSE_ICM42688P=y
CONFIG_COMMON_INS=y
CONFIG_COMMON_LIGHT=y
CONFIG_COMMON_MAGNETOMETER=y
CONFIG_COMMON_OPTICAL_FLOW=y
CONFIG_COMMON_OSD=y
CONFIG_DRIVERS_POWER_MONITOR_INA226=y
CONFIG_DRIVERS_POWER_MONITOR_INA228=y
CONFIG_DRIVERS_POWER_MONITOR_INA238=y

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=4
CONFIG_FS_LITTLEFS_LOOKAHEAD_SIZE=128
CONFIG_FS_LITTLEFS_PROGRAM_SIZE_FACTOR=1
CONFIG_FS_PROCFS=y
CONFIG_FS_PROCFS_INCLUDE_PROGMEM=y
CONFIG_FS_PROCFS_MAX_TASKS=64

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=4
CONFIG_FS_LITTLEFS_LOOKAHEAD_SIZE=128
CONFIG_FS_LITTLEFS_PROGRAM_SIZE_FACTOR=1
CONFIG_FS_PROCFS=y
CONFIG_FS_PROCFS_INCLUDE_PROGMEM=y
CONFIG_FS_PROCFS_MAX_TASKS=64

View File

@ -102,6 +102,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=4
CONFIG_FS_LITTLEFS_LOOKAHEAD_SIZE=128
CONFIG_FS_LITTLEFS_PROGRAM_SIZE_FACTOR=1
CONFIG_FS_PROCFS=y
CONFIG_FS_PROCFS_INCLUDE_PROGMEM=y
CONFIG_FS_PROCFS_MAX_TASKS=64

View File

@ -96,6 +96,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=4
CONFIG_FS_LITTLEFS_LOOKAHEAD_SIZE=128
CONFIG_FS_LITTLEFS_PROGRAM_SIZE_FACTOR=1
CONFIG_FS_PROCFS=y
CONFIG_FS_PROCFS_INCLUDE_PROGMEM=y
CONFIG_FS_PROCFS_REGISTER=y

View File

@ -96,6 +96,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=4
CONFIG_FS_LITTLEFS_LOOKAHEAD_SIZE=128
CONFIG_FS_LITTLEFS_PROGRAM_SIZE_FACTOR=1
CONFIG_FS_PROCFS=y
CONFIG_FS_PROCFS_INCLUDE_PROGMEM=y
CONFIG_FS_PROCFS_REGISTER=y

View File

@ -94,6 +94,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=4
CONFIG_FS_LITTLEFS_LOOKAHEAD_SIZE=128
CONFIG_FS_LITTLEFS_PROGRAM_SIZE_FACTOR=1
CONFIG_FS_PROCFS=y
CONFIG_FS_PROCFS_INCLUDE_PROGMEM=y
CONFIG_FS_PROCFS_REGISTER=y

View File

@ -77,6 +77,24 @@ __EXPORT int px4_mtd_get_geometry(const mtd_instance_s *instance, unsigned long
*/
__EXPORT ssize_t px4_mtd_get_partition_size(const mtd_instance_s *instance, const char *partname);
/*
Helper function for transition to LittleFS.
It will unmount MTD for parameters with LittleFS and mount Block Device
*/
__EXPORT int px4_mtd_unmount_littlefs_mount_block_device(void);
/*
Helper function for transition to LittleFS.
It will unmount MTD for parameters with Block Device and mount LittleFS with force formatting
*/
__EXPORT int px4_mtd_unmount_block_device_mount_littlefs(void);
/*
Helper function for transition to LittleFS.
It will force formatting to LittleFS
*/
__EXPORT int px4_mtd_forceformat_littlefs(void);
int px4_at24c_initialize(FAR struct i2c_master_s *dev,
uint8_t address, FAR struct mtd_dev_s **mtd_dev);

View File

@ -89,7 +89,7 @@ static constexpr wq_config_t ttyS9{"wq:ttyS9", 1728, -30};
static constexpr wq_config_t ttyACM0{"wq:ttyACM0", 1728, -31};
static constexpr wq_config_t ttyUnknown{"wq:ttyUnknown", 1728, -32};
static constexpr wq_config_t lp_default{"wq:lp_default", 1920, -50};
static constexpr wq_config_t lp_default{"wq:lp_default", 2048, -50};
static constexpr wq_config_t test1{"wq:test1", 2000, 0};
static constexpr wq_config_t test2{"wq:test2", 2000, 0};

View File

@ -76,9 +76,12 @@ __EXPORT int px4_mft_configure(const px4_mft_s *mft)
if (mft != nullptr) {
for (uint32_t m = 0; m < mft->nmft; m++) {
switch (mft->mfts[m]->type) {
#if defined(CONFIG_MTD)
case MTD:
px4_mtd_config(static_cast<const px4_mtd_manifest_t *>(mft->mfts[m]->pmft));
break;
#endif // CONFIG_MTD
case MFT:
default:
@ -99,9 +102,12 @@ __EXPORT int px4_mft_query(const px4_mft_s *mft, px4_manifest_types_e type,
for (uint32_t m = 0; m < mft->nmft; m++) {
if (mft->mfts[m]->type == type)
switch (type) {
#if defined(CONFIG_MTD)
case MTD:
return px4_mtd_query(sub, val, nullptr);
break;
#endif // CONFIG_MTD
case MFT:
default:

View File

@ -39,6 +39,8 @@
* @author David Sidrane <david.sidrane@nscdg.com>
*/
#if defined(CONFIG_MTD)
#ifndef MODULE_NAME
#define MODULE_NAME "PX4_MTD"
#endif
@ -57,6 +59,7 @@
#include <nuttx/drivers/drivers.h>
#include <nuttx/spi/spi.h>
#include <nuttx/mtd/mtd.h>
#include <nuttx/fs/fs.h>
extern "C" {
struct mtd_dev_s *ramtron_initialize(FAR struct spi_dev_s *dev);
@ -67,6 +70,9 @@ static int num_instances = 0;
static int total_blocks = 0;
static mtd_instance_s *instances[MAX_MTD_INSTANCES] = {};
static int8_t param_instance = -1;
static int8_t param_part = -1;
static int8_t param_block = -1;
static int ramtron_attach(mtd_instance_s &instance)
{
@ -118,15 +124,6 @@ static int ramtron_attach(mtd_instance_s &instance)
return -EIO;
}
int ret = instance.mtd_dev->ioctl(instance.mtd_dev, MTDIOC_SETSPEED, (unsigned long)spi_speed_mhz * 1000 * 1000);
if (ret != OK) {
// FIXME: From the previous warning call, it looked like this should have been fatal error instead. Tried
// that but setting the bus speed does fail all the time. Which was then exiting and the board would
// not run correctly. So changed to PX4_WARN.
PX4_WARN("failed to set bus speed");
}
return 0;
#endif
}
@ -395,27 +392,54 @@ memoryout:
}
/* Initialize to provide an FTL block driver on the MTD FLASH interface */
snprintf(blockname, sizeof(blockname), "/dev/mtdblock%d", total_blocks);
rv = ftl_initialize(total_blocks, instances[i]->part_dev[part]);
printf("blockname: %s, type: %d, name: %s\n", blockname, instances[i]->partition_types[part],
instances[i]->partition_names[part]);
if (rv < 0) {
PX4_ERR("ftl_initialize %s failed: %d", blockname, rv);
goto errout;
if (instances[i]->partition_types[part] == MTD_PARAMETERS) {
param_instance = i;
param_part = part;
param_block = total_blocks;
rv = register_mtddriver(blockname, instances[i]->part_dev[part], 0755, nullptr);
if (rv < 0) {
PX4_ERR("register_mtddriver %s failed: %d", blockname, rv);
goto errout;
}
// Now create a character device on the block device
//TODO: after the transition period return "autoformat"
rv = nx_mount(blockname, instances[i]->partition_names[part], "littlefs", 0, "");
printf("nx_mount: blockname: %s partition: %s\n", blockname, instances[i]->partition_names[part]);
if (rv < 0) {
PX4_ERR("nx_mount %s failed: %d", instances[i]->partition_names[part], rv);
goto errout;
}
} else {
rv = ftl_initialize(total_blocks, instances[i]->part_dev[part]);
if (rv < 0) {
PX4_ERR("ftl_initialize %s failed: %d", blockname, rv);
goto errout;
}
/* Now create a character device on the block device */
rv = bchdev_register(blockname, instances[i]->partition_names[part], false);
if (rv < 0) {
PX4_ERR("bchdev_register %s failed: %d", instances[i]->partition_names[part], rv);
goto errout;
}
}
total_blocks++;
/* Now create a character device on the block device */
rv = bchdev_register(blockname, instances[i]->partition_names[part], false);
if (rv < 0) {
PX4_ERR("bchdev_register %s failed: %d", instances[i]->partition_names[part], rv);
goto errout;
}
instances[i]->n_partitions_current++;
}
@ -474,3 +498,97 @@ __EXPORT int px4_mtd_query(const char *sub, const char *val, const char **get)
return rv;
}
int px4_mtd_unmount_littlefs_mount_block_device(void)
{
if ((param_instance == -1) || (param_part == -1) || (param_block == -1)) {
PX4_ERR("MTD_PARAMETERS never initialized");
return -1;
}
char blockname[32];
snprintf(blockname, sizeof(blockname), "/dev/mtdblock%d", param_block);
// in case LittleFS is mounted, unmount it
nx_umount2(instances[param_instance]->partition_names[param_part], 0);
unregister_mtddriver(blockname);
int ret = ftl_initialize(0, instances[param_instance]->part_dev[param_part]);
if (ret < 0) {
PX4_ERR("ftl_initialize failed with error %d, param_block %d, param_instance %d, param_part %d, block_counts %d",
ret, param_block, param_instance, param_part, *instances[param_instance]->partition_block_counts);
} else {
ret = bchdev_register(blockname, instances[param_instance]->partition_names[param_part], false);
if (ret < 0) {
PX4_ERR("bchdev_register failed: %d", ret);
}
}
return ret;
}
int px4_mtd_unmount_block_device_mount_littlefs(void)
{
if ((param_instance == -1) || (param_part == -1) || (param_block == -1)) {
PX4_ERR("MTD_PARAMETERS never initialized");
return -1;
}
char blockname[32];
snprintf(blockname, sizeof(blockname), "/dev/mtdblock%d", param_block);
int ret = bchdev_unregister(instances[param_instance]->partition_names[param_part]);
if (ret < 0) {
PX4_ERR("bchdev_unregister %s failed: %d", instances[param_instance]->partition_names[param_part], ret);
} else {
ret = unregister_blockdriver(blockname);
if (ret < 0) {
PX4_ERR("unregister_blockdriver %s failed: %d", blockname, ret);
} else {
ret = px4_mtd_forceformat_littlefs();
}
}
return ret;
}
int px4_mtd_forceformat_littlefs(void)
{
if ((param_instance == -1) || (param_part == -1) || (param_block == -1)) {
PX4_ERR("MTD_PARAMETERS never initialized");
return -1;
}
char blockname[32];
snprintf(blockname, sizeof(blockname), "/dev/mtdblock%d", param_block);
// in case bchdev is register
bchdev_unregister(instances[param_instance]->partition_names[param_part]);
unregister_blockdriver(blockname);
int ret = register_mtddriver(blockname, instances[param_instance]->part_dev[param_part], 0755, nullptr);
if (ret < 0) {
PX4_ERR("register_mtddriver %s failed: %d", blockname, ret);
} else {
ret = nx_mount(blockname, instances[param_instance]->partition_names[param_part], "littlefs", 0, "forceformat");
if (ret < 0) {
PX4_ERR("nx_mount %s failed: %d", instances[param_instance]->partition_names[param_part], ret);
}
}
return ret;
}
#endif // CONFIG_MTD

View File

@ -35,6 +35,7 @@ px4_add_module(
MAIN param
COMPILE_FLAGS
-Wno-array-bounds
STACK_MAIN 4096
SRCS
param.cpp
DEPENDS

View File

@ -43,6 +43,7 @@
#include <px4_platform_common/log.h>
#include <px4_platform_common/module.h>
#include <px4_platform_common/posix.h>
#include <px4_platform_common/px4_mtd.h>
#include <float.h>
#include <errno.h>
@ -84,6 +85,7 @@ enum class COMPARE_ERROR_LEVEL {
static int do_save(const char *param_file_name);
static int do_save_default();
static int do_load(const char *param_file_name);
static int do_transition();
static int do_import(const char *param_file_name = nullptr);
static int do_show(const char *search_string, bool only_changed);
static int do_show_for_airframe();
@ -218,6 +220,11 @@ param_main(int argc, char *argv[])
}
}
// TODO: This code shall be reverted after the BCH->LittleFS param transition time is completed
if (!strcmp(argv[1], "transition")) {
return do_transition();
}
if (!strcmp(argv[1], "import")) {
if (argc >= 3) {
return do_import(argv[2]);
@ -466,6 +473,57 @@ do_load(const char *param_file_name)
return 0;
}
static int
do_transition()
{
#if defined(CONFIG_FS_LITTLEFS)
int ret_val = px4_mtd_unmount_littlefs_mount_block_device();
if (ret_val < 0) {
PX4_ERR("Transition from LittleFS to Blockdriver");
} else {
char param_path[] = "/fs/mtd_params";
PX4_INFO("Try path: %s", param_path);
ret_val = do_import(param_path);
if (ret_val == 1) {
PX4_WARN("Try path: %s", param_path);
char param_path_backup[] = "/fs/microsd/parameters_backup.bson";
ret_val = do_import(param_path_backup);
}
if (ret_val == 0) {
ret_val = px4_mtd_unmount_block_device_mount_littlefs();
if (ret_val < 0) {
PX4_ERR("Transition from Blockdriver to LittleFS failed");
} else {
PX4_INFO("Exporting params to LittleFS!");
ret_val = param_export(param_get_default_file(), nullptr);
if (ret_val == 0) {
PX4_INFO("Successful params transition!");
}
}
} else {
PX4_INFO("Params are unreadable from any known path. Format partition to LittleFS!");
ret_val = px4_mtd_forceformat_littlefs();
}
}
if (ret_val < 0) {
return 1;
}
#endif // CONFIG_FS_LITTLEFS
return 0;
}
static int
do_import(const char *param_file_name)
{