px4-firmware/ROMFS/px4fmu_common/init.d/rc.mc_apps

50 lines
731 B
Plaintext
Raw Normal View History

#!nsh
#
# Standard apps for multirotors:
# att & pos estimator, att & pos control.
#
#---------------------------------------
# Estimator group selction
#
# INAV
if param compare SYS_MC_EST_GROUP 0
2015-03-01 13:05:22 -04:00
then
2015-10-03 07:48:51 -03:00
attitude_estimator_q start
2015-03-01 13:05:22 -04:00
position_estimator_inav start
fi
# LPE
if param compare SYS_MC_EST_GROUP 1
then
attitude_estimator_q start
local_position_estimator start
fi
# EKF
if param compare SYS_MC_EST_GROUP 2
then
ekf2 start
fi
#---------------------------------------
2015-01-09 04:15:48 -04:00
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