ekf2: add kconfig to disable gravity fusion

This commit is contained in:
Daniel Agar 2023-10-17 13:27:29 -04:00
parent e8a0a0772e
commit 755b45441f
8 changed files with 67 additions and 31 deletions

View File

@ -124,7 +124,6 @@ list(APPEND EKF_SRCS
EKF/estimator_interface.cpp
EKF/fake_height_control.cpp
EKF/fake_pos_control.cpp
EKF/gravity_fusion.cpp
EKF/height_control.cpp
EKF/imu_down_sampler.cpp
EKF/output_predictor.cpp
@ -175,6 +174,10 @@ if(CONFIG_EKF2_GNSS_YAW)
list(APPEND EKF_SRCS EKF/gps_yaw_fusion.cpp)
endif()
if(CONFIG_EKF2_GRAVITY_FUSION)
list(APPEND EKF_SRCS EKF/gravity_fusion.cpp)
endif()
if(CONFIG_EKF2_MAGNETOMETER)
list(APPEND EKF_SRCS
EKF/mag_3d_control.cpp

View File

@ -42,7 +42,6 @@ list(APPEND EKF_SRCS
estimator_interface.cpp
fake_height_control.cpp
fake_pos_control.cpp
gravity_fusion.cpp
height_control.cpp
imu_down_sampler.cpp
output_predictor.cpp
@ -93,6 +92,10 @@ if(CONFIG_EKF2_GNSS_YAW)
list(APPEND EKF_SRCS gps_yaw_fusion.cpp)
endif()
if(CONFIG_EKF2_GRAVITY_FUSION)
list(APPEND EKF_SRCS gravity_fusion.cpp)
endif()
if(CONFIG_EKF2_MAGNETOMETER)
list(APPEND EKF_SRCS
mag_3d_control.cpp

View File

@ -454,8 +454,10 @@ struct parameters {
Vector3f ev_pos_body{}; ///< xyz position of VI-sensor focal point in body frame (m)
#endif // CONFIG_EKF2_EXTERNAL_VISION
#if defined(CONFIG_EKF2_GRAVITY_FUSION)
// gravity fusion
float gravity_noise{1.0f}; ///< accelerometer measurement gaussian noise (m/s**2)
#endif // CONFIG_EKF2_GRAVITY_FUSION
#if defined(CONFIG_EKF2_OPTICAL_FLOW)
int32_t flow_ctrl{0};

View File

@ -128,7 +128,10 @@ void Ekf::controlFusionModes(const imuSample &imu_delayed)
#endif // CONFIG_EKF2_DRAG_FUSION
controlHeightFusion(imu_delayed);
#if defined(CONFIG_EKF2_GRAVITY_FUSION)
controlGravityFusion(imu_delayed);
#endif // CONFIG_EKF2_GRAVITY_FUSION
#if defined(CONFIG_EKF2_EXTERNAL_VISION)
// Additional data odometry data from an external estimator can be fused.

View File

@ -310,9 +310,13 @@ public:
void getBetaInnovRatio(float &beta_innov_ratio) const { beta_innov_ratio = _aid_src_sideslip.test_ratio; }
#endif // CONFIG_EKF2_SIDESLIP
#if defined(CONFIG_EKF2_GRAVITY_FUSION)
const auto &aid_src_gravity() const { return _aid_src_gravity; }
void getGravityInnov(float grav_innov[3]) const { memcpy(grav_innov, _aid_src_gravity.innovation, sizeof(_aid_src_gravity.innovation)); }
void getGravityInnovVar(float grav_innov_var[3]) const { memcpy(grav_innov_var, _aid_src_gravity.innovation_variance, sizeof(_aid_src_gravity.innovation_variance)); }
void getGravityInnovRatio(float &grav_innov_ratio) const { grav_innov_ratio = Vector3f(_aid_src_gravity.test_ratio).max(); }
#endif // CONFIG_EKF2_GRAVITY_FUSION
// get the state vector at the delayed time horizon
const matrix::Vector<float, State::size> &getStateAtFusionHorizonAsVector() const { return _state.vector(); }
@ -554,8 +558,6 @@ public:
const auto &aid_src_mag() const { return _aid_src_mag; }
#endif // CONFIG_EKF2_MAGNETOMETER
const auto &aid_src_gravity() const { return _aid_src_gravity; }
#if defined(CONFIG_EKF2_AUXVEL)
const auto &aid_src_aux_vel() const { return _aid_src_aux_vel; }
#endif // CONFIG_EKF2_AUXVEL
@ -731,7 +733,9 @@ private:
# endif // CONFIG_EKF2_GNSS_YAW
#endif // CONFIG_EKF2_GNSS
#if defined(CONFIG_EKF2_GRAVITY_FUSION)
estimator_aid_source3d_s _aid_src_gravity{};
#endif // CONFIG_EKF2_GRAVITY_FUSION
#if defined(CONFIG_EKF2_AUXVEL)
estimator_aid_source2d_s _aid_src_aux_vel{};
@ -1184,8 +1188,10 @@ private:
void updateGroundEffect();
#endif // CONFIG_EKF2_BAROMETER
#if defined(CONFIG_EKF2_GRAVITY_FUSION)
// gravity fusion: heuristically enable / disable gravity fusion
void controlGravityFusion(const imuSample &imu_delayed);
#endif // CONFIG_EKF2_GRAVITY_FUSION
void resetQuatCov(const float yaw_noise = NAN);
void resetQuatCov(const Vector3f &euler_noise_ned);

View File

@ -189,6 +189,16 @@ EKF2::EKF2(bool multi_mode, const px4::wq_config_t &config, bool replay_mode):
_param_ekf2_of_pos_y(_params->flow_pos_body(1)),
_param_ekf2_of_pos_z(_params->flow_pos_body(2)),
#endif // CONFIG_EKF2_OPTICAL_FLOW
#if defined(CONFIG_EKF2_DRAG_FUSION)
_param_ekf2_drag_ctrl(_params->drag_ctrl),
_param_ekf2_drag_noise(_params->drag_noise),
_param_ekf2_bcoef_x(_params->bcoef_x),
_param_ekf2_bcoef_y(_params->bcoef_y),
_param_ekf2_mcoef(_params->mcoef),
#endif // CONFIG_EKF2_DRAG_FUSION
#if defined(CONFIG_EKF2_GRAVITY_FUSION)
_param_ekf2_grav_noise(_params->gravity_noise),
#endif // CONFIG_EKF2_GRAVITY_FUSION
_param_ekf2_imu_pos_x(_params->imu_pos_body(0)),
_param_ekf2_imu_pos_y(_params->imu_pos_body(1)),
_param_ekf2_imu_pos_z(_params->imu_pos_body(2)),
@ -199,16 +209,7 @@ EKF2::EKF2(bool multi_mode, const px4::wq_config_t &config, bool replay_mode):
_param_ekf2_abl_acclim(_params->acc_bias_learn_acc_lim),
_param_ekf2_abl_gyrlim(_params->acc_bias_learn_gyr_lim),
_param_ekf2_abl_tau(_params->acc_bias_learn_tc),
_param_ekf2_gyr_b_lim(_params->gyro_bias_lim),
#if defined(CONFIG_EKF2_DRAG_FUSION)
_param_ekf2_drag_ctrl(_params->drag_ctrl),
_param_ekf2_drag_noise(_params->drag_noise),
_param_ekf2_bcoef_x(_params->bcoef_x),
_param_ekf2_bcoef_y(_params->bcoef_y),
_param_ekf2_mcoef(_params->mcoef),
#endif // CONFIG_EKF2_DRAG_FUSION
_param_ekf2_grav_noise(_params->gravity_noise)
_param_ekf2_gyr_b_lim(_params->gyro_bias_lim)
{
// advertise expected minimal topic set immediately to ensure logging
_attitude_pub.advertise();
@ -1082,8 +1083,10 @@ void EKF2::PublishAidSourceStatus(const hrt_abstime &timestamp)
PublishAidSourceStatus(_ekf.aid_src_mag(), _status_mag_pub_last, _estimator_aid_src_mag_pub);
#endif // CONFIG_EKF2_MAGNETOMETER
#if defined(CONFIG_EKF2_GRAVITY_FUSION)
// gravity
PublishAidSourceStatus(_ekf.aid_src_gravity(), _status_gravity_pub_last, _estimator_aid_src_gravity_pub);
#endif // CONFIG_EKF2_GRAVITY_FUSION
#if defined(CONFIG_EKF2_AUXVEL)
// aux velocity
@ -1431,7 +1434,9 @@ void EKF2::PublishInnovations(const hrt_abstime &timestamp)
_ekf.getBetaInnov(innovations.beta);
#endif // CONFIG_EKF2_SIDESLIP
#if defined(CONFIG_EKF2_GRAVITY_FUSION)
_ekf.getGravityInnov(innovations.gravity);
#endif // CONFIG_EKF2_GRAVITY_FUSION
#if defined(CONFIG_EKF2_TERRAIN)
# if defined(CONFIG_EKF2_RANGE_FINDER)
@ -1525,7 +1530,9 @@ void EKF2::PublishInnovationTestRatios(const hrt_abstime &timestamp)
_ekf.getBetaInnovRatio(test_ratios.beta);
#endif // CONFIG_EKF2_SIDESLIP
#if defined(CONFIG_EKF2_GRAVITY_FUSION)
_ekf.getGravityInnovRatio(test_ratios.gravity[0]);
#endif // CONFIG_EKF2_GRAVITY_FUSION
#if defined(CONFIG_EKF2_TERRAIN)
# if defined(CONFIG_EKF2_RANGE_FINDER)
@ -1590,7 +1597,9 @@ void EKF2::PublishInnovationVariances(const hrt_abstime &timestamp)
# endif // CONFIG_EKF2_OPTICAL_FLOW
#endif // CONFIG_EKF2_TERRAIN && CONFIG_EKF2_RANGE_FINDER
#if defined(CONFIG_EKF2_GRAVITY_FUSION)
_ekf.getGravityInnovVar(variances.gravity);
#endif // CONFIG_EKF2_GRAVITY_FUSION
// Not yet supported
variances.aux_vvel = NAN;

View File

@ -349,8 +349,6 @@ private:
uORB::PublicationMulti<estimator_bias3d_s> _estimator_ev_pos_bias_pub{ORB_ID(estimator_ev_pos_bias)};
#endif // CONFIG_EKF2_EXTERNAL_VISION
hrt_abstime _status_gravity_pub_last{0};
#if defined(CONFIG_EKF2_AUXVEL)
uORB::Subscription _landing_target_pose_sub {ORB_ID(landing_target_pose)};
@ -476,8 +474,6 @@ private:
uORB::PublicationMulti<estimator_aid_source1d_s> _estimator_aid_src_fake_hgt_pub{ORB_ID(estimator_aid_src_fake_hgt)};
uORB::PublicationMulti<estimator_aid_source2d_s> _estimator_aid_src_fake_pos_pub{ORB_ID(estimator_aid_src_fake_pos)};
uORB::PublicationMulti<estimator_aid_source3d_s> _estimator_aid_src_gravity_pub{ORB_ID(estimator_aid_src_gravity)};
// publications with topic dependent on multi-mode
uORB::PublicationMulti<vehicle_attitude_s> _attitude_pub;
uORB::PublicationMulti<vehicle_local_position_s> _local_position_pub;
@ -518,6 +514,11 @@ private:
# endif // CONFIG_EKF2_GNSS_YAW
#endif // CONFIG_EKF2_GNSS
#if defined(CONFIG_EKF2_GRAVITY_FUSION)
hrt_abstime _status_gravity_pub_last{0};
uORB::PublicationMulti<estimator_aid_source3d_s> _estimator_aid_src_gravity_pub{ORB_ID(estimator_aid_src_gravity)};
#endif // CONFIG_EKF2_GRAVITY_FUSION
PreFlightChecker _preflt_checker;
Ekf _ekf;
@ -722,6 +723,20 @@ private:
_param_ekf2_of_pos_z, ///< Z position of optical flow sensor focal point in body frame (m)
#endif // CONFIG_EKF2_OPTICAL_FLOW
#if defined(CONFIG_EKF2_DRAG_FUSION)
(ParamExtInt<px4::params::EKF2_DRAG_CTRL>) _param_ekf2_drag_ctrl, ///< drag fusion selection
// Multi-rotor drag specific force fusion
(ParamExtFloat<px4::params::EKF2_DRAG_NOISE>)
_param_ekf2_drag_noise, ///< observation noise variance for drag specific force measurements (m/sec**2)**2
(ParamExtFloat<px4::params::EKF2_BCOEF_X>) _param_ekf2_bcoef_x, ///< ballistic coefficient along the X-axis (kg/m**2)
(ParamExtFloat<px4::params::EKF2_BCOEF_Y>) _param_ekf2_bcoef_y, ///< ballistic coefficient along the Y-axis (kg/m**2)
(ParamExtFloat<px4::params::EKF2_MCOEF>) _param_ekf2_mcoef, ///< propeller momentum drag coefficient (1/s)
#endif // CONFIG_EKF2_DRAG_FUSION
#if defined(CONFIG_EKF2_GRAVITY_FUSION)
(ParamExtFloat<px4::params::EKF2_GRAV_NOISE>) _param_ekf2_grav_noise,
#endif // CONFIG_EKF2_GRAVITY_FUSION
// sensor positions in body frame
(ParamExtFloat<px4::params::EKF2_IMU_POS_X>) _param_ekf2_imu_pos_x, ///< X position of IMU in body frame (m)
(ParamExtFloat<px4::params::EKF2_IMU_POS_Y>) _param_ekf2_imu_pos_y, ///< Y position of IMU in body frame (m)
@ -746,21 +761,9 @@ private:
(ParamExtFloat<px4::params::EKF2_GYR_B_LIM>) _param_ekf2_gyr_b_lim, ///< Gyro bias learning limit (rad/s)
#if defined(CONFIG_EKF2_DRAG_FUSION)
(ParamExtInt<px4::params::EKF2_DRAG_CTRL>) _param_ekf2_drag_ctrl, ///< drag fusion selection
// Multi-rotor drag specific force fusion
(ParamExtFloat<px4::params::EKF2_DRAG_NOISE>)
_param_ekf2_drag_noise, ///< observation noise variance for drag specific force measurements (m/sec**2)**2
(ParamExtFloat<px4::params::EKF2_BCOEF_X>) _param_ekf2_bcoef_x, ///< ballistic coefficient along the X-axis (kg/m**2)
(ParamExtFloat<px4::params::EKF2_BCOEF_Y>) _param_ekf2_bcoef_y, ///< ballistic coefficient along the Y-axis (kg/m**2)
(ParamExtFloat<px4::params::EKF2_MCOEF>) _param_ekf2_mcoef, ///< propeller momentum drag coefficient (1/s)
#endif // CONFIG_EKF2_DRAG_FUSION
// output predictor filter time constants
(ParamFloat<px4::params::EKF2_TAU_VEL>) _param_ekf2_tau_vel,
(ParamFloat<px4::params::EKF2_TAU_POS>) _param_ekf2_tau_pos,
(ParamExtFloat<px4::params::EKF2_GRAV_NOISE>) _param_ekf2_grav_noise
(ParamFloat<px4::params::EKF2_TAU_POS>) _param_ekf2_tau_pos
)
};
#endif // !EKF2_HPP

View File

@ -75,6 +75,13 @@ depends on MODULES_EKF2
---help---
EKF2 GNSS yaw fusion support.
menuconfig EKF2_GRAVITY_FUSION
depends on MODULES_EKF2
bool "gravity fusion support"
default y
---help---
EKF2 gravity fusion support.
menuconfig EKF2_MAGNETOMETER
depends on MODULES_EKF2
bool "magnetometer support"