forked from Archive/PX4-Autopilot
Merge pull request #4269 from jgoppert/mc_est_groups
Added SYS_MC_EST_GROUP to allow fine grained algorithm selection.
This commit is contained in:
commit
4666a9a4db
|
@ -4,23 +4,31 @@
|
|||
# att & pos estimator, att & pos control.
|
||||
#
|
||||
|
||||
# The system is defaulting to INAV_ENABLED = 1
|
||||
# but users can alternatively try the EKF-based
|
||||
# filter by setting INAV_ENABLED = 0
|
||||
if param compare INAV_ENABLED 1
|
||||
|
||||
#---------------------------------------
|
||||
# Estimator group selction
|
||||
#
|
||||
# INAV
|
||||
if param compare SYS_MC_EST_GROUP 0
|
||||
then
|
||||
attitude_estimator_q start
|
||||
position_estimator_inav start
|
||||
else
|
||||
if param compare LPE_ENABLED 1
|
||||
then
|
||||
attitude_estimator_q start
|
||||
local_position_estimator start
|
||||
else
|
||||
ekf2 start
|
||||
fi
|
||||
fi
|
||||
|
||||
# LPE
|
||||
if param compare SYS_MC_EST_GROUP 1
|
||||
then
|
||||
attitude_estimator_q start
|
||||
local_position_estimator start
|
||||
fi
|
||||
|
||||
# EKF
|
||||
if param compare SYS_MC_EST_GROUP 2
|
||||
then
|
||||
ekf2 start
|
||||
fi
|
||||
#---------------------------------------
|
||||
|
||||
if mc_att_control start
|
||||
then
|
||||
else
|
||||
|
|
|
@ -3,24 +3,34 @@
|
|||
# Standard apps for vtol:
|
||||
# att & pos estimator, att & pos control.
|
||||
#
|
||||
#
|
||||
|
||||
# The system is defaulting to INAV_ENABLED = 1
|
||||
# but users can alternatively try the EKF-based
|
||||
# filter by setting INAV_ENABLED = 0
|
||||
if param compare INAV_ENABLED 1
|
||||
|
||||
#---------------------------------------
|
||||
# Estimator group selction
|
||||
#
|
||||
# INAV
|
||||
if param compare SYS_MC_EST_GROUP 0
|
||||
then
|
||||
attitude_estimator_q start
|
||||
position_estimator_inav start
|
||||
else
|
||||
if param compare LPE_ENABLED 1
|
||||
then
|
||||
attitude_estimator_q start
|
||||
local_position_estimator start
|
||||
else
|
||||
ekf2 start
|
||||
fi
|
||||
fi
|
||||
|
||||
# LPE
|
||||
if param compare SYS_MC_EST_GROUP 1
|
||||
then
|
||||
attitude_estimator_q start
|
||||
local_position_estimator start
|
||||
fi
|
||||
|
||||
# EKF
|
||||
if param compare SYS_MC_EST_GROUP 2
|
||||
then
|
||||
ekf2 start
|
||||
fi
|
||||
#---------------------------------------
|
||||
|
||||
|
||||
vtol_att_control start
|
||||
mc_att_control start
|
||||
mc_pos_control start
|
||||
|
|
|
@ -345,18 +345,6 @@ PARAM_DEFINE_FLOAT(INAV_LIDAR_OFF, 0.0f);
|
|||
*/
|
||||
PARAM_DEFINE_INT32(CBRK_NO_VISION, 0);
|
||||
|
||||
/**
|
||||
* INAV enabled
|
||||
*
|
||||
* If set to 1, use INAV for position estimation.
|
||||
* Else the system uses the combined attitude / position
|
||||
* filter framework.
|
||||
*
|
||||
* @boolean
|
||||
* @group Position Estimator INAV
|
||||
*/
|
||||
PARAM_DEFINE_INT32(INAV_ENABLED, 1);
|
||||
|
||||
int inav_parameters_init(struct position_estimator_inav_param_handles *h)
|
||||
{
|
||||
h->w_z_baro = param_find("INAV_W_Z_BARO");
|
||||
|
|
|
@ -682,7 +682,7 @@ Sensors::Sensors() :
|
|||
(void)param_find("PWM_AUX_DISARMED");
|
||||
(void)param_find("TRIG_MODE");
|
||||
(void)param_find("UAVCAN_ENABLE");
|
||||
(void)param_find("LPE_ENABLED");
|
||||
(void)param_find("SYS_MC_EST_GROUP");
|
||||
|
||||
/* fetch initial parameter values */
|
||||
parameters_update();
|
||||
|
|
|
@ -82,6 +82,22 @@ PARAM_DEFINE_INT32(SYS_USE_IO, 1);
|
|||
*/
|
||||
PARAM_DEFINE_INT32(SYS_RESTART_TYPE, 2);
|
||||
|
||||
/**
|
||||
* Set multicopter estimator group
|
||||
*
|
||||
* Set the group of estimators used for multicopters and vtols
|
||||
*
|
||||
* @value 0 position_estimator_inav, attitude_estimator_q
|
||||
* @value 1 local_position_estimator, attitude_estimator_q
|
||||
* @value 2 ekf2
|
||||
*
|
||||
* @min 0
|
||||
* @max 2
|
||||
* @reboot_required true
|
||||
* @group System
|
||||
*/
|
||||
PARAM_DEFINE_INT32(SYS_MC_EST_GROUP, 0);
|
||||
|
||||
/**
|
||||
* Companion computer interface
|
||||
*
|
||||
|
|
Loading…
Reference in New Issue