Skip to content

Commit

Permalink
ekf2: block process noise increment without constraining the variance
Browse files Browse the repository at this point in the history
The wind variance can be reset to a value larger than the wind init
variance (e.g.: when the reset occurs when flying close to the N or E
axis). Constraining the variance after a covariance initialization would
artificially increase the correlation and could destabilize the filter.
  • Loading branch information
bresch committed Jul 24, 2024
1 parent 39abd87 commit 79e0e00
Showing 1 changed file with 9 additions and 8 deletions.
17 changes: 9 additions & 8 deletions src/modules/ekf2/EKF/covariance.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -201,14 +201,15 @@ void Ekf::predictCovariance(const imuSample &imu_delayed)
#if defined(CONFIG_EKF2_WIND)

// wind vel: add process noise
if (!_external_wind_init) {
float wind_vel_nsd_scaled = math::constrain(_params.wind_vel_nsd, 0.f, 1.f)
* (1.f + _params.wind_vel_nsd_scaler * fabsf(_height_rate_lpf));
float wind_vel_process_noise = sq(wind_vel_nsd_scaled) * dt;

for (unsigned index = 0; index < State::wind_vel.dof; index++) {
const unsigned i = State::wind_vel.idx + index;
P(i, i) = fminf(P(i, i) + wind_vel_process_noise, sq(_params.initial_wind_uncertainty));
float wind_vel_nsd_scaled = math::constrain(_params.wind_vel_nsd, 0.f, 1.f)
* (1.f + _params.wind_vel_nsd_scaler * fabsf(_height_rate_lpf));
float wind_vel_process_noise = sq(wind_vel_nsd_scaled) * dt;

for (unsigned index = 0; index < State::wind_vel.dof; index++) {
const unsigned i = State::wind_vel.idx + index;

if (P(i, i) < sq(_params.initial_wind_uncertainty)) {
P(i, i) += wind_vel_process_noise;
}
}

Expand Down

0 comments on commit 79e0e00

Please sign in to comment.