SYS_MC_EST_GROUP mark LPE unsupported and update airframes (#11925)

This commit is contained in:
Daniel Agar
2019-04-29 11:50:36 -04:00
committed by GitHub
parent 2142459027
commit f032d0d9fc
17 changed files with 20 additions and 74 deletions
@@ -56,7 +56,6 @@ then
param set RTL_RETURN_ALT 30
param set SDLOG_DIRS_MAX 7
param set SYS_MC_EST_GROUP 2
param set SYS_RESTART_TYPE 2
param set VT_F_TRANS_THR 0.75
-8
View File
@@ -5,14 +5,6 @@
# NOTE: Script variables are declared/initialized/unset in the rcS script.
#
# LPE
if param compare SYS_MC_EST_GROUP 1
then
echo "ERROR [init] Estimator LPE not supported on fixed wing. Using EKF2"
param set SYS_MC_EST_GROUP 2
param save
fi
#
# Start the attitude and position estimator.
#
+8 -17
View File
@@ -9,16 +9,6 @@
# Begin Estimator Group Selection #
###############################################################################
#
# INAV (deprecated).
#
if param compare SYS_MC_EST_GROUP 0
then
echo "ERROR [init] Estimator INAV deprecated. Using EKF2"
param set SYS_MC_EST_GROUP 2
param save
fi
#
# LPE
#
@@ -30,21 +20,22 @@ then
#
if attitude_estimator_q start
then
echo "WARN [init] Estimator LPE unsupported, EKF2 recommended."
local_position_estimator start
else
echo "ERROR [init] Estimator LPE not available. Using EKF2"
param set SYS_MC_EST_GROUP 2
param save
reboot
fi
fi
#
# EKF2
#
if param compare SYS_MC_EST_GROUP 2
then
else
#
# EKF2
#
param set SYS_MC_EST_GROUP 2
ekf2 start
fi
###############################################################################
# End Estimator Group Selection #
###############################################################################
+1 -28
View File
@@ -9,34 +9,7 @@
# Begin Estimator group selection #
###############################################################################
# INAV (deprecated)
if param compare SYS_MC_EST_GROUP 0
then
echo "ERROR [init] Estimator INAV deprecated. Using EKF2"
param set SYS_MC_EST_GROUP 2
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 px4_fmu-v2 due to a limited flash.
if attitude_estimator_q start
then
local_position_estimator start
else
echo "ERROR [init] Estimator LPE not available. Using EKF2"
param set SYS_MC_EST_GROUP 2
param save
fi
fi
# EKF
if param compare SYS_MC_EST_GROUP 2
then
ekf2 start
fi
ekf2 start
###############################################################################
# End Estimator group selection #