ekf2: purge remaining EKF2_AID_MASK references

This commit is contained in:
Daniel Agar 2023-11-15 15:55:27 -05:00 committed by Mathieu Bresciani
parent e90e8ae0ea
commit 3b2d766573
3 changed files with 1 additions and 162 deletions

View File

@ -821,19 +821,6 @@ void EKF2::VerifyParams()
{
#if defined(CONFIG_EKF2_GNSS)
if ((_param_ekf2_aid_mask.get() & SensorFusionMask::DEPRECATED_USE_GPS)
|| (_param_ekf2_aid_mask.get() & SensorFusionMask::DEPRECATED_USE_GPS_YAW)) {
_param_ekf2_aid_mask.set(_param_ekf2_aid_mask.get() & ~(SensorFusionMask::DEPRECATED_USE_GPS |
SensorFusionMask::DEPRECATED_USE_GPS_YAW));
_param_ekf2_aid_mask.commit();
mavlink_log_critical(&_mavlink_log_pub, "Use EKF2_GPS_CTRL instead\n");
/* EVENT
* @description <param>EKF2_AID_MASK</param> is set to {1:.0}.
*/
events::send<float>(events::ID("ekf2_aid_mask_gps"), events::Log::Warning,
"Use EKF2_GPS_CTRL instead", _param_ekf2_aid_mask.get());
}
if ((_param_ekf2_gps_ctrl.get() & GnssCtrl::VPOS) && !(_param_ekf2_gps_ctrl.get() & GnssCtrl::HPOS)) {
_param_ekf2_gps_ctrl.set(_param_ekf2_gps_ctrl.get() & ~GnssCtrl::VPOS);
_param_ekf2_gps_ctrl.commit();
@ -906,110 +893,8 @@ void EKF2::VerifyParams()
"EV vertical position enabled by EKF2_HGT_REF", _param_ekf2_ev_ctrl.get());
}
// EV EKF2_AID_MASK -> EKF2_EV_CTRL
if ((_param_ekf2_aid_mask.get() & SensorFusionMask::DEPRECATED_USE_EXT_VIS_VEL)
|| (_param_ekf2_aid_mask.get() & SensorFusionMask::DEPRECATED_USE_EXT_VIS_POS)
|| (_param_ekf2_aid_mask.get() & SensorFusionMask::DEPRECATED_USE_EXT_VIS_YAW)
) {
// EKF2_EV_CTRL set VEL bit
if ((_param_ekf2_aid_mask.get() & SensorFusionMask::DEPRECATED_USE_EXT_VIS_VEL)) {
_param_ekf2_ev_ctrl.set(_param_ekf2_ev_ctrl.get() | static_cast<int32_t>(EvCtrl::VEL));
}
// EKF2_EV_CTRL set HPOS/VPOS bits
if ((_param_ekf2_aid_mask.get() & SensorFusionMask::DEPRECATED_USE_EXT_VIS_POS)) {
_param_ekf2_ev_ctrl.set(_param_ekf2_ev_ctrl.get()
| static_cast<int32_t>(EvCtrl::HPOS) | static_cast<int32_t>(EvCtrl::VPOS));
}
// EKF2_EV_CTRL set YAW bit
if ((_param_ekf2_aid_mask.get() & SensorFusionMask::DEPRECATED_USE_EXT_VIS_YAW)) {
_param_ekf2_ev_ctrl.set(_param_ekf2_ev_ctrl.get() | static_cast<int32_t>(EvCtrl::YAW));
}
_param_ekf2_aid_mask.set(_param_ekf2_aid_mask.get() & ~(SensorFusionMask::DEPRECATED_USE_EXT_VIS_VEL));
_param_ekf2_aid_mask.set(_param_ekf2_aid_mask.get() & ~(SensorFusionMask::DEPRECATED_USE_EXT_VIS_POS));
_param_ekf2_aid_mask.set(_param_ekf2_aid_mask.get() & ~(SensorFusionMask::DEPRECATED_USE_EXT_VIS_YAW));
_param_ekf2_ev_ctrl.commit();
_param_ekf2_aid_mask.commit();
mavlink_log_critical(&_mavlink_log_pub, "EKF2 EV use EKF2_EV_CTRL instead of EKF2_AID_MASK\n");
/* EVENT
* @description <param>EKF2_AID_MASK</param> is set to {1:.0}.
*/
events::send<float>(events::ID("ekf2_aid_mask_ev"), events::Log::Warning,
"Use EKF2_EV_CTRL instead", _param_ekf2_aid_mask.get());
}
#endif // CONFIG_EKF2_EXTERNAL_VISION
// IMU EKF2_AID_MASK -> EKF2_IMU_CTRL (2023-01-31)
if (_param_ekf2_aid_mask.get() & SensorFusionMask::DEPRECATED_INHIBIT_ACC_BIAS) {
// EKF2_IMU_CTRL set disable accel bias bit
_param_ekf2_imu_ctrl.set(_param_ekf2_imu_ctrl.get() & ~(static_cast<int32_t>(ImuCtrl::AccelBias)));
// EKF2_AID_MASK clear inhibit accel bias bit
_param_ekf2_aid_mask.set(_param_ekf2_aid_mask.get() & ~(SensorFusionMask::DEPRECATED_INHIBIT_ACC_BIAS));
_param_ekf2_imu_ctrl.commit();
_param_ekf2_aid_mask.commit();
mavlink_log_critical(&_mavlink_log_pub, "EKF2 IMU accel bias inhibit use EKF2_IMU_CTRL instead of EKF2_AID_MASK\n");
/* EVENT
* @description <param>EKF2_AID_MASK</param> is set to {1:.0}.
*/
events::send<float>(events::ID("ekf2_aid_mask_imu"), events::Log::Warning,
"Use EKF2_IMU_CTRL instead", _param_ekf2_aid_mask.get());
}
#if defined(CONFIG_EKF2_DRAG_FUSION)
if (_param_ekf2_aid_mask.get() & SensorFusionMask::DEPRECATED_USE_DRAG) {
// EKF2_DRAG_CTRL enable drag fusion
_param_ekf2_drag_ctrl.set(1);
// EKF2_AID_MASK clear deprecated bits
_param_ekf2_aid_mask.set(_param_ekf2_aid_mask.get() & ~(SensorFusionMask::DEPRECATED_USE_DRAG));
_param_ekf2_drag_ctrl.commit();
_param_ekf2_aid_mask.commit();
mavlink_log_critical(&_mavlink_log_pub, "EKF2 drag fusion use EKF2_DRAG_CTRL instead of EKF2_AID_MASK\n");
/* EVENT
* @description <param>EKF2_AID_MASK</param> is set to {1:.0}.
*/
events::send<float>(events::ID("ekf2_aid_mask_drag"), events::Log::Warning,
"Use EKF2_DRAG_CTRL instead", _param_ekf2_aid_mask.get());
}
#endif // CONFIG_EKF2_DRAG_FUSION
#if defined(CONFIG_EKF2_OPTICAL_FLOW)
// IMU EKF2_AID_MASK -> EKF2_OF_CTRL (2023-04-26)
if (_param_ekf2_aid_mask.get() & SensorFusionMask::DEPRECATED_USE_OPT_FLOW) {
// EKF2_OF_CTRL enable flow fusion
_param_ekf2_of_ctrl.set(1);
// EKF2_AID_MASK clear deprecated bit
_param_ekf2_aid_mask.set(_param_ekf2_aid_mask.get() & ~(SensorFusionMask::DEPRECATED_USE_OPT_FLOW));
_param_ekf2_of_ctrl.commit();
_param_ekf2_aid_mask.commit();
mavlink_log_critical(&_mavlink_log_pub, "EKF2 optical flow use EKF2_OF_CTRL instead of EKF2_AID_MASK\n");
/* EVENT
* @description <param>EKF2_AID_MASK</param> is set to {1:.0}.
*/
events::send<float>(events::ID("ekf2_aid_mask_opt_flow"), events::Log::Warning,
"Use EKF2_OF_CTRL instead", _param_ekf2_aid_mask.get());
}
#endif // CONFIG_EKF2_OPTICAL_FLOW
#if defined(CONFIG_EKF2_MAGNETOMETER)
// EKF2_MAG_TYPE obsolete options
@ -1020,7 +905,7 @@ void EKF2::VerifyParams()
mavlink_log_critical(&_mavlink_log_pub, "EKF2_MAG_TYPE invalid, resetting to default");
/* EVENT
* @description <param>EKF2_AID_MASK</param> is set to {1:.0}.
* @description <param>EKF2_MAG_TYPE</param> is set to {1:.0}.
*/
events::send<float>(events::ID("ekf2_mag_type_invalid"), events::Log::Warning,
"EKF2_MAG_TYPE invalid, resetting to default", _param_ekf2_mag_type.get());

