注:本文转载自—— 博主:虾米一代 博客:《pixhawk原生码rcS分析》
代码执行流程
1. 编译时将cmake/configs/nuttx_px4fmu-v2_default.cmake文件中配置的模块全部编译并烧写到固件中去。
2. 地面站的配置会在flash中生成/fs/mtd_params文件,该文件包含了飞行器的各类信息(机架,校准信息,飞行模式等)。
3. 启动pixhawk,执行/Firmware/ROMFS/px4fmu_common/init.d/rcS,该文件会读入之前生成的参数文件,进而选择执行哪一个脚本文 件。(如选择DJI450机架会执行/Firmware/ROMFS/px4fmu_common/init.d/rc.mc_apps 和/Firmware/ROMFS/px4fmu_common/init.d/4011_dji_f450),它们的主要作用为启动飞控所需的各类软件。
4. 不同模块通过uORB通信。
上图形象说明启动流程
以下为代码做了部分注释
rcS
[cpp] view plain copy
- #!nsh
- #
- # PX4FMU startup script.
- #
- # NOTE: COMMENT LINES ARE REMOVED BEFORE STORED IN ROMFS.
- #
- #
- # Start CDC/ACM serial driver
- #
- sercon
- #
- # Default to auto-start mode. //一些默认设置
- #
- set MODE autostart
- set FRC /fs/microsd/etc/rc.txt
- set FCONFIG /fs/microsd/etc/config.txt
- set TUNE_ERR ML<<CP4CP4CP4CP4CP4
- set LOG_FILE /fs/microsd/bootlog.txt
- #
- # Try to mount the microSD card. //挂载SD卡
- #
- # REBOOTWORK this needs to start after the flight control loop
- if mount -t vfat /dev/mmcsd0 /fs/microsd
- then
- echo "[i] microSD mounted: /fs/microsd"
- # Start playing the startup tune
- tone_alarm start
- else
- tone_alarm MBAGP
- if mkfatfs /dev/mmcsd0
- then
- if mount -t vfat /dev/mmcsd0 /fs/microsd
- then
- echo "[i] microSD card formatted"
- else
- echo "[i] format failed"
- tone_alarm MNBG
- set LOG_FILE /dev/null
- fi
- else
- set LOG_FILE /dev/null
- fi
- fi
- #
- # Look for an init script on the microSD card.
- # Disable autostart if the script found.
- #
- if [ -f $FRC ] //如果找到初始化脚本,则不自动启动
- then
- echo "[i] Executing script: $FRC"
- sh $FRC
- set MODE custom
- fi
- unset FRC
- if [ $MODE == autostart ] //自动启动过程
- then
- #
- # Start the ORB (first app to start) //启动uORB
- #
- uorb start
- #
- # Load parameters //下载上位机传到sd卡上的参数(机型什么的)
- #
- set PARAM_FILE /fs/microsd/params
- if mtd start //启动mtd
- then
- set PARAM_FILE /fs/mtd_params
- fi
- param select $PARAM_FILE
- if param load //下载参数
- then
- echo "[param] Loaded: $PARAM_FILE"
- else
- echo "[param] FAILED loading $PARAM_FILE"
- if param reset
- then
- fi
- fi
- #
- # Start system state indicator //启动系统状态指示
- #
- if rgbled start //启动rgbled
- then
- else
- if blinkm start //启动blinkm(闪光)
- then
- blinkm systemstate
- fi
- fi
- # Currently unused, but might be useful down the road
- #if pca8574 start
- #then
- #fi
- #
- # Set default values //设置默认值
- #
- set HIL no
- set VEHICLE_TYPE none
- set MIXER none
- set MIXER_AUX none
- set OUTPUT_MODE none
- set PWM_OUT none
- set PWM_RATE none
- set PWM_DISARMED none
- set PWM_MIN none
- set PWM_MAX none
- set PWM_AUX_OUT none
- set PWM_AUX_RATE none
- set PWM_ACHDIS none
- set PWM_AUX_DISARMED none
- set PWM_AUX_MIN none
- set PWM_AUX_MAX none
- set FAILSAFE_AUX none
- set MK_MODE none
- set FMU_MODE pwm
- set AUX_MODE pwm
- set MAVLINK_F default
- set EXIT_ON_END no
- set MAV_TYPE none
- set LOAD_DAPPS yes
- set GPS yes
- set GPS_FAKE no
- set FAILSAFE none
- #
- # Set AUTOCNF flag to use it in AUTOSTART scripts //设置AUTOCNF标志
- #
- if param compare SYS_AUTOCONFIG 1
- then
- # Wipe out params except RC*
- param reset_nostart RC*
- set AUTOCNF yes
- else
- set AUTOCNF no
- fi
- #
- # Set USE_IO flag //设置USE_IO标志
- #
- if param compare SYS_USE_IO 1
- then
- if ver hwcmp PX4FMU_V4 //比较px4版本
- then
- set USE_IO no
- else
- set USE_IO yes
- fi
- else
- set USE_IO no
- fi
- #
- # Set parameters and env variables for selected AUTOSTART
- #
- if param compare SYS_AUTOSTART 0
- then
- echo "[i] No autostart"
- else
- sh /etc/init.d/rc.autostart //执行rc.autostart
- fi
- unset MODE
- #
- # Wipe incompatible settings for boards not having two outputs
- if ver hwcmp PX4FMU_V4
- then
- set MIXER_AUX none
- fi
- #
- # Override parameters from user configuration file//根据用户配置文件重写参数
- #
- if [ -f $FCONFIG ]
- then
- echo "[i] Custom config: $FCONFIG"
- sh $FCONFIG
- fi
- unset FCONFIG
- #
- # If autoconfig parameter was set, reset it and save parameters
- #
- if [ $AUTOCNF == yes ] //如果AUTOCNF == yes,那么复位并保存参数
- then
- param set SYS_AUTOCONFIG 0
- param save
- fi
- unset AUTOCNF
- set IO_PRESENT no
- if [ $USE_IO == yes ] //px4的版本为v2,所以条件满足
- then
- #
- # Check if PX4IO present and update firmware if needed//比较PX4IO,判断是否升级
- #
- if [ -f /etc/extras/px4io-v2.bin ] //选择PX4IO-v2固件
- then
- set IO_FILE /etc/extras/px4io-v2.bin
- else
- set IO_FILE /etc/extras/px4io-v1.bin
- fi
- if px4io checkcrc ${IO_FILE}//crc检验是否是最新版本
- then
- echo "PX4IO CRC OK" >> $LOG_FILE
- set IO_PRESENT yes
- else
- echo "PX4IO Trying to update" >> $LOG_FILE
- tone_alarm MLL32CP8MB
- if px4io start//启动px4io
- then
- # try to safe px4 io so motor outputs dont go crazy
- if px4io safety_on//判断px4io是否安全
- then
- # success! no-op
- else
- # px4io did not respond to the safety command
- px4io stop
- fi
- fi
- if px4io forceupdate 14662 ${IO_FILE}//是否强制升级
- then
- usleep 500000
- if px4io checkcrc $IO_FILE
- then
- echo "PX4IO CRC OK after updating" >> $LOG_FILE
- tone_alarm MLL8CDE
- set IO_PRESENT yes
- else
- echo "ERROR: PX4IO update failed" >> $LOG_FILE
- tone_alarm $TUNE_ERR
- fi
- else
- echo "ERROR: PX4IO update failed" >> $LOG_FILE
- tone_alarm $TUNE_ERR
- fi
- fi
- unset IO_FILE
- if [ $IO_PRESENT == no ] //没有找到px4io
- then
- echo "[i] ERROR: PX4IO not found"
- echo "ERROR: PX4IO not found" >> $LOG_FILE
- tone_alarm $TUNE_ERR
- fi
- fi
- #
- # Set default output if not set//如果不设置,则为默认设置none
- #
- if [ $OUTPUT_MODE == none ]
- then
- if [ $USE_IO == yes ] //px4的版本为v2,所以条件满足
- then
- set OUTPUT_MODE io
- else
- set OUTPUT_MODE fmu
- fi
- fi
- if [ $OUTPUT_MODE == io -a $IO_PRESENT != yes ]
- then
- # Need IO for output but it not present, disable output//需要IO口输出,但是它不存在
- set OUTPUT_MODE none
- echo "[i] ERROR: PX4IO not found, disabling output"
- # Avoid using ttyS0 for MAVLink on FMUv1
- if ver hwcmp PX4FMU_V1//比较px4的版本
- then
- set FMU_MODE serial //设置FMU_MODE为serial模式
- fi
- fi
- if [ $OUTPUT_MODE == ardrone ]
- then
- set FMU_MODE gpio_serial
- fi
- if [ $HIL == yes ] //比较HIL参数设置
- then
- set OUTPUT_MODE hil
- set GPS no
- if ver hwcmp PX4FMU_V1
- then
- set FMU_MODE serial
- fi
- fi
- unset HIL
- # waypoint storage //存储路径
- # REBOOTWORK this needs to start in parallel
- if dataman start
- then
- fi
- #
- # Sensors System (start before Commander so Preflight checks are properly run)
- #//起飞前传感器检查
- sh /etc/init.d/rc.sensors//执行rc.sensors(标准的PX4FMU v1, v2, v3传感器启动脚本)
- if [ $GPS == yes ] //检查GPS和GPS_FRAK
- then
- if [ $GPS_FAKE == yes ]
- then
- echo "[i] Faking GPS"
- gps start -f
- else
- gps start
- fi
- fi
- unset GPS
- unset GPS_FAKE
- # Needs to be this early for in-air-restarts
- commander start //启动commander,类似于任务管理器
- #
- # Start primary output//以下为一系列判断,再启动如何输出
- #
- set TTYS1_BUSY no
- #
- # Check if UAVCAN is enabled, default to it for ESCs//检查UAVCAN是否使能
- #
- if param greater UAVCAN_ENABLE 2 //如果UAVCAN_ENABLE大于2
- then
- set OUTPUT_MODE uavcan_esc
- fi
- # If OUTPUT_MODE == none then something is wrong with setup and we shouldn't try to enable output
- //如果OUTPUT_MODE == none,那么有问题,不能尝试使能输出
- if [ $OUTPUT_MODE != none ]
- then
- if [ $OUTPUT_MODE == uavcan_esc ]
- then
- if param compare UAVCAN_ENABLE 0
- then
- echo "[i] OVERRIDING UAVCAN_ENABLE = 1"
- param set UAVCAN_ENABLE 1
- fi
- fi
- if [ $OUTPUT_MODE == io -o $OUTPUT_MODE == uavcan_esc ]
- then
- if px4io start
- then
- sh /etc/init.d/rc.io//执行rc.io
- else
- echo "ERROR: PX4IO start failed" >> $LOG_FILE
- tone_alarm $TUNE_ERR
- fi
- fi
- if [ $OUTPUT_MODE == fmu -o $OUTPUT_MODE == ardrone ]
- then
- if fmu mode_$FMU_MODE
- then
- echo "[i] FMU mode_$FMU_MODE started"
- else
- echo "[i] ERROR: FMU mode_$FMU_MODE start failed"
- echo "ERROR: FMU start failed" >> $LOG_FILE
- tone_alarm $TUNE_ERR
- fi
- if ver hwcmp PX4FMU_V1
- then
- if [ $FMU_MODE == pwm -o $FMU_MODE == gpio ]
- then
- set TTYS1_BUSY yes
- fi
- if [ $FMU_MODE == pwm_gpio -o $OUTPUT_MODE == ardrone ]
- then
- set TTYS1_BUSY yes
- fi
- fi
- fi
- if [ $OUTPUT_MODE == mkblctrl ]
- then
- set MKBLCTRL_ARG ""
- if [ $MKBLCTRL_MODE == x ]
- then
- set MKBLCTRL_ARG "-mkmode x"
- fi
- if [ $MKBLCTRL_MODE == + ]
- then
- set MKBLCTRL_ARG "-mkmode +"
- fi
- if mkblctrl $MKBLCTRL_ARG
- then
- echo "[i] MK started"
- else
- echo "[i] ERROR: MK start failed"
- echo "ERROR: MK start failed" >> $LOG_FILE
- tone_alarm $TUNE_ERR
- fi
- unset MKBLCTRL_ARG
- fi
- unset MK_MODE
- if [ $OUTPUT_MODE == hil ]
- then
- if pwm_out_sim mode_port2_pwm8
- then
- echo "[i] PWM SIM output started"
- else
- echo "[i] ERROR: PWM SIM output start failed"
- echo "ERROR: PWM SIM output start failed" >> $LOG_FILE
- tone_alarm $TUNE_ERR
- fi
- fi
- #
- # Start IO or FMU for RC PPM input if needed//如果需要,则启动IO和FMU接收PPM
- #
- if [ $IO_PRESENT == yes ]
- then
- if [ $OUTPUT_MODE != io ]
- then
- if px4io start
- then
- echo "[i] PX4IO started"
- sh /etc/init.d/rc.io
- else
- echo "[i] ERROR: PX4IO start failed"
- echo "ERROR: PX4IO start failed" >> $LOG_FILE
- tone_alarm $TUNE_ERR
- fi
- fi
- else
- if [ $OUTPUT_MODE != fmu -a $OUTPUT_MODE != ardrone ]
- then
- if fmu mode_$FMU_MODE
- then
- echo "[i] FMU mode_$FMU_MODE started"
- else
- echo "[i] ERROR: FMU mode_$FMU_MODE start failed"
- echo "ERROR: FMU mode_$FMU_MODE start failed" >> $LOG_FILE
- tone_alarm $TUNE_ERR
- fi
- if ver hwcmp PX4FMU_V1
- then
- if [ $FMU_MODE == pwm -o $FMU_MODE == gpio ]
- then
- set TTYS1_BUSY yes
- fi
- if [ $FMU_MODE == pwm_gpio -o $OUTPUT_MODE == ardrone ]
- then
- set TTYS1_BUSY yes
- fi
- fi
- fi
- fi
- fi
- //以下为mavlink的设置
- if [ $MAVLINK_F == default ]
- then
- # Normal mode, use baudrate 57600 (default) and data rate 1000 bytes/s
- if [ $TTYS1_BUSY == yes ]
- then
- # Start MAVLink on ttyS0, because FMU ttyS1 pins configured as something else
- set MAVLINK_F "-r 1200 -d /dev/ttyS0"
- # Exit from nsh to free port for mavlink
- set EXIT_ON_END yes
- else
- set MAVLINK_F "-r 1200"
- # Avoid using ttyS1 for MAVLink on FMUv4
- if ver hwcmp PX4FMU_V4
- then
- set MAVLINK_F "-r 1200 -d /dev/ttyS1"
- # Start MAVLink on Wifi (ESP8266 port)
- mavlink start -r 20000 -m config -b 921600 -d /dev/ttyS0
- fi
- fi
- fi
- mavlink start $MAVLINK_F
- unset MAVLINK_F
- #
- # MAVLink onboard / TELEM2
- #
- if ver hwcmp PX4FMU_V1
- then
- else
- # XXX We need a better way for runtime eval of shell variables,
- # but this works for now
- if param compare SYS_COMPANION 921600
- then
- mavlink start -d /dev/ttyS2 -b 921600 -m onboard -r 80000 -x
- fi
- if param compare SYS_COMPANION 57600
- then
- mavlink start -d /dev/ttyS2 -b 57600 -m onboard -r 5000 -x
- fi
- if param compare SYS_COMPANION 157600
- then
- mavlink start -d /dev/ttyS2 -b 57600 -m osd -r 1000
- fi
- if param compare SYS_COMPANION 257600
- then
- mavlink start -d /dev/ttyS2 -b 57600 -m magic -r 5000 -x
- fi
- if param compare SYS_COMPANION 357600
- then
- mavlink start -d /dev/ttyS2 -b 57600 -r 1000
- fi
- # Sensors on the PWM interface bank
- # clear pins 5 and 6
- if param compare SENS_EN_LL40LS 1
- then
- set AUX_MODE pwm4
- fi
- if param greater TRIG_MODE 0
- then
- # Get FMU driver out of the way
- set MIXER_AUX none
- set AUX_MODE none
- camera_trigger start
- fi
- fi
- # Transitional support: Disable safety on all Pixracer boards
- if ver hwcmp PX4FMU_V4
- then
- param set CBRK_IO_SAFETY 22027
- fi
- #
- # UAVCAN
- #
- sh /etc/init.d/rc.uavcan//执行rc.uavcan,也就是启动rc.uavcan
- #
- # Logging
- #
- sh /etc/init.d/rc.logging//执行rc.logging,也就是启动rc.logging
- #
- # Start up ARDrone Motor interface
- #
- if [ $OUTPUT_MODE == ardrone ]
- then
- ardrone_interface start -d /dev/ttyS1
- fi
- #
- # Fixed wing setup//固定翼的设置
- #
- if [ $VEHICLE_TYPE == fw ]
- then
- echo "[i] FIXED WING"
- if [ $MIXER == none ]
- then
- # Set default mixer for fixed wing if not defined
- set MIXER AERT
- fi
- if [ $MAV_TYPE == none ]
- then
- # Use MAV_TYPE = 1 (fixed wing) if not defined
- set MAV_TYPE 1
- fi
- param set MAV_TYPE $MAV_TYPE
- # Load mixer and configure outputs
- sh /etc/init.d/rc.interface//执行rc.interface,配置控制接口
- # Start standard fixedwing apps
- if [ $LOAD_DAPPS == yes ]
- then
- sh /etc/init.d/rc.fw_apps//执行rc.fw_apps,开启姿态和位置估算
- fi
- fi
- #
- # Multicopters setup//多旋翼的设置
- #
- if [ $VEHICLE_TYPE == mc ]
- then
- echo "[i] MULTICOPTER"
- if [ $MIXER == none ]
- then
- echo "Mixer undefined"
- fi
- if [ $MAV_TYPE == none ]//根据用户的选择,设置MAV_TYPE
- then
- # Use mixer to detect vehicle type
- if [ $MIXER == quad_x -o $MIXER == quad_+ ]
- then
- set MAV_TYPE 2
- fi
- if [ $MIXER == quad_w -o $MIXER == sk450_deadcat ]
- then
- set MAV_TYPE 2
- fi
- if [ $MIXER == quad_h ]
- then
- set MAV_TYPE 2
- fi
- if [ $MIXER == tri_y_yaw- -o $MIXER == tri_y_yaw+ ]
- then
- set MAV_TYPE 15
- fi
- if [ $MIXER == hexa_x -o $MIXER == hexa_+ ]
- then
- set MAV_TYPE 13
- fi
- if [ $MIXER == hexa_cox ]
- then
- set MAV_TYPE 13
- fi
- if [ $MIXER == octo_x -o $MIXER == octo_+ ]
- then
- set MAV_TYPE 14
- fi
- if [ $MIXER == octo_cox -o $MIXER == octo_cox_w ]
- then
- set MAV_TYPE 14
- fi
- fi
- # Still no MAV_TYPE found//mav的类型没找到
- if [ $MAV_TYPE == none ]
- then
- echo "Unknown MAV_TYPE"
- param set MAV_TYPE 2
- else
- param set MAV_TYPE $MAV_TYPE
- fi
- # Load mixer and configure outputs
- sh /etc/init.d/rc.interface//执行rc.interface,配置控制接口
- # Start standard multicopter apps
- if [ $LOAD_DAPPS == yes ]
- then
- sh /etc/init.d/rc.mc_apps// 执行rc.mc_apps,启动姿态位置的估计和控制
- fi
- fi
- #
- # VTOL setup//工具类型设置
- #
- if [ $VEHICLE_TYPE == vtol ]
- then
- echo "[init] Vehicle type: VTOL"
- if [ $MIXER == none ]
- then
- echo "Default mixer for vtol not defined"
- fi
- if [ $MAV_TYPE == none ]
- then
- # Use mixer to detect vehicle type
- if [ $MIXER == caipirinha_vtol ]
- then
- set MAV_TYPE 19
- fi
- if [ $MIXER == firefly6 ]
- then
- set MAV_TYPE 21
- fi
- if [ $MIXER == quad_x_pusher_vtol ]
- then
- set MAV_TYPE 22
- fi
- fi
- # Still no MAV_TYPE found
- if [ $MAV_TYPE == none ]
- then
- echo "Unknown MAV_TYPE"
- param set MAV_TYPE 19
- else
- param set MAV_TYPE $MAV_TYPE
- fi
- # Load mixer and configure outputs
- sh /etc/init.d/rc.interface//执行rc.interface,下载mixer并配置输出
- # Start standard vtol apps
- if [ $LOAD_DAPPS == yes ]
- then
- sh /etc/init.d/rc.vtol_apps//执行rc.vtol_apps,
- //启动attitude_estimator_q start、
- //position_estimator_inav start、
- //vtol_att_control start、
- //mc_att_control start、
- //mc_pos_control start、
- //fw_att_control start、
- //fw_pos_control_l1 start
- fi
- fi
- #
- # Rover setup//漫游设置
- #
- if [ $VEHICLE_TYPE == rover ]
- then
- # 10 is MAV_TYPE_GROUND_ROVER
- set MAV_TYPE 10
- # Load mixer and configure outputs
- sh /etc/init.d/rc.interface//执行rc.interface,下载mixer并配置输出
- # Start standard rover apps
- if [ $LOAD_DAPPS == yes ]
- then
- sh /etc/init.d/rc.axialracing_ax10_apps//ekf_att_pos_estimator start
- fi
- param set MAV_TYPE 10
- fi
- unset MIXER
- unset MAV_TYPE
- unset OUTPUT_MODE
- #
- # Start the navigator//启动导航
- #
- navigator start
- #
- # Generic setup (autostart ID not found) //常规设置
- #
- if [ $VEHICLE_TYPE == none ]
- then
- echo "[i] No autostart ID found"
- fi
- # Start any custom addons //启动自定义插件
- set FEXTRAS /fs/microsd/etc/extras.txt
- if [ -f $FEXTRAS ]
- then
- echo "[i] Addons script: $FEXTRAS"
- sh $FEXTRAS
- fi
- unset FEXTRAS
- # Run no SD alarm //运行没有sd卡的警告
- if [ $LOG_FILE == /dev/null ]
- then
- echo "[i] No microSD card found"
- # Play SOS
- tone_alarm error
- fi
- # End of autostart
- fi
- # There is no further script processing, so we can free some RAM
- # XXX potentially unset all script variables.
- unset TUNE_ERR
- # Boot is complete, inform MAVLink app(s) that the system is now fully up and running
- mavlink boot_complete
- # Sensors on the PWM interface bank
- if param compare SENS_EN_LL40LS 1
- then
- if pwm_input start //启动pwm输入设置
- then
- if ll40ls start pwm
- then
- fi
- fi
- fi
- if ver hwcmp PX4FMU_V4
- then
- frsky_telemetry start -d /dev/ttyS6
- fi
- if ver hwcmp PX4FMU_V2
- then
- # Check for flow sensor - as it is a background task, launch it last
- px4flow start & //如果检测到光流,则启动
- fi
- # Start USB shell if no microSD present, MAVLink else //如果没找到sd卡,则启动usb shell,
- if [ $LOG_FILE == /dev/null ] //找到了则启动mavlink
- then
- # Try to get an USB console
- nshterm /dev/ttyACM0 &
- else
- mavlink start -r 800000 -d /dev/ttyACM0 -m config -x
- fi
- if [ $EXIT_ON_END == yes ]
- then
- echo "Exit from nsh"
- exit
- fi
- unset EXIT_ON_END
rc.sensors
[cpp] view plain copy
- #!nsh
- #
- # Standard startup script for PX4FMU v1, v2, v3 onboard sensor drivers.
- #
- if ver hwcmp PX4FMU_V1 //比较px4版本
- then
- if ms5611 start
- then
- fi
- else
- if ms5611 -s start
- then
- fi
- # Blacksheep telemetry
- if bst start
- then
- fi
- fi
- if adc start
- then
- fi
- if ver hwcmp PX4FMU_V2//比较px4版本
- then
- # External I2C bus
- if hmc5883 -C -T -X start //启动hmc5883
- then
- fi
- # Internal I2C bus
- if hmc5883 -C -T -I -R 4 start
- then
- fi
- # external MPU6K is rotated 180 degrees yaw
- if mpu6000 -X -R 4 start
- then
- set BOARD_FMUV3 true
- else
- set BOARD_FMUV3 false
- fi
- if [ $BOARD_FMUV3 == true ]
- then
- # external L3GD20H is rotated 180 degrees yaw
- if l3gd20 -X -R 4 start
- then
- fi
- # external LSM303D is rotated 270 degrees yaw
- if lsm303d -X -R 6 start
- then
- fi
- # internal MPU6000 is rotated 180 deg roll, 270 deg yaw
- if mpu6000 -R 14 start
- then
- fi
- if hmc5883 -C -T -S -R 8 start
- then
- fi
- else
- # FMUv2
- if mpu6000 start
- then
- fi
- if l3gd20 start
- then
- fi
- if lsm303d start
- then
- fi
- fi
- else
- if ver hwcmp PX4FMU_V4
- then
- # External I2C bus
- if hmc5883 -C -T -X start
- then
- fi
- # Internal SPI bus is rotated 90 deg yaw
- if hmc5883 -C -T -S -R 2 start
- then
- fi
- # Internal SPI bus ICM-20608-G is rotated 90 deg yaw
- if mpu6000 -R 2 -T 20608 start
- then
- fi
- # Internal SPI bus mpu9250 is rotated 90 deg yaw
- if mpu9250 -R 2 start
- then
- fi
- else
- # FMUv1
- if mpu6000 start
- then
- fi
- if l3gd20 start
- then
- fi
- # MAG selection
- if param compare SENS_EXT_MAG 2
- then
- if hmc5883 -C -I start
- then
- fi
- else
- # Use only external as primary
- if param compare SENS_EXT_MAG 1
- then
- if hmc5883 -C -X start
- then
- fi
- else
- # auto-detect the primary, prefer external
- if hmc5883 start
- then
- fi
- fi
- fi
- fi
- fi
- if meas_airspeed start
- then
- else
- if ets_airspeed start
- then
- else
- if ets_airspeed start -b 1
- then
- fi
- fi
- fi
- if sf10a start
- then
- fi
- # Wait 20 ms for sensors (because we need to wait for the HRT and work queue callbacks to fire)
- usleep 20000
- if sensors start
- then
- fi
rc.mc_apps
[cpp] view plain copy
- #!nsh
- #
- # Standard apps for multirotors:
- # att & pos estimator, att & pos control.
- #
- # The system is defaulting to INAV_ENABLED = 1
- # but users can alternatively try the EKF-based
- # filter by setting INAV_ENABLED = 0
- //选择姿态位置估计和控制使用的算法,默认INAV_ENABLED = 1,那么
- 姿态估计 Attitude_estimator_q
- 位置估计 position_estimator_inav
- 姿态控制 mc_att_control
- 位置控制 mc_pos_control
- if param compare INAV_ENABLED 1
- then
- attitude_estimator_q start
- position_estimator_inav start
- else
- if param compare LPE_ENABLED 1
- then
- attitude_estimator_q start
- local_position_estimator start
- else
- ekf2 start
- fi
- fi
- if mc_att_control start
- then
- else
- # try the multiplatform version
- mc_att_control_m start
- fi
- if mc_pos_control start
- then
- else
- # try the multiplatform version
- mc_pos_control_m start
- fi
- #
- # Start Land Detector
- #
- land_detector start multicopter