mirror of
https://gitee.com/xiaohuolufeihua/bizhang_-obav.git
synced 2026-05-21 01:12:11 +00:00
Breakout rc.thermal_cal from rcS and group set/unset parameters at the beginning and end of the rcS script. Revert commit 2a3d66cf45 to reduce px4fmu-v2_default flash size. Standardize tabs/whitespaces across all files in the init.d directory.
This commit is contained in:
@@ -18,4 +18,3 @@ sh /etc/init.d/rc.mc_defaults
|
|||||||
set MIXER tri_y_yaw+
|
set MIXER tri_y_yaw+
|
||||||
|
|
||||||
set PWM_OUT 1234
|
set PWM_OUT 1234
|
||||||
|
|
||||||
|
|||||||
@@ -12,4 +12,3 @@
|
|||||||
sh /etc/init.d/rc.fw_defaults
|
sh /etc/init.d/rc.fw_defaults
|
||||||
|
|
||||||
set MIXER Viper
|
set MIXER Viper
|
||||||
|
|
||||||
|
|||||||
@@ -28,4 +28,3 @@ set PWM_OUT 1234
|
|||||||
set MIXER_AUX mount
|
set MIXER_AUX mount
|
||||||
set PWM_AUX_OUT 123456
|
set PWM_AUX_OUT 123456
|
||||||
set PWM_AUX_RATE 50
|
set PWM_AUX_RATE 50
|
||||||
|
|
||||||
|
|||||||
@@ -111,6 +111,7 @@ px4_add_romfs_files(
|
|||||||
rc.mc_defaults
|
rc.mc_defaults
|
||||||
rcS
|
rcS
|
||||||
rc.sensors
|
rc.sensors
|
||||||
|
rc.thermal_cal
|
||||||
rc.ugv_apps
|
rc.ugv_apps
|
||||||
rc.ugv_defaults
|
rc.ugv_defaults
|
||||||
rc.vtol_apps
|
rc.vtol_apps
|
||||||
|
|||||||
40
ROMFS/px4fmu_common/init.d/rc.thermal_cal
Normal file
40
ROMFS/px4fmu_common/init.d/rc.thermal_cal
Normal file
@@ -0,0 +1,40 @@
|
|||||||
|
#!nsh
|
||||||
|
#
|
||||||
|
# Thermal Calibration startup script.
|
||||||
|
#
|
||||||
|
# NOTE: Script variables are declared/initialized/unset in the rcS script.
|
||||||
|
#
|
||||||
|
|
||||||
|
set TEMP_CALIB_ARGS ""
|
||||||
|
|
||||||
|
#
|
||||||
|
# Determine if a thermal calibration should be started.
|
||||||
|
#
|
||||||
|
|
||||||
|
if param compare SYS_CAL_ACCEL 1
|
||||||
|
then
|
||||||
|
set TEMP_CALIB_ARGS "${TEMP_CALIB_ARGS} -a"
|
||||||
|
param set SYS_CAL_ACCEL 0
|
||||||
|
fi
|
||||||
|
|
||||||
|
if param compare SYS_CAL_GYRO 1
|
||||||
|
then
|
||||||
|
set TEMP_CALIB_ARGS "${TEMP_CALIB_ARGS} -g"
|
||||||
|
param set SYS_CAL_GYRO 0
|
||||||
|
fi
|
||||||
|
|
||||||
|
if param compare SYS_CAL_BARO 1
|
||||||
|
then
|
||||||
|
set TEMP_CALIB_ARGS "${TEMP_CALIB_ARGS} -b"
|
||||||
|
param set SYS_CAL_BARO 0
|
||||||
|
fi
|
||||||
|
|
||||||
|
#
|
||||||
|
# Start the thermal calibration cycle.
|
||||||
|
#
|
||||||
|
if [ "x$TEMP_CALIB_ARGS" != "x" ]
|
||||||
|
then
|
||||||
|
send_event temperature_calibration ${TEMP_CALIB_ARGS}
|
||||||
|
fi
|
||||||
|
|
||||||
|
unset TEMP_CALIB_ARGS
|
||||||
@@ -39,6 +39,47 @@ set +e
|
|||||||
# UART7 /dev/ttyS5 ?
|
# UART7 /dev/ttyS5 ?
|
||||||
# UART8 /dev/ttyS6 CONSOLE
|
# UART8 /dev/ttyS6 CONSOLE
|
||||||
|
|
||||||
|
#
|
||||||
|
# Set default paramter values
|
||||||
|
#
|
||||||
|
set AUX_MODE pwm
|
||||||
|
set DATAMAN_OPT ""
|
||||||
|
set FAILSAFE none
|
||||||
|
set FAILSAFE_AUX none
|
||||||
|
set FCONFIG /fs/microsd/etc/config.txt
|
||||||
|
set FEXTRAS /fs/microsd/etc/extras.txt
|
||||||
|
set FRC /fs/microsd/etc/rc.txt
|
||||||
|
set FMU_ARGS ""
|
||||||
|
set FMU_MODE pwm
|
||||||
|
set IO_FILE ""
|
||||||
|
set IO_PRESENT no
|
||||||
|
set LOG_FILE /fs/microsd/bootlog.txt
|
||||||
|
set LOGGER_BUF 14
|
||||||
|
set MAVLINK_F default
|
||||||
|
set MAVLINK_COMPANION_DEVICE /dev/ttyS2
|
||||||
|
set MAV_TYPE none
|
||||||
|
set MIXER none
|
||||||
|
set MIXER_AUX none
|
||||||
|
set MK_MODE none
|
||||||
|
set MKBLCTRL_ARG ""
|
||||||
|
set MODE autostart
|
||||||
|
set OUTPUT_MODE none
|
||||||
|
set PARAM_FILE /fs/microsd/params
|
||||||
|
set PWM_OUT none
|
||||||
|
set PWM_RATE p:PWM_RATE
|
||||||
|
set PWM_DISARMED p:PWM_DISARMED
|
||||||
|
set PWM_MIN p:PWM_MIN
|
||||||
|
set PWM_MAX p:PWM_MAX
|
||||||
|
set PWM_AUX_OUT none
|
||||||
|
set PWM_AUX_RATE none
|
||||||
|
set PWM_ACHDIS none
|
||||||
|
set PWM_AUX_DISARMED p:PWM_AUX_DISARMED
|
||||||
|
set PWM_AUX_MIN p:PWM_AUX_MIN
|
||||||
|
set PWM_AUX_MAX p:PWM_AUX_MAX
|
||||||
|
set TUNE_ERR "ML<<CP4CP4CP4CP4CP4"
|
||||||
|
set USE_IO no
|
||||||
|
set VEHICLE_TYPE none
|
||||||
|
|
||||||
#
|
#
|
||||||
# Mount the procfs.
|
# Mount the procfs.
|
||||||
#
|
#
|
||||||
@@ -52,14 +93,6 @@ sercon
|
|||||||
# print full system version
|
# print full system version
|
||||||
ver all
|
ver all
|
||||||
|
|
||||||
#
|
|
||||||
# Default to auto-start mode.
|
|
||||||
#
|
|
||||||
set MODE autostart
|
|
||||||
|
|
||||||
set TUNE_ERR "ML<<CP4CP4CP4CP4CP4"
|
|
||||||
set LOG_FILE /fs/microsd/bootlog.txt
|
|
||||||
|
|
||||||
#
|
#
|
||||||
# Try to mount the microSD card.
|
# Try to mount the microSD card.
|
||||||
#
|
#
|
||||||
@@ -96,17 +129,14 @@ fi
|
|||||||
# Look for an init script on the microSD card.
|
# Look for an init script on the microSD card.
|
||||||
# Disable autostart if the script found.
|
# Disable autostart if the script found.
|
||||||
#
|
#
|
||||||
set FRC /fs/microsd/etc/rc.txt
|
|
||||||
if [ -f $FRC ]
|
if [ -f $FRC ]
|
||||||
then
|
then
|
||||||
sh $FRC
|
sh $FRC
|
||||||
set MODE custom
|
set MODE custom
|
||||||
fi
|
fi
|
||||||
unset FRC
|
|
||||||
|
|
||||||
if [ $MODE == autostart ]
|
if [ $MODE == autostart ]
|
||||||
then
|
then
|
||||||
|
|
||||||
#
|
#
|
||||||
# Start the ORB (first app to start)
|
# Start the ORB (first app to start)
|
||||||
#
|
#
|
||||||
@@ -121,7 +151,6 @@ then
|
|||||||
#
|
#
|
||||||
# Load parameters
|
# Load parameters
|
||||||
#
|
#
|
||||||
set PARAM_FILE /fs/microsd/params
|
|
||||||
if mtd start
|
if mtd start
|
||||||
then
|
then
|
||||||
set PARAM_FILE /fs/mtd_params
|
set PARAM_FILE /fs/mtd_params
|
||||||
@@ -173,36 +202,6 @@ then
|
|||||||
fi
|
fi
|
||||||
fi
|
fi
|
||||||
|
|
||||||
#
|
|
||||||
# Set default values
|
|
||||||
#
|
|
||||||
set VEHICLE_TYPE none
|
|
||||||
set MIXER none
|
|
||||||
set MIXER_AUX none
|
|
||||||
set OUTPUT_MODE none
|
|
||||||
set PWM_OUT none
|
|
||||||
set PWM_RATE p:PWM_RATE
|
|
||||||
set PWM_DISARMED p:PWM_DISARMED
|
|
||||||
set PWM_MIN p:PWM_MIN
|
|
||||||
set PWM_MAX p:PWM_MAX
|
|
||||||
set PWM_AUX_OUT none
|
|
||||||
set PWM_AUX_RATE none
|
|
||||||
set PWM_ACHDIS none
|
|
||||||
set PWM_AUX_DISARMED p:PWM_AUX_DISARMED
|
|
||||||
set PWM_AUX_MIN p:PWM_AUX_MIN
|
|
||||||
set PWM_AUX_MAX p:PWM_AUX_MAX
|
|
||||||
set FAILSAFE_AUX none
|
|
||||||
set MK_MODE none
|
|
||||||
set FMU_MODE pwm
|
|
||||||
set AUX_MODE pwm
|
|
||||||
set FMU_ARGS ""
|
|
||||||
set MAVLINK_F default
|
|
||||||
set MAVLINK_COMPANION_DEVICE /dev/ttyS2
|
|
||||||
set MAV_TYPE none
|
|
||||||
set FAILSAFE none
|
|
||||||
set USE_IO no
|
|
||||||
set LOGGER_BUF 14
|
|
||||||
|
|
||||||
if ver hwcmp PX4FMU_V5
|
if ver hwcmp PX4FMU_V5
|
||||||
then
|
then
|
||||||
set LOGGER_BUF 64
|
set LOGGER_BUF 64
|
||||||
@@ -261,7 +260,6 @@ then
|
|||||||
else
|
else
|
||||||
sh /etc/init.d/rc.autostart
|
sh /etc/init.d/rc.autostart
|
||||||
fi
|
fi
|
||||||
unset MODE
|
|
||||||
|
|
||||||
#
|
#
|
||||||
# If mount (gimbal) control is enabled and output mode is AUX, set the aux
|
# If mount (gimbal) control is enabled and output mode is AUX, set the aux
|
||||||
@@ -279,13 +277,11 @@ then
|
|||||||
#
|
#
|
||||||
# Override parameters from user configuration file
|
# Override parameters from user configuration file
|
||||||
#
|
#
|
||||||
set FCONFIG /fs/microsd/etc/config.txt
|
|
||||||
if [ -f $FCONFIG ]
|
if [ -f $FCONFIG ]
|
||||||
then
|
then
|
||||||
echo "Custom: ${FCONFIG}"
|
echo "Custom: ${FCONFIG}"
|
||||||
sh $FCONFIG
|
sh $FCONFIG
|
||||||
fi
|
fi
|
||||||
unset FCONFIG
|
|
||||||
|
|
||||||
#
|
#
|
||||||
# If autoconfig parameter was set, reset it and save parameters
|
# If autoconfig parameter was set, reset it and save parameters
|
||||||
@@ -317,9 +313,6 @@ then
|
|||||||
|
|
||||||
param set SYS_AUTOCONFIG 0
|
param set SYS_AUTOCONFIG 0
|
||||||
fi
|
fi
|
||||||
unset AUTOCNF
|
|
||||||
|
|
||||||
set IO_PRESENT no
|
|
||||||
|
|
||||||
#
|
#
|
||||||
# Check if PX4IO present and update firmware if needed
|
# Check if PX4IO present and update firmware if needed
|
||||||
@@ -365,7 +358,6 @@ then
|
|||||||
fi
|
fi
|
||||||
fi
|
fi
|
||||||
fi
|
fi
|
||||||
unset IO_FILE
|
|
||||||
|
|
||||||
if [ $USE_IO == yes -a $IO_PRESENT == no ]
|
if [ $USE_IO == yes -a $IO_PRESENT == no ]
|
||||||
then
|
then
|
||||||
@@ -397,7 +389,6 @@ then
|
|||||||
set FMU_MODE rcin
|
set FMU_MODE rcin
|
||||||
fi
|
fi
|
||||||
|
|
||||||
set DATAMAN_OPT ""
|
|
||||||
if ver hwcmp AEROFC_V1
|
if ver hwcmp AEROFC_V1
|
||||||
then
|
then
|
||||||
set DATAMAN_OPT -i
|
set DATAMAN_OPT -i
|
||||||
@@ -406,16 +397,19 @@ then
|
|||||||
then
|
then
|
||||||
set DATAMAN_OPT "-f /fs/mtd_dataman"
|
set DATAMAN_OPT "-f /fs/mtd_dataman"
|
||||||
fi
|
fi
|
||||||
|
|
||||||
|
#
|
||||||
# waypoint storage
|
# waypoint storage
|
||||||
# REBOOTWORK this needs to start in parallel
|
# REBOOTWORK this needs to start in parallel
|
||||||
|
#
|
||||||
if dataman start $DATAMAN_OPT
|
if dataman start $DATAMAN_OPT
|
||||||
then
|
then
|
||||||
fi
|
fi
|
||||||
unset DATAMAN_OPT
|
|
||||||
|
|
||||||
#
|
#
|
||||||
# Sensors System (start before Commander so Preflight checks are properly run)
|
# Sensors System (start before Commander so Preflight checks are properly run)
|
||||||
# commander Needs to be this early for in-air-restarts
|
# commander Needs to be this early for in-air-restarts
|
||||||
|
#
|
||||||
if param compare SYS_HITL 1
|
if param compare SYS_HITL 1
|
||||||
then
|
then
|
||||||
set OUTPUT_MODE hil
|
set OUTPUT_MODE hil
|
||||||
@@ -431,6 +425,7 @@ then
|
|||||||
sh /etc/init.d/rc.sensors
|
sh /etc/init.d/rc.sensors
|
||||||
commander start
|
commander start
|
||||||
fi
|
fi
|
||||||
|
|
||||||
send_event start
|
send_event start
|
||||||
load_mon start
|
load_mon start
|
||||||
|
|
||||||
@@ -501,7 +496,6 @@ then
|
|||||||
|
|
||||||
if [ $OUTPUT_MODE == mkblctrl ]
|
if [ $OUTPUT_MODE == mkblctrl ]
|
||||||
then
|
then
|
||||||
set MKBLCTRL_ARG ""
|
|
||||||
if [ $MKBLCTRL_MODE == x ]
|
if [ $MKBLCTRL_MODE == x ]
|
||||||
then
|
then
|
||||||
set MKBLCTRL_ARG "-mkmode x"
|
set MKBLCTRL_ARG "-mkmode x"
|
||||||
@@ -516,9 +510,7 @@ then
|
|||||||
else
|
else
|
||||||
tune_control play -m ${TUNE_ERR}
|
tune_control play -m ${TUNE_ERR}
|
||||||
fi
|
fi
|
||||||
unset MKBLCTRL_ARG
|
|
||||||
fi
|
fi
|
||||||
unset MK_MODE
|
|
||||||
|
|
||||||
if [ $OUTPUT_MODE == hil ]
|
if [ $OUTPUT_MODE == hil ]
|
||||||
then
|
then
|
||||||
@@ -603,7 +595,6 @@ fi
|
|||||||
else
|
else
|
||||||
mavlink start ${MAVLINK_F}
|
mavlink start ${MAVLINK_F}
|
||||||
fi
|
fi
|
||||||
unset MAVLINK_F
|
|
||||||
|
|
||||||
#
|
#
|
||||||
# MAVLink onboard / TELEM2
|
# MAVLink onboard / TELEM2
|
||||||
@@ -707,8 +698,6 @@ fi
|
|||||||
mavlink start -d ${MAVLINK_COMPANION_DEVICE} -b 1500000 -m onboard -r 10000 -x -f
|
mavlink start -d ${MAVLINK_COMPANION_DEVICE} -b 1500000 -m onboard -r 10000 -x -f
|
||||||
fi
|
fi
|
||||||
|
|
||||||
unset MAVLINK_COMPANION_DEVICE
|
|
||||||
|
|
||||||
#
|
#
|
||||||
# Starting stuff according to UAVCAN_ENABLE value
|
# Starting stuff according to UAVCAN_ENABLE value
|
||||||
#
|
#
|
||||||
@@ -904,10 +893,6 @@ fi
|
|||||||
sh /etc/init.d/rc.ugv_apps
|
sh /etc/init.d/rc.ugv_apps
|
||||||
fi
|
fi
|
||||||
|
|
||||||
unset MIXER
|
|
||||||
unset MAV_TYPE
|
|
||||||
unset OUTPUT_MODE
|
|
||||||
|
|
||||||
#
|
#
|
||||||
# Start the navigator
|
# Start the navigator
|
||||||
#
|
#
|
||||||
@@ -923,13 +908,11 @@ fi
|
|||||||
fi
|
fi
|
||||||
|
|
||||||
# Start any custom addons
|
# Start any custom addons
|
||||||
set FEXTRAS /fs/microsd/etc/extras.txt
|
|
||||||
if [ -f $FEXTRAS ]
|
if [ -f $FEXTRAS ]
|
||||||
then
|
then
|
||||||
echo "Addons script: ${FEXTRAS}"
|
echo "Addons script: ${FEXTRAS}"
|
||||||
sh $FEXTRAS
|
sh $FEXTRAS
|
||||||
fi
|
fi
|
||||||
unset FEXTRAS
|
|
||||||
|
|
||||||
if ver hwcmp CRAZYFLIE
|
if ver hwcmp CRAZYFLIE
|
||||||
then
|
then
|
||||||
@@ -940,7 +923,6 @@ fi
|
|||||||
then
|
then
|
||||||
# AEROCORE2 shouldn't have an sd card
|
# AEROCORE2 shouldn't have an sd card
|
||||||
else
|
else
|
||||||
|
|
||||||
# Run no SD alarm
|
# Run no SD alarm
|
||||||
if [ $LOG_FILE == /dev/null ]
|
if [ $LOG_FILE == /dev/null ]
|
||||||
then
|
then
|
||||||
@@ -953,32 +935,13 @@ fi
|
|||||||
fi
|
fi
|
||||||
|
|
||||||
#
|
#
|
||||||
# Check if we should start a thermal calibration
|
# Start a thermal calibration if required.
|
||||||
# TODO move further up and don't start unnecessary services if we are calibrating
|
|
||||||
#
|
#
|
||||||
set TEMP_CALIB_ARGS ""
|
sh /etc/init.d/rc.thermal_cal
|
||||||
if param compare SYS_CAL_GYRO 1
|
|
||||||
then
|
|
||||||
set TEMP_CALIB_ARGS "${TEMP_CALIB_ARGS} -g"
|
|
||||||
param set SYS_CAL_GYRO 0
|
|
||||||
fi
|
|
||||||
if param compare SYS_CAL_ACCEL 1
|
|
||||||
then
|
|
||||||
set TEMP_CALIB_ARGS "${TEMP_CALIB_ARGS} -a"
|
|
||||||
param set SYS_CAL_ACCEL 0
|
|
||||||
fi
|
|
||||||
if param compare SYS_CAL_BARO 1
|
|
||||||
then
|
|
||||||
set TEMP_CALIB_ARGS "${TEMP_CALIB_ARGS} -b"
|
|
||||||
param set SYS_CAL_BARO 0
|
|
||||||
fi
|
|
||||||
if [ "x$TEMP_CALIB_ARGS" != "x" ]
|
|
||||||
then
|
|
||||||
send_event temperature_calibration ${TEMP_CALIB_ARGS}
|
|
||||||
fi
|
|
||||||
unset TEMP_CALIB_ARGS
|
|
||||||
|
|
||||||
|
#
|
||||||
# vmount to control mounts such as gimbals, disabled by default.
|
# vmount to control mounts such as gimbals, disabled by default.
|
||||||
|
#
|
||||||
if param compare MNT_MODE_IN -1
|
if param compare MNT_MODE_IN -1
|
||||||
then
|
then
|
||||||
else
|
else
|
||||||
@@ -994,7 +957,47 @@ fi
|
|||||||
|
|
||||||
# There is no further script processing, so we can free some RAM
|
# There is no further script processing, so we can free some RAM
|
||||||
# XXX potentially unset all script variables.
|
# XXX potentially unset all script variables.
|
||||||
|
unset AUX_MODE
|
||||||
|
unset DATAMAN_OPT
|
||||||
|
unset FAILSAFE
|
||||||
|
unset FAILSAFE_AUX
|
||||||
|
unset FCONFIG
|
||||||
|
unset FEXTRAS
|
||||||
|
unset FRC
|
||||||
|
unset FMU_ARGS
|
||||||
|
unset FMU_MODE
|
||||||
|
unset IO_FILE
|
||||||
|
unset IO_PRESENT
|
||||||
|
unset LOG_FILE
|
||||||
|
unset LOGGER_BUF
|
||||||
|
unset MAVLINK_F
|
||||||
|
unset MAVLINK_COMPANION_DEVICE
|
||||||
|
unset MAV_TYPE
|
||||||
|
unset MIXER
|
||||||
|
unset MIXER_AUX
|
||||||
|
unset MK_MODE
|
||||||
|
unset MKBLCTRL_ARG
|
||||||
|
unset MODE
|
||||||
|
unset OUTPUT_AUX_DEV
|
||||||
|
unset OUTPUT_DEV
|
||||||
|
unset OUTPUT_MODE
|
||||||
|
unset PARAM_FILE
|
||||||
|
unset PWM_ACHDIS
|
||||||
|
unset PWM_OUT
|
||||||
|
unset PWM_RATE
|
||||||
|
unset PWM_DISARMED
|
||||||
|
unset PWM_MIN
|
||||||
|
unset PWM_MAX
|
||||||
|
unset PWM_AUX_OUT
|
||||||
|
unset PWM_AUX_RATE
|
||||||
|
unset PWM_ACHDIS
|
||||||
|
unset PWM_AUX_DISARMED
|
||||||
|
unset PWM_AUX_MIN
|
||||||
|
unset PWM_AUX_MAX
|
||||||
unset TUNE_ERR
|
unset TUNE_ERR
|
||||||
|
unset USE_IO
|
||||||
|
unset VEHICLE_TYPE
|
||||||
|
|
||||||
|
|
||||||
# Boot is complete, inform MAVLink app(s) that the system is now fully up and running
|
# Boot is complete, inform MAVLink app(s) that the system is now fully up and running
|
||||||
mavlink boot_complete
|
mavlink boot_complete
|
||||||
|
|||||||
@@ -62,7 +62,7 @@ set(config_module_list
|
|||||||
#
|
#
|
||||||
# System commands
|
# System commands
|
||||||
#
|
#
|
||||||
systemcmds/bl_update
|
#systemcmds/bl_update
|
||||||
#systemcmds/config
|
#systemcmds/config
|
||||||
#systemcmds/dumpfile
|
#systemcmds/dumpfile
|
||||||
#systemcmds/esc_calib
|
#systemcmds/esc_calib
|
||||||
|
|||||||
Reference in New Issue
Block a user