mirror of
https://gitee.com/mirrors_PX4/PX4-Autopilot.git
synced 2026-04-14 10:07:39 +08:00
- new modules/simulation directory to collect all simulators and related modules - new Tools/simulation directory to collect and organize scattered simulation submodules, scripts, etc - simulation module renamed to simulator_mavlink - sih renamed to simulator_sih (not a great name, but I wanted to be clear it was a simulator) - ignition_simulator renamed to simulator_ignition_bridge - large sitl_target.cmake split by simulation option and in some cases pushed to appropriate modules - sitl targets broken down to what's actually available (eg jmavsim only has 1 model and 1 world) - new Gazebo consistently referred to as Ignition for now (probably the least confusing thing until we fully drop Gazebo classic support someday)
589 lines
12 KiB
Bash
589 lines
12 KiB
Bash
#!/bin/sh
|
|
# Un comment and use set +e to ignore and set -e to enable 'exit on error control'
|
|
set +e
|
|
# Un comment the line below to help debug scripts by printing a trace of the script commands
|
|
#set -x
|
|
# PX4FMU startup script.
|
|
#
|
|
# NOTE: environment variable references:
|
|
# If the dollar sign ('$') is followed by a left bracket ('{') then the
|
|
# variable name is terminated with the right bracket character ('}').
|
|
# Otherwise, the variable name goes to the end of the argument.
|
|
#
|
|
#
|
|
# NOTE: COMMENT LINES ARE REMOVED BEFORE STORED IN ROMFS.
|
|
#
|
|
#------------------------------------------------------------------------------
|
|
|
|
#
|
|
# Set default paramter values.
|
|
# Do not add intra word spaces
|
|
# it wastes flash
|
|
#
|
|
set R /
|
|
set FCONFIG /fs/microsd/etc/config.txt
|
|
set FEXTRAS /fs/microsd/etc/extras.txt
|
|
set FRC /fs/microsd/etc/rc.txt
|
|
set IOFW "/etc/extras/px4_io-v2_default.bin"
|
|
set IO_PRESENT no
|
|
set LOGGER_ARGS ""
|
|
set LOGGER_BUF 8
|
|
set MIXER skip
|
|
set MIXER_AUX none
|
|
set MIXER_FILE none
|
|
set MIXER_EXTRA none
|
|
set OUTPUT_MODE none
|
|
set PARAM_FILE ""
|
|
set PWM_OUT none
|
|
set PWM_MAIN_RATE p:PWM_MAIN_RATE
|
|
set PWM_AUX_OUT none
|
|
set PWM_AUX_RATE p:PWM_AUX_RATE
|
|
set PWM_EXTRA_OUT none
|
|
set PWM_EXTRA_RATE p:PWM_EXTRA_RATE
|
|
set EXTRA_MIXER_MODE none
|
|
set RC_INPUT_ARGS ""
|
|
set SDCARD_AVAILABLE no
|
|
set SDCARD_EXT_PATH /fs/microsd/ext_autostart
|
|
set SDCARD_FORMAT no
|
|
set SDCARD_MIXERS_PATH /fs/microsd/etc/mixers
|
|
set STARTUP_TUNE 1
|
|
set USE_IO no
|
|
set VEHICLE_TYPE none
|
|
|
|
#
|
|
# Print full system version.
|
|
#
|
|
ver all
|
|
|
|
#
|
|
# Try to mount the microSD card.
|
|
#
|
|
if [ -b "/dev/mmcsd0" ]
|
|
then
|
|
if mount -t vfat /dev/mmcsd0 /fs/microsd
|
|
then
|
|
if [ -f "/fs/microsd/.format" ]
|
|
then
|
|
echo "INFO [init] format /dev/mmcsd0 requested (/fs/microsd/.format)"
|
|
set SDCARD_FORMAT yes
|
|
rm /fs/microsd/.format
|
|
umount /fs/microsd
|
|
|
|
else
|
|
set SDCARD_AVAILABLE yes
|
|
fi
|
|
fi
|
|
|
|
if [ $SDCARD_AVAILABLE = no -o $SDCARD_FORMAT = yes ]
|
|
then
|
|
echo "INFO [init] formatting /dev/mmcsd0"
|
|
set STARTUP_TUNE 15 # tune 15 = SD_ERROR (overridden to SD_INIT if format + mount succeeds)
|
|
|
|
if mkfatfs -F 32 /dev/mmcsd0
|
|
then
|
|
echo "INFO [init] card formatted"
|
|
|
|
if mount -t vfat /dev/mmcsd0 /fs/microsd
|
|
then
|
|
set SDCARD_AVAILABLE yes
|
|
set STARTUP_TUNE 14 # tune 14 = SD_INIT
|
|
else
|
|
echo "ERROR [init] card mount failed"
|
|
fi
|
|
else
|
|
echo "ERROR [init] format failed"
|
|
fi
|
|
fi
|
|
|
|
if [ $SDCARD_AVAILABLE = yes ]
|
|
then
|
|
if hardfault_log check
|
|
then
|
|
set STARTUP_TUNE 2 # tune 2 = ERROR_TUNE
|
|
if hardfault_log commit
|
|
then
|
|
hardfault_log reset
|
|
fi
|
|
fi
|
|
fi
|
|
|
|
set PARAM_FILE /fs/microsd/params
|
|
fi
|
|
|
|
#
|
|
# Look for an init script on the microSD card.
|
|
# Disable autostart if the script found.
|
|
#
|
|
if [ -f $FRC ]
|
|
then
|
|
. $FRC
|
|
else
|
|
|
|
#
|
|
# Set the parameter file the board supports params on
|
|
# MTD device.
|
|
#
|
|
if mft query -q -k MTD -s MTD_PARAMETERS -v /fs/mtd_params
|
|
then
|
|
set PARAM_FILE /fs/mtd_params
|
|
fi
|
|
|
|
#
|
|
# Load parameters.
|
|
#
|
|
# if the board has a storage for (factory) calibration data
|
|
if mft query -q -k MTD -s MTD_CALDATA -v /fs/mtd_caldata
|
|
then
|
|
param load /fs/mtd_caldata
|
|
fi
|
|
|
|
param select $PARAM_FILE
|
|
if ! param import
|
|
then
|
|
echo "ERROR [init] param import failed"
|
|
set STARTUP_TUNE 2 # tune 2 = ERROR_TUNE
|
|
|
|
param dump $PARAM_FILE
|
|
|
|
if [ -d "/fs/microsd" ]
|
|
then
|
|
dmesg >> /fs/microsd/param_import_fail.txt &
|
|
|
|
# try to make a backup copy
|
|
cp $PARAM_FILE /fs/microsd/param_import_fail.bson &
|
|
fi
|
|
|
|
# try importing from backup file
|
|
if [ -f "/fs/microsd/parameters_backup.bson" ]
|
|
then
|
|
echo "[init] importing from parameter backup"
|
|
|
|
# dump current backup file contents for comparison
|
|
param dump /fs/microsd/parameters_backup.bson
|
|
|
|
param import /fs/microsd/parameters_backup.bson
|
|
fi
|
|
fi
|
|
|
|
if [ $SDCARD_AVAILABLE = yes ]
|
|
then
|
|
param select-backup /fs/microsd/parameters_backup.bson
|
|
fi
|
|
|
|
if ver hwcmp PX4_FMU_V5X PX4_FMU_V6X
|
|
then
|
|
netman update -i eth0
|
|
fi
|
|
|
|
#
|
|
# If the airframe has been previously reset SYS_AUTCONFIG will have been set to 1 and other params will be reset on the next boot.
|
|
#
|
|
if param greater SYS_AUTOCONFIG 0
|
|
then
|
|
# Reset params except Airframe, RC calibration, sensor calibration, flight modes, total flight time, and next flight UUID.
|
|
param reset_all SYS_AUTOSTART RC* CAL_* COM_FLTMODE* LND_FLIGHT* TC_* COM_FLIGHT*
|
|
fi
|
|
|
|
#
|
|
# Optional board architecture defaults: rc.board_arch_defaults
|
|
#
|
|
set BOARD_ARCH_RC_DEFAULTS ${R}etc/init.d/rc.board_arch_defaults
|
|
if [ -f $BOARD_ARCH_RC_DEFAULTS ]
|
|
then
|
|
echo "Board architecture defaults: ${BOARD_ARCH_RC_DEFAULTS}"
|
|
. $BOARD_ARCH_RC_DEFAULTS
|
|
fi
|
|
unset BOARD_ARCH_RC_DEFAULTS
|
|
|
|
#
|
|
# Optional board defaults: rc.board_defaults
|
|
#
|
|
set BOARD_RC_DEFAULTS ${R}etc/init.d/rc.board_defaults
|
|
if [ -f $BOARD_RC_DEFAULTS ]
|
|
then
|
|
echo "Board defaults: ${BOARD_RC_DEFAULTS}"
|
|
. $BOARD_RC_DEFAULTS
|
|
fi
|
|
unset BOARD_RC_DEFAULTS
|
|
|
|
#
|
|
# Set parameters and env variables for selected SYS_AUTOSTART.
|
|
#
|
|
set AUTOSTART_PATH etc/init.d/rc.autostart
|
|
if ! param compare SYS_AUTOSTART 0
|
|
then
|
|
if param greater SYS_AUTOSTART 1000000
|
|
then
|
|
# Use external startup file
|
|
if [ $SDCARD_AVAILABLE = yes ]
|
|
then
|
|
set AUTOSTART_PATH etc/init.d/rc.autostart_ext
|
|
else
|
|
echo "ERROR [init] SD card not mounted - trying to load airframe from ROMFS"
|
|
fi
|
|
fi
|
|
. ${R}$AUTOSTART_PATH
|
|
fi
|
|
unset AUTOSTART_PATH
|
|
|
|
#
|
|
# Start the tone_alarm driver.
|
|
# Needs to be started after the parameters are loaded (for CBRK_BUZZER).
|
|
#
|
|
tone_alarm start
|
|
|
|
#
|
|
# Waypoint storage.
|
|
# REBOOTWORK this needs to start in parallel.
|
|
#
|
|
if param compare SYS_DM_BACKEND 1
|
|
then
|
|
dataman start -r
|
|
else
|
|
if param compare SYS_DM_BACKEND 0
|
|
then
|
|
# dataman start default
|
|
dataman start
|
|
fi
|
|
fi
|
|
|
|
#
|
|
# Start the socket communication send_event handler.
|
|
#
|
|
send_event start
|
|
|
|
#
|
|
# Start the resource load monitor.
|
|
#
|
|
load_mon start
|
|
|
|
#
|
|
# Start system state indicator.
|
|
#
|
|
rgbled start -X -q
|
|
rgbled_ncp5623c start -X -q
|
|
|
|
#
|
|
# Override parameters from user configuration file.
|
|
#
|
|
if [ -f $FCONFIG ]
|
|
then
|
|
echo "Custom: ${FCONFIG}"
|
|
. $FCONFIG
|
|
fi
|
|
|
|
#
|
|
# Check if UAVCAN is enabled, default to it for ESCs.
|
|
#
|
|
if param greater -s UAVCAN_ENABLE 0
|
|
then
|
|
# Start core UAVCAN module.
|
|
if uavcan start
|
|
then
|
|
if param greater UAVCAN_ENABLE 2
|
|
then
|
|
set OUTPUT_MODE uavcan_esc
|
|
fi
|
|
else
|
|
tune_control play error
|
|
fi
|
|
else
|
|
if param greater -s CYPHAL_ENABLE 0
|
|
then
|
|
cyphal start
|
|
fi
|
|
fi
|
|
|
|
#
|
|
# Check if PX4IO present and update firmware if needed.
|
|
# Assumption IOFW set to firmware file and IO_PRESENT = no
|
|
#
|
|
|
|
if [ -f $IOFW ]
|
|
then
|
|
# Check for the mini using build with px4io fw file
|
|
# but not a px4IO
|
|
if ver hwtypecmp V5004000 V5006000
|
|
then
|
|
param set SYS_USE_IO 0
|
|
else
|
|
if px4io checkcrc ${IOFW}
|
|
then
|
|
set IO_PRESENT yes
|
|
else
|
|
# tune Program PX4IO
|
|
tune_control play -t 16 # tune 16 = PROG_PX4IO
|
|
|
|
if px4io update ${IOFW}
|
|
then
|
|
usleep 10000
|
|
tune_control stop
|
|
if px4io checkcrc ${IOFW}
|
|
then
|
|
tune_control play -t 17 # tune 17 = PROG_PX4IO_OK
|
|
set IO_PRESENT yes
|
|
else
|
|
tune_control play -t 18 # tune 18 = PROG_PX4IO_ERR
|
|
fi
|
|
else
|
|
tune_control stop
|
|
fi
|
|
fi
|
|
fi
|
|
fi
|
|
|
|
#
|
|
# Set USE_IO flag.
|
|
#
|
|
if param compare -s SYS_USE_IO 1
|
|
then
|
|
set USE_IO yes
|
|
fi
|
|
|
|
if [ $USE_IO = yes -a $IO_PRESENT = no ]
|
|
then
|
|
echo "PX4IO not found"
|
|
set STARTUP_TUNE 2 # tune 2 = ERROR_TUNE
|
|
fi
|
|
|
|
#
|
|
# RC update (map raw RC input to calibrate manual control)
|
|
# start before commander
|
|
#
|
|
rc_update start
|
|
manual_control start
|
|
|
|
#
|
|
# Sensors System (start before Commander so Preflight checks are properly run).
|
|
# Commander needs to be this early for in-air-restarts.
|
|
#
|
|
if param greater SYS_HITL 0
|
|
then
|
|
set OUTPUT_MODE hil
|
|
sensors start -h
|
|
commander start -h
|
|
# disable GPS
|
|
param set GPS_1_CONFIG 0
|
|
|
|
# start the simulator in hardware if needed
|
|
if param compare SYS_HITL 2
|
|
then
|
|
simulator_sih start
|
|
fi
|
|
|
|
else
|
|
#
|
|
# board sensors: rc.sensors
|
|
#
|
|
set BOARD_RC_SENSORS ${R}etc/init.d/rc.board_sensors
|
|
if [ -f $BOARD_RC_SENSORS ]
|
|
then
|
|
echo "Board sensors: ${BOARD_RC_SENSORS}"
|
|
. $BOARD_RC_SENSORS
|
|
fi
|
|
unset BOARD_RC_SENSORS
|
|
|
|
. ${R}etc/init.d/rc.sensors
|
|
|
|
if param compare -s BAT1_SOURCE 2
|
|
then
|
|
esc_battery start
|
|
fi
|
|
|
|
if ! param compare BAT1_SOURCE 1
|
|
then
|
|
battery_status start
|
|
fi
|
|
|
|
sensors start
|
|
commander start
|
|
fi
|
|
|
|
#
|
|
# Configure vehicle type specific parameters.
|
|
# Note: rc.vehicle_setup is the entry point for rc.interface,
|
|
# rc.fw_apps, rc.mc_apps, rc.rover_apps, and rc.vtol_apps.
|
|
#
|
|
. ${R}etc/init.d/rc.vehicle_setup
|
|
|
|
# Pre-takeoff continuous magnetometer calibration
|
|
if param compare -s MBE_ENABLE 1
|
|
then
|
|
mag_bias_estimator start
|
|
fi
|
|
|
|
if param greater -s TRIG_MODE 0
|
|
then
|
|
camera_trigger start
|
|
camera_feedback start
|
|
fi
|
|
|
|
#
|
|
# Optional board mavlink streams: rc.board_mavlink
|
|
#
|
|
set BOARD_RC_MAVLINK ${R}etc/init.d/rc.board_mavlink
|
|
if [ -f $BOARD_RC_MAVLINK ]
|
|
then
|
|
echo "Board mavlink: ${BOARD_RC_MAVLINK}"
|
|
. $BOARD_RC_MAVLINK
|
|
fi
|
|
unset BOARD_RC_MAVLINK
|
|
|
|
#
|
|
# Start UART/Serial device drivers.
|
|
# Note: rc.serial is auto-generated from Tools/serial/generate_config.py
|
|
#
|
|
. ${R}etc/init.d/rc.serial
|
|
|
|
if [ $IO_PRESENT = no ]
|
|
then
|
|
# Must be started after the serial config is read
|
|
rc_input start $RC_INPUT_ARGS
|
|
fi
|
|
|
|
# PPS capture driver (before pwm_out)
|
|
if param greater -s PPS_CAP_ENABLE 0
|
|
then
|
|
pps_capture start
|
|
fi
|
|
|
|
# Camera capture driver (before pwm_out)
|
|
if param greater -s CAM_CAP_FBACK 0
|
|
then
|
|
if camera_capture start
|
|
then
|
|
camera_capture on
|
|
fi
|
|
fi
|
|
|
|
#
|
|
# Play the startup tune (if not disabled or there is an error)
|
|
#
|
|
param compare CBRK_BUZZER 782090
|
|
if [ "$?" != "0" -o "$STARTUP_TUNE" != "1" ]
|
|
then
|
|
tune_control play -t $STARTUP_TUNE
|
|
fi
|
|
|
|
#
|
|
# Start the navigator.
|
|
#
|
|
navigator start
|
|
|
|
#
|
|
# Start a thermal calibration if required.
|
|
#
|
|
. ${R}etc/init.d/rc.thermal_cal
|
|
|
|
#
|
|
# Start gimbal to control mounts such as gimbals, disabled by default.
|
|
#
|
|
if param greater -s MNT_MODE_IN -1
|
|
then
|
|
gimbal start
|
|
fi
|
|
|
|
# Blacksheep telemetry
|
|
if param compare -s TEL_BST_EN 1
|
|
then
|
|
bst start -X
|
|
fi
|
|
|
|
if param compare -s IMU_GYRO_FFT_EN 1
|
|
then
|
|
gyro_fft start
|
|
fi
|
|
|
|
if param compare -s IMU_GYRO_CAL_EN 1
|
|
then
|
|
gyro_calibration start
|
|
fi
|
|
|
|
# Check for px4flow sensor
|
|
if param compare -s SENS_EN_PX4FLOW 1
|
|
then
|
|
px4flow start -X &
|
|
fi
|
|
|
|
#
|
|
# Optional board supplied extras: rc.board_extras
|
|
#
|
|
set BOARD_RC_EXTRAS ${R}etc/init.d/rc.board_extras
|
|
if [ -f $BOARD_RC_EXTRAS ]
|
|
then
|
|
echo "Board extras: ${BOARD_RC_EXTRAS}"
|
|
. $BOARD_RC_EXTRAS
|
|
fi
|
|
unset BOARD_RC_EXTRAS
|
|
|
|
#
|
|
# Start any custom addons from the sdcard.
|
|
#
|
|
if [ -f $FEXTRAS ]
|
|
then
|
|
echo "Addons script: ${FEXTRAS}"
|
|
. $FEXTRAS
|
|
fi
|
|
|
|
#
|
|
# Start the logger.
|
|
#
|
|
. ${R}etc/init.d/rc.logging
|
|
|
|
#
|
|
# Set additional parameters and env variables for selected AUTOSTART.
|
|
#
|
|
if ! param compare SYS_AUTOSTART 0
|
|
then
|
|
. ${R}etc/init.d/rc.autostart.post
|
|
fi
|
|
|
|
|
|
set BOARD_BOOTLOADER_UPGRADE ${R}etc/init.d/rc.board_bootloader_upgrade
|
|
if [ -f $BOARD_BOOTLOADER_UPGRADE ]
|
|
then
|
|
sh $BOARD_BOOTLOADER_UPGRADE
|
|
fi
|
|
unset BOARD_BOOTLOADER_UPGRADE
|
|
|
|
#
|
|
# End of autostart.
|
|
#
|
|
fi
|
|
|
|
#
|
|
# Unset all script parameters to free RAM.
|
|
#
|
|
unset R
|
|
unset FCONFIG
|
|
unset FEXTRAS
|
|
unset FRC
|
|
unset IO_PRESENT
|
|
unset IOFW
|
|
unset LOGGER_ARGS
|
|
unset LOGGER_BUF
|
|
unset MIXER
|
|
unset MIXER_AUX
|
|
unset MIXER_FILE
|
|
unset OUTPUT_MODE
|
|
unset PARAM_FILE
|
|
unset PWM_AUX_OUT
|
|
unset PWM_AUX_RATE
|
|
unset PWM_MAIN_RATE
|
|
unset PWM_OUT
|
|
unset PWM_EXTRA_OUT
|
|
unset PWM_EXTRA_RATE
|
|
unset RC_INPUT_ARGS
|
|
unset SDCARD_AVAILABLE
|
|
unset SDCARD_EXT_PATH
|
|
unset SDCARD_FORMAT
|
|
unset SDCARD_MIXERS_PATH
|
|
unset STARTUP_TUNE
|
|
unset USE_IO
|
|
unset VEHICLE_TYPE
|
|
|
|
#
|
|
# Boot is complete, inform MAVLink app(s) that the system is now fully up and running.
|
|
#
|
|
mavlink boot_complete
|