ROMFS: Reset the estimator param to EKF2 if LPE fails to start

This commit is contained in:
Lorenz Meier 2017-06-04 12:43:28 +02:00
parent 69ba69f30c
commit c9a28fc0eb
3 changed files with 20 additions and 5 deletions

View File

@ -3,6 +3,15 @@
# Standard apps for fixed wing
#
# 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
ekf2 start
fi
#
# Start the attitude and position estimator
#

View File

@ -11,8 +11,8 @@
# 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
echo "ERROR [init] Estimator INAV deprecated. Using EKF2"
param set SYS_MC_EST_GROUP 2
param save
fi
@ -25,6 +25,9 @@ then
then
local_position_estimator start
else
echo "ERROR [init] Estimator LPE not available. Using EKF2"
param set SYS_MC_EST_GROUP 2
param save
ekf2 start
fi
fi

View File

@ -12,8 +12,8 @@
# 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
echo "ERROR [init] Estimator INAV deprecated. Using EKF2"
param set SYS_MC_EST_GROUP 2
param save
fi
@ -21,11 +21,14 @@ fi
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.
# Unfortunately we do not build it on px4fmu-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
ekf2 start
fi
fi