PX4 (APM)的启动流程
1. 脚本运行阶段
PX4的软件主要可分为Bootloader,Nuttx内核,ROMFS文件系统的挂载,和ArduPilot程序的执行,我们首先讨论ROMFS文件系统挂载完成到ArduPilot执行的过程。
ROMFS挂载完成后,会先执行/etc/init.d/rcS脚本,在源代码中的位置为mk/PX4/ROMFS/init.d/rcS,其内容见附录一
在px4-v2上,正常运行时,此脚本可以简化为下:
set MODE autostart set USB autoconnect rgbled start set HAVE_RGBLED 1 rgbled rgb 16 16 16
echo "[init] looking for microSD..." mount -t vfat /dev/mmcsd0 /fs/microsd echo "[init] card mounted at /fs/microsd" set HAVE_MICROSD 1 tone_alarm 1
sercon echo "[init] USB interface connected"
echo Running rc.APM sh /etc/init.d/rc.APM |
可以看到此脚本的功能就是,挂载rgbled设备并置成白色,挂载SD卡,注册CDC/ACM驱动,执行rc.APM脚本。
rc.APM脚本位于源代码mk/PX4/ROMFS/init.d路径下,其内容见附录二。
在px4-v2上正常运行时,此脚本可以简化如下:
set deviceA /dev/ttyACM0
echo "Mounting binfs" mount -t binfs /dev/null /bin echo "binfs mounted OK"
set sketch NONE
rm /fs/microsd/APM/boot.log set logfile /fs/microsd/APM/BOOT.LOG
mkdir /fs/microsd/APM > /dev/null
echo "Detected FMUv2 board" set BOARD FMUv2
set deviceC /dev/ttyS1 set deviceD /dev/ttyS2
uorb start echo "uorb started OK"
echo "Trying PX4IO board" set HAVE_PX4IO false px4io start norc set HAVE_PX4IO true
echo "PX4IO board OK" px4io checkcrc /etc/px4io/px4io.bin echo "PX4IO CRC OK"
fmu mode_pwm4 echo "Set FMU mode_pwm4"
echo "Starting APM sensors"
ms5611 start echo "ms5611 started OK"
adc start echo "adc started OK"
echo "Starting FMUv2 sensors"
hmc5883 -C -T -X start echo "Have external hmc5883" hmc5883 -C -T -I -R 4 start echo "No internal hmc5883"
mpu6000 -X -R 4 start mpu9250 -X -R 4 start echo "No MPU6000 or MPU9250 external" set HAVE_FMUV3 false
mpu6000 start echo "Found MPU6000"
l3gd20 start echo "l3gd20 started OK" lsm303d start echo "lsm303d started OK"
ets_airspeed start
meas_airspeed start meas_airspeed start -b 2
ll40ls -X start ll40ls -I start
trone start
mb12xx start
px4flow start
pwm_input start echo "started pwm_input driver"
mtd start /fs/mtd echo "started mtd driver OK"
mtd readtest /fs/mtd echo "mtd readtest OK"
oreoled start autoupdate echo "oreoled started OK"
batt_smbus -b 2 start echo "Found batt_smbus"
irlock start
mtd rwtest /fs/mtd echo "mtd rwtest OK"
echo Starting ArduPilot $deviceA $deviceC $deviceD ArduPilot -d $deviceA -d2 $deviceC -d3 $deviceD start echo ArduPilot started OK
echo "rc.APM finished" |
可以看到,此脚本主要是启动px4io及各个传感器,最后启动了ArduPilot主程序。下面我们来来看看ArduPilot主程序。
2. ArduPilot程序的启动
在ArduCopter下的ArduCopter.cpp的最后一行为:
AP_HAL_MAIN_CALLBACKS(&copter); |
而AP_HAL_MAIN_CALLBACKS定义在libraries/AP_HAL/ AP_HAL_Main.h中
#define AP_MAIN __EXPORT ArduPilot_main
#define AP_HAL_MAIN_CALLBACKS |