View File

@ -156,19 +156,6 @@ 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;
@ -642,9 +629,6 @@ private:
(ParamExtInt<px4::params::EKF2_SYNT_MAG_Z>) _param_ekf2_synthetic_mag_z,
#endif // CONFIG_EKF2_MAGNETOMETER
// measurement source control
(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_NOAID_TOUT>)

View File

@ -603,36 +603,6 @@ PARAM_DEFINE_FLOAT(EKF2_GPS_V_GATE, 5.0f);
*/
PARAM_DEFINE_FLOAT(EKF2_TAS_GATE, 5.0f);
/**
* Will be removed after v1.14 release
*
* Set bits in the following positions to enable:
* 0 : Deprecated, use EKF2_GPS_CTRL instead
* 1 : Deprecated. use EKF2_OF_CTRL instead
* 2 : Deprecated, use EKF2_IMU_CTRL instead
* 3 : Deprecated, use EKF2_EV_CTRL instead
* 4 : Deprecated, use EKF2_EV_CTRL instead
* 5 : Deprecated. use EKF2_DRAG_CTRL instead
* 6 : Deprecated, use EKF2_EV_CTRL instead
* 7 : Deprecated, use EKF2_GPS_CTRL instead
* 8 : Deprecated, use EKF2_EV_CTRL instead
*
* @group EKF2
* @min 0
* @max 511
* @bit 0 unused
* @bit 1 unused
* @bit 2 unused
* @bit 3 unused
* @bit 4 unused
* @bit 5 unused
* @bit 6 unused
* @bit 7 unused
* @bit 8 unused
* @reboot_required true
*/
PARAM_DEFINE_INT32(EKF2_AID_MASK, 0);
/**
* Determines the reference source of height data used by the EKF.
*