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
No known key found for this signature in database
GPG Key ID: 4AEE18F83AFDEB23
17 changed files with 20 additions and 74 deletions

View File

@ -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

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.
#

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 #
###############################################################################

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 #

View File

@ -33,9 +33,6 @@ param set MAV_BROADCAST 1
# MAV_TYPE: 1 Fixed wing aircraft, 2 Quadrotor
param set MAV_TYPE 2
# Set multicopter estimator group, 1 local_position_estimator, attitude_estimator_q, 2 ekf2
param set SYS_MC_EST_GROUP 2
# Three possible main power battery sources for BBBlue:
# 1. onboard 2S LiPo battery connector, which is connect to ADC channel 6
# 2. onboard 9-18V DC Jack, which is connect to ADC channel 5. This is the board default.

View File

@ -33,9 +33,6 @@ param set MAV_BROADCAST 1
# MAV_TYPE: 1 Fixed wing aircraft, 2 Quadrotor
param set MAV_TYPE 2
# Set multicopter estimator group, 1 local_position_estimator, attitude_estimator_q, 2 ekf2
param set SYS_MC_EST_GROUP 2
# Three possible main power battery sources for BBBlue:
# 1. onboard 2S LiPo battery connector, which is connect to ADC channel 6
# 2. onboard 9-18V DC Jack, which is connect to ADC channel 5. This is the board default.

View File

@ -36,8 +36,6 @@ param set MC_PITCHRATE_I 0.8
param set MC_PITCHRATE_D 0.0
param set MC_PR_INT_LIM 0.5
param set SYS_MC_EST_GROUP 2
df_ms5607_wrapper start
df_mpu6050_wrapper start -R 8
df_ak8963_wrapper start -R 32

View File

@ -23,7 +23,6 @@ param set UART_ESC_MOTOR1 4
param set UART_ESC_MOTOR2 2
param set UART_ESC_MOTOR3 1
param set UART_ESC_MOTOR4 3
param set SYS_MC_EST_GROUP 2
sleep 1
df_mpu9250_wrapper start
df_bmp280_wrapper start

View File

@ -23,7 +23,6 @@ param set UART_ESC_MOTOR1 4
param set UART_ESC_MOTOR2 2
param set UART_ESC_MOTOR3 1
param set UART_ESC_MOTOR4 3
param set SYS_MC_EST_GROUP 2
sleep 1
df_mpu9250_wrapper start
df_bmp280_wrapper start

View File

@ -1,7 +1,6 @@
uorb start
qshell start
param set SYS_AUTOSTART 4001
param set SYS_MC_EST_GROUP 2
sleep 1
gps start -d /dev/tty-4
param set MAV_TYPE 2

View File

@ -37,7 +37,6 @@ param set MC_ROLLRATE_P 0.03
param set ATT_W_ACC 0.0002
param set ATT_W_MAG 0.002
param set ATT_W_GYRO_BIAS 0.05
param set SYS_MC_EST_GROUP 0
sleep 1
commander start -hil
sensors start

View File

@ -14,7 +14,6 @@ param set SYS_AUTOSTART 4001
param set MAV_BROADCAST 1
param set MAV_TYPE 2
param set MAV_SYS_ID 1
param set SYS_MC_EST_GROUP 2
df_mpu9250_wrapper start_without_mag -R 10
df_hmc5883_wrapper start -D /dev/i2c-4

View File

@ -12,7 +12,6 @@ fi
param set SYS_AUTOSTART 4001
param set MAV_BROADCAST 1
param set MAV_TYPE 2
param set SYS_MC_EST_GROUP 2
param set BAT_CNT_V_VOLT 0.001
param set BAT_V_DIV 10.9176300578
param set BAT_CNT_V_CURR 0.001

View File

@ -10,7 +10,6 @@ param load
param set MAV_BROADCAST 1
param set SYS_AUTOSTART 2100
param set MAV_TYPE 1
param set SYS_MC_EST_GROUP 2
param set BAT_CNT_V_VOLT 0.001
param set BAT_V_DIV 10.9176300578

View File

@ -12,7 +12,6 @@ param load
param set SYS_AUTOSTART 1001
param set MAV_BROADCAST 1
param set MAV_TYPE 2
param set SYS_MC_EST_GROUP 0
dataman start
sensors start -hil
commander start -hil

View File

@ -100,8 +100,8 @@ PARAM_DEFINE_INT32(SYS_RESTART_TYPE, 2);
*
* Set the group of estimators used for multicopters and VTOLs
*
* @value 1 local_position_estimator, attitude_estimator_q
* @value 2 ekf2
* @value 1 local_position_estimator, attitude_estimator_q (unsupported)
* @value 2 ekf2 (recommended)
*
* @min 1
* @max 2

View File

@ -925,8 +925,15 @@ bool preflightCheck(orb_advert_t *mavlink_log_pub, vehicle_status_s &status,
/* ---- Navigation EKF ---- */
// only check EKF2 data if EKF2 is selected as the estimator and GNSS checking is enabled
int32_t estimator_type;
param_get(param_find("SYS_MC_EST_GROUP"), &estimator_type);
int32_t estimator_type = -1;
if (status.is_rotary_wing && !status.is_vtol) {
param_get(param_find("SYS_MC_EST_GROUP"), &estimator_type);
} else {
// EKF2 is currently the only supported option for FW & VTOL
estimator_type = 2;
}
if (estimator_type == 2) {
// don't report ekf failures for the first 10 seconds to allow time for the filter to start