mirror of
https://github.com/PX4/PX4-Autopilot.git
synced 2026-05-23 14:47:44 +08:00
use LPE estimator
This commit is contained in:
committed by
Lorenz Meier
parent
6c839f9b02
commit
42439829b0
@@ -8,4 +8,35 @@
|
||||
#
|
||||
# Start the attitude and position estimator.
|
||||
#
|
||||
ekf2 start &
|
||||
|
||||
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
|
||||
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
|
||||
else
|
||||
#
|
||||
# Q estimator (attitude estimation only)
|
||||
#
|
||||
if param compare SYS_MC_EST_GROUP 3
|
||||
then
|
||||
attitude_estimator_q start
|
||||
else
|
||||
#
|
||||
# EKF2
|
||||
#
|
||||
param set SYS_MC_EST_GROUP 2
|
||||
ekf2 start &
|
||||
fi
|
||||
fi
|
||||
|
||||
@@ -16,4 +16,5 @@ then
|
||||
# FW takeoff acceleration can easily exceed ublox GPS 2G default.
|
||||
#
|
||||
param set GPS_UBX_DYNMODEL 8
|
||||
param set SYS_MC_EST_GROUP 1
|
||||
fi
|
||||
|
||||
Reference in New Issue
Block a user