forked from Archive/PX4-Autopilot
ekf2: remove all remaining uses of EKF2_AID_MASK
This commit is contained in:
parent
98a8d080b6
commit
521abecbbf
|
@ -30,10 +30,10 @@ param set-default PWM_MAIN_FUNC3 103
|
|||
param set-default PWM_MAIN_FUNC4 104
|
||||
|
||||
# EKF2
|
||||
param set-default EKF2_AID_MASK 2
|
||||
param set-default EKF2_GPS_CTRL 0
|
||||
param set-default EKF2_EVP_NOISE 0.05
|
||||
param set-default EKF2_EVA_NOISE 0.05
|
||||
param set-default EKF2_OF_CTRL 1
|
||||
|
||||
# LPE: Flow-only mode
|
||||
param set-default LPE_FUSION 242
|
||||
|
|
|
@ -30,8 +30,8 @@ param set-default PWM_MAIN_FUNC3 103
|
|||
param set-default PWM_MAIN_FUNC4 104
|
||||
|
||||
# EKF2
|
||||
param set-default EKF2_AID_MASK 2
|
||||
param set-default EKF2_GPS_CTRL 0
|
||||
param set-default EKF2_OF_CTRL 1
|
||||
|
||||
# LPE: Flow-only mode
|
||||
param set-default LPE_FUSION 242
|
||||
|
|
|
@ -23,11 +23,12 @@ param set-default COM_OBS_AVOID 0
|
|||
param set-default COM_DISARM_LAND 0.5
|
||||
|
||||
# EKF2 parameters
|
||||
param set-default EKF2_AID_MASK 35
|
||||
param set-default EKF2_DRAG_CTRL 1
|
||||
param set-default EKF2_IMU_POS_X 0.02
|
||||
param set-default EKF2_GPS_POS_X 0.055
|
||||
param set-default EKF2_GPS_POS_Z -0.15
|
||||
param set-default EKF2_MIN_RNG 0.03
|
||||
param set-default EKF2_OF_CTRL 1
|
||||
param set-default EKF2_OF_POS_X 0.055
|
||||
param set-default EKF2_OF_POS_Y 0.02
|
||||
param set-default EKF2_OF_POS_Z 0.065
|
||||
|
|
|
@ -16,11 +16,12 @@ param set-default COM_OBS_AVOID 1
|
|||
param set-default COM_DISARM_LAND 0.5
|
||||
|
||||
# EKF2 parameters
|
||||
param set-default EKF2_AID_MASK 35
|
||||
param set-default EKF2_DRAG_CTRL 1
|
||||
param set-default EKF2_IMU_POS_X 0.02
|
||||
param set-default EKF2_GPS_POS_X 0.055
|
||||
param set-default EKF2_GPS_POS_Z -0.15
|
||||
param set-default EKF2_MIN_RNG 0.03
|
||||
param set-default EKF2_OF_CTRL 1
|
||||
param set-default EKF2_OF_POS_X 0.055
|
||||
param set-default EKF2_OF_POS_Y 0.02
|
||||
param set-default EKF2_OF_POS_Z 0.065
|
||||
|
|
|
@ -16,11 +16,12 @@ param set-default COM_OBS_AVOID 1
|
|||
param set-default COM_DISARM_LAND 0.5
|
||||
|
||||
# EKF2 parameters
|
||||
param set-default EKF2_AID_MASK 35
|
||||
param set-default EKF2_DRAG_CTRL 1
|
||||
param set-default EKF2_IMU_POS_X 0.02
|
||||
param set-default EKF2_GPS_POS_X 0.055
|
||||
param set-default EKF2_GPS_POS_Z -0.15
|
||||
param set-default EKF2_MIN_RNG 0.03
|
||||
param set-default EKF2_OF_CTRL 1
|
||||
param set-default EKF2_OF_POS_X 0.055
|
||||
param set-default EKF2_OF_POS_Y 0.02
|
||||
param set-default EKF2_OF_POS_Z 0.065
|
||||
|
|
|
@ -37,13 +37,14 @@ param set-default COM_RC_LOSS_T 3
|
|||
|
||||
|
||||
# ekf2
|
||||
param set-default EKF2_AID_MASK 33
|
||||
param set-default EKF2_TERR_MASK 1
|
||||
param set-default EKF2_BARO_NOISE 2.0
|
||||
|
||||
param set-default EKF2_BCOEF_X 31.5
|
||||
param set-default EKF2_BCOEF_Y 25.5
|
||||
|
||||
param set-default EKF2_DRAG_CTRL 1
|
||||
|
||||
param set-default EKF2_GPS_DELAY 100
|
||||
param set-default EKF2_GPS_POS_X 0.06
|
||||
param set-default EKF2_GPS_V_NOISE 0.5
|
||||
|
|
|
@ -37,11 +37,11 @@ param set-default SENS_TFMINI_CFG 103
|
|||
param set-default SENS_EN_BATT 1
|
||||
|
||||
# EKF2
|
||||
param set-default EKF2_AID_MASK 3
|
||||
param set-default EKF2_GND_EFF_DZ 6
|
||||
param set-default EKF2_MIN_RNG 0.3
|
||||
|
||||
# Flow
|
||||
param set-default EKF2_OF_CTRL 1
|
||||
param set-default EKF2_OF_QMIN 70
|
||||
|
||||
# Position control
|
||||
|
|
|
@ -24,10 +24,10 @@ param set-default CBRK_SUPPLY_CHK 894281
|
|||
param set-default COM_RC_IN_MODE 1
|
||||
|
||||
param set-default EKF2_ABL_LIM 2
|
||||
param set-default EKF2_AID_MASK 3
|
||||
param set-default EKF2_HGT_REF 2
|
||||
param set-default EKF2_RNG_CTRL 2
|
||||
param set-default EKF2_MAG_TYPE 1
|
||||
param set-default EKF2_OF_CTRL 1
|
||||
param set-default EKF2_OF_DELAY 10
|
||||
|
||||
param set-default IMU_GYRO_CUTOFF 100
|
||||
|
|
|
@ -19,7 +19,7 @@
|
|||
|
||||
param set-default SYS_MC_EST_GROUP 2
|
||||
param set-default SYS_HAS_MAG 0
|
||||
param set-default EKF2_AID_MASK 2
|
||||
param set-default EKF2_OF_CTRL 1
|
||||
param set-default EKF2_GPS_CTRL 0
|
||||
param set-default EKF2_MAG_TYPE 5
|
||||
|
||||
|
|
|
@ -12,8 +12,9 @@ param set IMU_GYRO_RATEMAX 800
|
|||
param set EKF2_IMU_POS_X 0.027
|
||||
param set EKF2_IMU_POS_Y 0.009
|
||||
param set EKF2_IMU_POS_Z -0.019
|
||||
param set EKF2_EV_CTRL 15
|
||||
param set EKF2_EV_DELAY 5
|
||||
param set EKF2_AID_MASK 280
|
||||
param set EKF2_GPS_CTRL 0
|
||||
param set EKF2_ABL_LIM 0.8
|
||||
param set EKF2_TAU_POS 0.25
|
||||
param set EKF2_TAU_VEL 0.25
|
||||
|
|
|
@ -105,7 +105,7 @@ enum MagFuseType : uint8_t {
|
|||
MAG_3D = 2, ///< Magnetometer 3-axis fusion will always be used. This is more accurate, but more affected by localised earth field distortions
|
||||
UNUSED = 3, ///< Not implemented
|
||||
INDOOR = 4, ///< The same as option 0, but magnetometer or yaw fusion will not be used unless earth frame external aiding (GPS or External Vision) is being used. This prevents inconsistent magnetic fields associated with indoor operation degrading state estimates.
|
||||
NONE = 5 ///< Do not use magnetometer under any circumstance. Other sources of yaw may be used if selected via the EKF2_AID_MASK parameter.
|
||||
NONE = 5 ///< Do not use magnetometer under any circumstance..
|
||||
};
|
||||
|
||||
#if defined(CONFIG_EKF2_RANGE_FINDER)
|
||||
|
@ -155,19 +155,6 @@ enum class EvCtrl : uint8_t {
|
|||
YAW = (1<<3)
|
||||
};
|
||||
|
||||
enum SensorFusionMask : uint16_t {
|
||||
// Bit locations for fusion_mode
|
||||
DEPRECATED_USE_GPS = (1<<0), ///< set to true to use GPS data (DEPRECATED, use gnss_ctrl)
|
||||
DEPRECATED_USE_OPT_FLOW = (1<<1), ///< set to true to use optical flow data
|
||||
DEPRECATED_INHIBIT_ACC_BIAS = (1<<2), ///< set to true to inhibit estimation of accelerometer delta velocity bias
|
||||
DEPRECATED_USE_EXT_VIS_POS = (1<<3), ///< set to true to use external vision position data
|
||||
DEPRECATED_USE_EXT_VIS_YAW = (1<<4), ///< set to true to use external vision quaternion data for yaw
|
||||
DEPRECATED_USE_DRAG = (1<<5), ///< set to true to use the multi-rotor drag model to estimate wind
|
||||
DEPRECATED_ROTATE_EXT_VIS = (1<<6), ///< set to true to if the EV observations are in a non NED reference frame and need to be rotated before being used
|
||||
DEPRECATED_USE_GPS_YAW = (1<<7), ///< set to true to use GPS yaw data if available (DEPRECATED, use gnss_ctrl)
|
||||
DEPRECATED_USE_EXT_VIS_VEL = (1<<8), ///< set to true to use external vision velocity data
|
||||
};
|
||||
|
||||
struct gpsMessage {
|
||||
uint64_t time_usec{};
|
||||
int32_t lat{}; ///< Latitude in 1E-7 degrees
|
||||
|
@ -297,7 +284,6 @@ struct parameters {
|
|||
int32_t imu_ctrl{static_cast<int32_t>(ImuCtrl::GyroBias) | static_cast<int32_t>(ImuCtrl::AccelBias)};
|
||||
|
||||
// measurement source control
|
||||
int32_t fusion_mode{}; ///< bitmasked integer that selects some aiding sources
|
||||
int32_t height_sensor_ref{HeightSensor::BARO};
|
||||
int32_t position_sensor_ref{static_cast<int32_t>(PositionSensor::GNSS)};
|
||||
int32_t baro_ctrl{1};
|
||||
|
|
|
@ -110,7 +110,6 @@ EKF2::EKF2(bool multi_mode, const px4::wq_config_t &config, bool replay_mode):
|
|||
_param_ekf2_req_pdop(_params->req_pdop),
|
||||
_param_ekf2_req_hdrift(_params->req_hdrift),
|
||||
_param_ekf2_req_vdrift(_params->req_vdrift),
|
||||
_param_ekf2_aid_mask(_params->fusion_mode),
|
||||
_param_ekf2_hgt_ref(_params->height_sensor_ref),
|
||||
_param_ekf2_baro_ctrl(_params->baro_ctrl),
|
||||
_param_ekf2_gps_ctrl(_params->gnss_ctrl),
|
||||
|
|
|
@ -144,6 +144,19 @@ public:
|
|||
int instance() const { return _instance; }
|
||||
|
||||
private:
|
||||
//TODO: remove after 1.14 release
|
||||
enum SensorFusionMask : uint16_t {
|
||||
// Bit locations for fusion_mode
|
||||
DEPRECATED_USE_GPS = (1 << 0), ///< set to true to use GPS data (DEPRECATED, use gnss_ctrl)
|
||||
DEPRECATED_USE_OPT_FLOW = (1 << 1), ///< set to true to use optical flow data
|
||||
DEPRECATED_INHIBIT_ACC_BIAS = (1 << 2), ///< set to true to inhibit estimation of accelerometer delta velocity bias
|
||||
DEPRECATED_USE_EXT_VIS_POS = (1 << 3), ///< set to true to use external vision position data
|
||||
DEPRECATED_USE_EXT_VIS_YAW = (1 << 4), ///< set to true to use external vision quaternion data for yaw
|
||||
DEPRECATED_USE_DRAG = (1 << 5), ///< set to true to use the multi-rotor drag model to estimate wind
|
||||
DEPRECATED_ROTATE_EXT_VIS = (1 << 6), ///< set to true to if the EV observations are in a non NED reference frame and need to be rotated before being used
|
||||
DEPRECATED_USE_GPS_YAW = (1 << 7), ///< set to true to use GPS yaw data if available (DEPRECATED, use gnss_ctrl)
|
||||
DEPRECATED_USE_EXT_VIS_VEL = (1 << 8), ///< set to true to use external vision velocity data
|
||||
};
|
||||
|
||||
static constexpr uint8_t MAX_NUM_IMUS = 4;
|
||||
static constexpr uint8_t MAX_NUM_MAGS = 4;
|
||||
|
@ -561,7 +574,7 @@ private:
|
|||
(ParamExtFloat<px4::params::EKF2_REQ_VDRIFT>) _param_ekf2_req_vdrift, ///< maximum acceptable vertical drift speed (m/s)
|
||||
|
||||
// measurement source control
|
||||
(ParamExtInt<px4::params::EKF2_AID_MASK>)
|
||||
(ParamInt<px4::params::EKF2_AID_MASK>)
|
||||
_param_ekf2_aid_mask, ///< bitmasked integer that selects which of the GPS and optical flow aiding sources will be used
|
||||
(ParamExtInt<px4::params::EKF2_HGT_REF>) _param_ekf2_hgt_ref, ///< selects the primary source for height data
|
||||
(ParamExtInt<px4::params::EKF2_BARO_CTRL>) _param_ekf2_baro_ctrl,///< barometer control selection
|
||||
|
|
|
@ -496,7 +496,7 @@ PARAM_DEFINE_INT32(EKF2_DECL_TYPE, 7);
|
|||
* If set to '3-axis' 3-axis field fusion is used at all times.
|
||||
* If set to 'VTOL custom' the behaviour is the same as 'Automatic', but if fusing airspeed, magnetometer fusion is only allowed to modify the magnetic field states. This can be used by VTOL platforms with large magnetic field disturbances to prevent incorrect bias states being learned during forward flight operation which can adversely affect estimation accuracy after transition to hovering flight.
|
||||
* If set to 'MC custom' the behaviour is the same as 'Automatic, but if there are no earth frame position or velocity observations being used, the magnetometer will not be used. This enables vehicles to operate with no GPS in environments where the magnetic field cannot be used to provide a heading reference. Prior to flight, the yaw angle is assumed to be constant if movement tests indicate that the vehicle is static. This allows the vehicle to be placed on the ground to learn the yaw gyro bias prior to flight.
|
||||
* If set to 'None' the magnetometer will not be used under any circumstance. If no external source of yaw is available, it is possible to use post-takeoff horizontal movement combined with GPS velocity measurements to align the yaw angle with the timer required (depending on the amount of movement and GPS data quality). Other external sources of yaw may be used if selected via the EKF2_AID_MASK parameter.
|
||||
* If set to 'None' the magnetometer will not be used under any circumstance. If no external source of yaw is available, it is possible to use post-takeoff horizontal movement combined with GPS velocity measurements to align the yaw angle with the timer required (depending on the amount of movement and GPS data quality).
|
||||
* @group EKF2
|
||||
* @value 0 Automatic
|
||||
* @value 1 Magnetic heading
|
||||
|
@ -610,7 +610,7 @@ PARAM_DEFINE_FLOAT(EKF2_GPS_V_GATE, 5.0f);
|
|||
PARAM_DEFINE_FLOAT(EKF2_TAS_GATE, 3.0f);
|
||||
|
||||
/**
|
||||
* Integer bitmask controlling data fusion and aiding methods.
|
||||
* Will be removed after v1.14 release
|
||||
*
|
||||
* Set bits in the following positions to enable:
|
||||
* 0 : Deprecated, use EKF2_GPS_CTRL instead
|
||||
|
|
Loading…
Reference in New Issue