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-yaw estimator: force set gyro bias when at rest #22840

Merged
merged 1 commit into from
Mar 5, 2024
Merged
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
4 changes: 2 additions & 2 deletions src/modules/ekf2/EKF/EKFGSF_yaw.h
Original file line number Diff line number Diff line change
Expand Up @@ -67,11 +67,11 @@ class EKFGSF_yaw

void setTrueAirspeed(float true_airspeed) { _true_airspeed = true_airspeed; }

void setGyroBias(const Vector3f &imu_gyro_bias)
void setGyroBias(const Vector3f &imu_gyro_bias, const bool force = false)
{
// Initialise to gyro bias estimate from main filter because there could be a large
// uncorrected rate gyro bias error about the gravity vector
if (!_ahrs_ekf_gsf_tilt_aligned || !_ekf_gsf_vel_fuse_started) {
if (!_ahrs_ekf_gsf_tilt_aligned || !_ekf_gsf_vel_fuse_started || force) {
// init gyro bias for each model
for (uint8_t model_index = 0; model_index < N_MODELS_EKFGSF; model_index++) {
_ahrs_ekf_gsf[model_index].gyro_bias = imu_gyro_bias;
Expand Down
2 changes: 1 addition & 1 deletion src/modules/ekf2/EKF/gps_control.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -47,7 +47,7 @@ void Ekf::controlGpsFusion(const imuSample &imu_delayed)
}

if (!gyro_bias_inhibited()) {
_yawEstimator.setGyroBias(getGyroBias());
_yawEstimator.setGyroBias(getGyroBias(), _control_status.flags.vehicle_at_rest);
}

// run EKF-GSF yaw estimator once per imu_delayed update
Expand Down
Loading