PX4通过rcS脚本来设定需要启动的程序,比如设备驱动、控制模块、数据通信等。rcS脚本在项目中的文件位置

ROMFS/px4fmu_common/rcS

对应硬件平台固件上的位置

/etc/init.d/rcS

启动脚本流程如下

#!/bin/sh
# PX4FMU startup script.
# 
# 一些注释
#

# 设置默认参数
set R /						#根目录
set AUTOCNF no
set FCONFIG /fs/microsd/etc/config.txt		#SD卡上的设置脚本
set FEXTRAS /fs/microsd/etc/extras.txt		#SD卡上的附加脚本
set FRC /fs/microsd/etc/rc.txt				#SD卡上启动脚本,如果有的话运行这个脚本
set IOFW "/etc/extras/px4_io-v2_default.bin"	#固件文件,如果有的话,自动刷新
set IO_PRESENT no
set LOGGER_ARGS ""
set LOGGER_BUF 8
set MAV_TYPE none			#飞行器类型,这里未设定
set MIXER none
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

#打印系统信息
ver all

# 载入SD卡
if [ -b "/dev/mmcsd0" ]
then
	if mount -t vfat /dev/mmcsd0 /fs/microsd		#mount
	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			#载入成功的情况下,设置参数文件为/fs/microsd/params
fi

# 查看SD卡上的启动脚本,如果有的话启动SD卡上的脚本,没有的话启动默认脚本
if [ -f $FRC ]
then
	. $FRC
