mirror of
https://gitee.com/mirrors_PX4/PX4-Autopilot.git
synced 2026-05-02 05:04:08 +08:00
- ekf2 can now run in multi-instance mode (currently up to 9 instances)
- in multi mode all estimates are published to alternate topics (eg estimator_attitude instead of vehicle_attitude)
- new ekf2 selector runs in multi-instance mode to monitor and compare all instances, selecting a primary (eg N x estimator_attitude => vehicle_attitude)
- sensors module accel & gyro inconsistency checks are now relative to the mean of all instances, rather than the current primary (when active ekf2 selector is responsible for choosing primary accel & gyro)
- existing consumers of estimator_status must check estimator_selector_status to select current primary instance status
- ekf2 single instance mode is still fully supported and the default
Co-authored-by: Paul Riseborough <gncsolns@gmail.com>
60 lines
1.4 KiB
Bash
60 lines
1.4 KiB
Bash
#!/bin/sh
|
|
#
|
|
# Standard apps for airships. Attitude/Position estimator, Attitude/Position control.
|
|
#
|
|
# NOTE: Script variables are declared/initialized/unset in the rcS script.
|
|
#
|
|
|
|
###############################################################################
|
|
# Begin Estimator Group Selection #
|
|
###############################################################################
|
|
|
|
#
|
|
# 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
|
|
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
|
|
|
|
###############################################################################
|
|
# End Estimator Group Selection #
|
|
###############################################################################
|
|
|
|
#
|
|
# Start Airship Attitude Controller.
|
|
#
|
|
airship_att_control start
|
|
|
|
#
|
|
# Start Land Detector.
|
|
#
|
|
land_detector start airship
|