forked from Archive/PX4-Autopilot
47 lines
803 B
Plaintext
47 lines
803 B
Plaintext
#!nsh
|
|
#
|
|
# Standard apps for multirotors:
|
|
# att & pos estimator, att & pos control.
|
|
#
|
|
|
|
|
|
#---------------------------------------
|
|
# Estimator group selction
|
|
#
|
|
# INAV (deprecated)
|
|
if param compare SYS_MC_EST_GROUP 0
|
|
then
|
|
echo "ERROR [init] Estimator INAV deprecated. Using LPE"
|
|
param set SYS_MC_EST_GROUP 1
|
|
param save
|
|
fi
|
|
|
|
# LPE
|
|
if param compare SYS_MC_EST_GROUP 1
|
|
then
|
|
# Try to start LPE. If it fails, start EKF2 as a default
|
|
# Unfortunately we do not build it on px4fmu-v2 duo to a limited flash.
|
|
if attitude_estimator_q start
|
|
then
|
|
local_position_estimator start
|
|
else
|
|
ekf2 start
|
|
fi
|
|
fi
|
|
|
|
# EKF
|
|
if param compare SYS_MC_EST_GROUP 2
|
|
then
|
|
ekf2 start
|
|
fi
|
|
#---------------------------------------
|
|
|
|
mc_att_control start
|
|
|
|
mc_pos_control start
|
|
|
|
#
|
|
# Start Land Detector
|
|
#
|
|
land_detector start multicopter
|