mirror of
https://gitee.com/mirrors_PX4/PX4-Autopilot.git
synced 2026-04-14 10:07:39 +08:00
rcS: fine-grained storage settings
This commit is contained in:
parent
0954e43708
commit
20cad48707
@ -193,6 +193,7 @@ endif()
|
||||
# board custom init files
|
||||
set(OPTIONAL_BOARD_RC)
|
||||
list(APPEND OPTIONAL_BOARD_RC
|
||||
rc.board_early
|
||||
rc.board_defaults
|
||||
rc.board_sensors
|
||||
rc.board_extras
|
||||
|
||||
@ -31,11 +31,20 @@ set PARAM_FILE ""
|
||||
set PARAM_BACKUP_FILE ""
|
||||
set RC_INPUT_ARGS ""
|
||||
set STORAGE_AVAILABLE no
|
||||
set STORAGE_CHECK yes
|
||||
set SDCARD_EXT_PATH /fs/microsd/ext_autostart
|
||||
set SDCARD_FORMAT no
|
||||
set STARTUP_TUNE 1
|
||||
set VEHICLE_TYPE none
|
||||
|
||||
# Fine-grained feature gates.
|
||||
set USE_HARDFAULT_LOG no
|
||||
set USE_EXTERNAL_AIRFRAMES no
|
||||
set USE_PARAM_BACKUPS no
|
||||
set USE_PARAM_IMPORT_DEBUG no
|
||||
set USE_TASK_WATCHDOG no
|
||||
set USE_ALT_UPDATE_DIRS no
|
||||
|
||||
# Airframe parameter versioning
|
||||
# Value set to 1 by default but can optionally be overridden in the airframe configuration startup script.
|
||||
# Airframe maintainers can ensure a reset to the airframe defaults during an update by increasing by one.
|
||||
@ -47,6 +56,22 @@ set PARAM_DEFAULTS_VER 1
|
||||
#
|
||||
ver all
|
||||
|
||||
#
|
||||
# Optional early board init: rc.board_early
|
||||
# Can be used for setting env vars for rcS.
|
||||
#
|
||||
set BOARD_RC_EARLY ${R}etc/init.d/rc.board_early
|
||||
if [ -f $BOARD_RC_EARLY ]
|
||||
then
|
||||
. $BOARD_RC_EARLY
|
||||
fi
|
||||
unset BOARD_RC_EARLY
|
||||
|
||||
#
|
||||
# Try to mount/check storage (rc.board_early can disable this).
|
||||
#
|
||||
if [ $STORAGE_CHECK = yes ]
|
||||
then
|
||||
#
|
||||
# Try to mount the microSD card.
|
||||
#
|
||||
@ -93,8 +118,20 @@ else
|
||||
set STORAGE_AVAILABLE yes
|
||||
fi
|
||||
fi
|
||||
fi
|
||||
|
||||
if [ $STORAGE_AVAILABLE = yes ]
|
||||
then
|
||||
set USE_HARDFAULT_LOG yes
|
||||
set USE_EXTERNAL_AIRFRAMES yes
|
||||
set USE_PARAM_BACKUPS yes
|
||||
set USE_PARAM_IMPORT_DEBUG yes
|
||||
set USE_ALT_UPDATE_DIRS yes
|
||||
set PARAM_FILE /fs/microsd/params
|
||||
set PARAM_BACKUP_FILE "/fs/microsd/parameters_backup.bson"
|
||||
fi
|
||||
|
||||
if [ $USE_HARDFAULT_LOG = yes ]
|
||||
then
|
||||
if hardfault_log check
|
||||
then
|
||||
@ -104,7 +141,15 @@ then
|
||||
hardfault_log reset
|
||||
fi
|
||||
fi
|
||||
fi
|
||||
|
||||
if [ $USE_TASK_WATCHDOG = yes ]
|
||||
then
|
||||
task_watchdog start
|
||||
fi
|
||||
|
||||
if [ $USE_ALT_UPDATE_DIRS = yes ]
|
||||
then
|
||||
# Check for an update of the ext_autostart folder, and replace the old one with it
|
||||
if [ -e /fs/microsd/ext_autostart_new ]
|
||||
then
|
||||
@ -112,9 +157,6 @@ then
|
||||
rm -r $SDCARD_EXT_PATH
|
||||
mv /fs/microsd/ext_autostart_new $SDCARD_EXT_PATH
|
||||
fi
|
||||
|
||||
set PARAM_FILE /fs/microsd/params
|
||||
set PARAM_BACKUP_FILE "/fs/microsd/parameters_backup.bson"
|
||||
fi
|
||||
|
||||
#
|
||||
@ -155,8 +197,11 @@ else
|
||||
|
||||
if [ -d "/fs/microsd" ]
|
||||
then
|
||||
# try to make a backup copy
|
||||
if [ $USE_PARAM_IMPORT_DEBUG = yes ]
|
||||
then
|
||||
# save copy of the failed param file for debugging
|
||||
cp $PARAM_FILE /fs/microsd/param_import_fail.bson
|
||||
fi
|
||||
|
||||
# try importing from backup file
|
||||
if [ -f $PARAM_BACKUP_FILE ]
|
||||
@ -174,11 +219,14 @@ else
|
||||
|
||||
param status
|
||||
|
||||
if [ $USE_PARAM_IMPORT_DEBUG = yes ]
|
||||
then
|
||||
dmesg >> /fs/microsd/param_import_fail.txt &
|
||||
fi
|
||||
fi
|
||||
fi
|
||||
|
||||
if [ $STORAGE_AVAILABLE = yes ]
|
||||
if [ $USE_PARAM_BACKUPS = yes ]
|
||||
then
|
||||
param select-backup $PARAM_BACKUP_FILE
|
||||
fi
|
||||
@ -234,12 +282,12 @@ else
|
||||
|
||||
if [ ${VEHICLE_TYPE} = none ]
|
||||
then
|
||||
# Run external airframe script on SD card
|
||||
if [ $STORAGE_AVAILABLE = yes ]
|
||||
# Run external airframe script on SD card or EEPROM-backed storage
|
||||
if [ $USE_EXTERNAL_AIRFRAMES = yes ]
|
||||
then
|
||||
. ${R}etc/init.d/rc.autostart_ext
|
||||
else
|
||||
echo "ERROR [init] SD not mounted, skipping external airframe"
|
||||
echo "ERROR [init] no external airframe storage, skipping"
|
||||
fi
|
||||
fi
|
||||
|
||||
@ -679,9 +727,16 @@ unset PARAM_BACKUP_FILE
|
||||
unset PARAM_DEFAULTS_VER
|
||||
unset RC_INPUT_ARGS
|
||||
unset STORAGE_AVAILABLE
|
||||
unset STORAGE_CHECK
|
||||
unset SDCARD_EXT_PATH
|
||||
unset SDCARD_FORMAT
|
||||
unset STARTUP_TUNE
|
||||
unset USE_HARDFAULT_LOG
|
||||
unset USE_EXTERNAL_AIRFRAMES
|
||||
unset USE_PARAM_BACKUPS
|
||||
unset USE_PARAM_IMPORT_DEBUG
|
||||
unset USE_TASK_WATCHDOG
|
||||
unset USE_ALT_UPDATE_DIRS
|
||||
unset VEHICLE_TYPE
|
||||
|
||||
#
|
||||
|
||||
@ -34,8 +34,5 @@ nshterm /dev/ttyS3 &
|
||||
# Start the time_persistor to cyclically store the RTC in FRAM
|
||||
time_persistor start
|
||||
|
||||
# Start the task_watchdog as we do not have the logger watchdog
|
||||
task_watchdog start
|
||||
|
||||
# Start the ESC telemetry
|
||||
dshot telemetry -d /dev/ttyS5 -x
|
||||
|
||||
19
boards/auterion/fmu-v6s/init/rc.board_early
Normal file
19
boards/auterion/fmu-v6s/init/rc.board_early
Normal file
@ -0,0 +1,19 @@
|
||||
#!/bin/sh
|
||||
#
|
||||
# Board early init.
|
||||
#
|
||||
# On FRAM boards STORAGE_AVAILABLE=yes will set the USE_* flags. Additional
|
||||
# enable required for task watchdog as this is not a generally used feature.
|
||||
# On EEPROM boards: Only airframes and params are needed.
|
||||
#
|
||||
|
||||
if mft query -q -k MTD -s MTD_PARAMETERS -v /mnt/microsd
|
||||
then
|
||||
# Start the task_watchdog as we do not have the logger watchdog
|
||||
set USE_TASK_WATCHDOG yes
|
||||
else
|
||||
set PARAM_FILE /fs/microsd/params
|
||||
set STORAGE_CHECK no
|
||||
set USE_EXTERNAL_AIRFRAMES yes
|
||||
set USE_ALT_UPDATE_DIRS yes
|
||||
fi
|
||||
Loading…
x
Reference in New Issue
Block a user