else
	# 默认启动脚本
	
	# 查询MTD设备,挂载SPI-EEPROM,如果有的话设置从mtd设备载入参数
	if mft query -q -k MTD -s MTD_PARAMETERS -v /fs/mtd_params
	then
		set PARAM_FILE /fs/mtd_params
	fi

	# 载入参数,如果有板载校正数据
	if mft query -q -k MTD -s MTD_CALDATA -v /fs/mtd_caldata
	then
		param load /fs/mtd_caldata
	fi

	# 从PARAM_FILE载入参数
	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

	# 如果硬件版本为V5X或V6X,启动网络管理程序
	if ver hwcmp PX4_FMU_V5X PX4_FMU_V6X
	then
		netman update -i eth0
	fi

	# 如果自动配置不为0,重设一系列参数
	# SYS_AUTOCONFIG定义针对某一机型的自动参数设置,如DJI-F330, DJI-F450, 3DR SOLO等,都有一个对应的数字,具体可以查看/etc/init.d目录下的脚本,或者项目目录ROMFS/px4fmu_common/init.d/airframes目录下的脚本
	if param greater SYS_AUTOCONFIG 0
	then
		# Wipe out params except RC*, flight modes, total flight time, calibration parameters, next flight UUID
		param reset_all SYS_AUTO* RC* COM_FLTMODE* LND_FLIGHT* TC_* CAL_ACC* CAL_GYRO* COM_FLIGHT*
		set AUTOCNF yes
	fi

	# 板载架构配置脚本(可选)
	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

	# 板载配置脚本(可选)
	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

	# 启动声调报警模块
	tone_alarm start

	# 启动数据管理模块,根据源代码注释,也包含路径点存储(waypoints storage)
	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

	# 启动socket通讯和事件发送模块
	send_event start

	# 启动资源载入监控
	load_mon start

	# 启动灯闪控制模块
	rgbled start -X -q
	rgbled_ncp5623c start -X -q

	# 运行自动配置脚本,自动配置脚本中,根据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

	# 运行SD卡上的用户配置文件,FCONFIG在前面定义,指向SD卡上的配置文件
	if [ -f $FCONFIG ]
	then
		echo "Custom: ${FCONFIG}"
		. $FCONFIG
	fi

	# 如果AUTOCNF已经设置,SYS_AUTOCONFIG置零
	if [ $AUTOCNF = yes ]
	then
		param set SYS_AUTOCONFIG 0
	fi

	# 如果设置了UAVCAN_ENABLE,启动CAN总线控制
	if param greater -s UAVCAN_ENABLE 0
	then
		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 UAVCAN_V1_ENABLE 0
		then
			uavcan_v1 start
		fi
	fi

	# 检查PX4IO以及是否需要更新固件
	if [ -f $IOFW ]
	then
		# Check for the mini using build with px4io fw file
		# but not a px4IO
		if ver hwtypecmp V540 V560
		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

	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更新(把RC输入映射到手动控制)
	rc_update start

	#启动手动控制模块
	manual_control start

	# 启动传感器程序,启动commander模块
	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
			sih start
		fi
	else
		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

		commander start
	fi

	# 启动磁偏估计
	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

	# 启动板载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

	# 启动UART/串口驱动程序
	. ${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输入驱动
	if param greater -s PPS_CAP_ENABLE 0
	then
		pps_capture start
	fi

	# 启动摄像头拍摄模块
	if param greater -s CAM_CAP_FBACK 0
	then
		if camera_capture start
		then
			camera_capture on
		fi
	fi

	# 运行rc.vehicle_setup
	# rc.vehicle_setup脚本中运行接口程序(rc.interface)和飞行器应用程序(rc.mc_apps)(以多轴飞行器为例)
	# 其中rc.interface中启动电机PWM控制程序pwm_out和载入输出配置mixer文件,类似
	#		pwm_out start			- 启动PWM输出程序
	#		mixer load ...			- 载入PWM输出配置文件
	# rc.mc_apps启动飞行器相关主要控制程序,包括
	#		attitude_estimate_q		- 姿态估计
	#		ekf2					- 卡尔曼滤波
	#		mc_att_control			- 姿态控制
	#		mc_rate_control			- 速度控制
	#		mc_pos_control			- 位置控制
	#		land_detector			- 着陆检测
	# 等
	
	. ${R}etc/init.d/rc.vehicle_setup

	# 播放启动提示音
	param compare CBRK_BUZZER 782090
	if [ "$?" != "0" -o "$STARTUP_TUNE" != "1" ]
	then
		tune_control play -t $STARTUP_TUNE
	fi

	# 启动导航模块
	navigator start

	# 启动热校正(thermal calibration)程序
	. ${R}etc/init.d/rc.thermal_cal

	# 启动vmount, px4flow, bst等模块
	if param greater -s MNT_MODE_IN -1
	then
		vmount start
	fi

	if param compare -s SENS_EN_PX4FLOW 1
	then
		px4flow start -X
	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

	# 启动附加板载脚本
	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

	# 启动SD卡俯加脚本
	if [ -f $FEXTRAS ]
	then
		echo "Addons script: ${FEXTRAS}"
		. $FEXTRAS
	fi

	# 启动数据记录
	. ${R}etc/init.d/rc.logging

	# 启动AUTOSTART后处理程序
	if ! param compare SYS_AUTOSTART 0
	then
		. ${R}etc/init.d/rc.autostart.post
	fi

	# 启动板载bootloader升级程序
	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
fi

# 清除参数设置
unset R
unset AUTOCNF
unset FCONFIG
unset FEXTRAS
unset FRC
unset IO_PRESENT
unset IOFW
unset LOGGER_ARGS
unset LOGGER_BUF
unset MAV_TYPE
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

# 通知mavlink启动完成
mavlink boot_complete

启动的过程按图示大致如下(当前版本)
在这里插入图片描述

在这里插入图片描述

在这里插入图片描述

在这里插入图片描述

其中黄色部分为SD卡自定义脚本,蓝色部分为控制相关程序,紫色部分为机型相关自动配置程序,绿色部分为算法程序。

总结主要的点有:

1 程序启动首先Load SD卡,如果SD卡上有自定义启动脚本,就运行SD卡上的脚本,如果没有(默认情况),运行板载自动启动流程
2 机型相关的参数配置通过SYS_AUTOSTART值来定义,通过设置这个值,可以自动载入某一机型对应的参数(如DJI 450,3DR SOLO等)
3 飞行控制相关程序在commander,rc.vehicle_setup,navigator等模块或脚本启动,主要的飞控相关模块有
rc_input - 遥控输入
commander - 命令处理
navigator - 导航
pos_control - 位置控制
att_control - 姿态控制
pwm_out - 电机输出