Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

[EKF2] Tilt estimate improvements #24247

Draft
wants to merge 3 commits into
base: main
Choose a base branch
from
Draft
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
5 changes: 3 additions & 2 deletions src/modules/ekf2/EKF/aid_sources/gravity/gravity_fusion.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -54,8 +54,9 @@ void Ekf::controlGravityFusion(const imuSample &imu)

const float upper_accel_limit = CONSTANTS_ONE_G * 1.1f;
const float lower_accel_limit = CONSTANTS_ONE_G * 0.9f;
const bool accel_lpf_norm_good = (_accel_magnitude_filt > lower_accel_limit)
&& (_accel_magnitude_filt < upper_accel_limit);
const float accel_lpf_norm_sq = _accel_lpf.getState().norm_squared();
Copy link
Member

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

_accel_lpf is only being updated during init, but I was thinking we should move it regardless.

bool Ekf::initialiseFilter()
{
// Filter accel for tilt initialization
const imuSample &imu_init = _imu_buffer.get_newest();
// protect against zero data
if (imu_init.delta_vel_dt < 1e-4f || imu_init.delta_ang_dt < 1e-4f) {
return false;
}
if (_is_first_imu_sample) {
_accel_lpf.reset(imu_init.delta_vel / imu_init.delta_vel_dt);
_gyro_lpf.reset(imu_init.delta_ang / imu_init.delta_ang_dt);
_is_first_imu_sample = false;
} else {
_accel_lpf.update(imu_init.delta_vel / imu_init.delta_vel_dt);
_gyro_lpf.update(imu_init.delta_ang / imu_init.delta_ang_dt);
}

Copy link
Member

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

I was moving it here, but got a little sidetracked. #24046

Copy link
Member Author

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Ouch, I didn't realize that; thanks

const bool accel_lpf_norm_good = (accel_lpf_norm_sq > sq(lower_accel_limit))
&& (accel_lpf_norm_sq < sq(upper_accel_limit));

// fuse gravity observation if our overall acceleration isn't too big
_control_status.flags.gravity_vector = (_params.imu_ctrl & static_cast<int32_t>(ImuCtrl::GravityVector))
Expand Down
4 changes: 2 additions & 2 deletions src/modules/ekf2/EKF/aid_sources/magnetometer/mag_control.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -236,13 +236,13 @@ void Ekf::controlMagFusion(const imuSample &imu_sample)
&& PX4_ISFINITE(_wmm_declination_rad)
) {
// using declination from the world magnetic model
fuseDeclination(_wmm_declination_rad, 0.5f, update_all_states);
fuseDeclination(_wmm_declination_rad, 0.5f, update_all_states, update_tilt);

} else if ((_params.mag_declination_source & GeoDeclinationMask::SAVE_GEO_DECL)
&& PX4_ISFINITE(_params.mag_declination_deg) && (fabsf(_params.mag_declination_deg) > 0.f)
) {
// using previously saved declination
fuseDeclination(math::radians(_params.mag_declination_deg), R_DECL, update_all_states);
fuseDeclination(math::radians(_params.mag_declination_deg), R_DECL, update_all_states, update_tilt);

} else {
// if there is no aiding coming from an inertial frame we need to fuse some declination
Expand Down
10 changes: 8 additions & 2 deletions src/modules/ekf2/EKF/aid_sources/magnetometer/mag_fusion.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -140,7 +140,7 @@ bool Ekf::fuseMag(const Vector3f &mag, const float R_MAG, VectorState &H, estima
return true;
}

bool Ekf::fuseDeclination(float decl_measurement_rad, float R, bool update_all_states)
bool Ekf::fuseDeclination(float decl_measurement_rad, float R, bool update_all_states, bool update_tilt)
{
VectorState H;
float decl_pred;
Expand All @@ -160,7 +160,13 @@ bool Ekf::fuseDeclination(float decl_measurement_rad, float R, bool update_all_s
// Calculate the Kalman gains
VectorState Kfusion = P * H / innovation_variance;

if (!update_all_states) {
if (update_all_states) {
if (!update_tilt) {
Kfusion(State::quat_nominal.idx + 0) = 0.f;
Kfusion(State::quat_nominal.idx + 1) = 0.f;
}

} else {
// zero non-mag Kalman gains if not updating all states

// copy mag_I and mag_B Kalman gains
Expand Down
3 changes: 2 additions & 1 deletion src/modules/ekf2/EKF/ekf.h
Original file line number Diff line number Diff line change
Expand Up @@ -669,7 +669,8 @@ class Ekf final : public EstimatorInterface

// fuse magnetometer declination measurement
// R: declination observation variance (rad**2)
bool fuseDeclination(const float decl_measurement_rad, const float R, bool update_all_states = false);
bool fuseDeclination(const float decl_measurement_rad, const float R, bool update_all_states = false,
bool update_tilt = false);

#endif // CONFIG_EKF2_MAGNETOMETER

Expand Down
4 changes: 2 additions & 2 deletions src/modules/ekf2/EKF/ekf_helper.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -1013,8 +1013,8 @@ void Ekf::updateIMUBiasInhibit(const imuSample &imu_delayed)
} else if (_control_status.flags.fake_hgt) {
is_bias_observable = false;

} else if (_control_status.flags.fake_pos) {
// when using fake position (but not fake height) only consider an accel bias observable if aligned with the gravity vector
} else if (_control_status.flags.fake_pos || _control_status.flags.gravity_vector) {
// only consider an accel bias observable if aligned with the gravity vector
is_bias_observable = (fabsf(_R_to_earth(2, index)) > 0.966f); // cos 15 degrees ~= 0.966
}

Expand Down
Loading