Browse Source

AP_NavEKF3: fix wind speed covariance initialisation bug

gps-1.3.1
Paul Riseborough 3 years ago committed by Andrew Tridgell
parent
commit
e9c339a0a0
  1. 8
      libraries/AP_NavEKF3/AP_NavEKF3_Control.cpp

8
libraries/AP_NavEKF3/AP_NavEKF3_Control.cpp

@ -88,11 +88,9 @@ void NavEKF3_core::setWindMagStateLearningMode() @@ -88,11 +88,9 @@ void NavEKF3_core::setWindMagStateLearningMode()
}
// set the wind state variances to the measurement uncertainty
for (uint8_t index=22; index<=23; index++) {
zeroCols(P, 22, 23);
zeroRows(P, 22, 23);
P[index][index] = trueAirspeedVariance;
}
zeroCols(P, 22, 23);
zeroRows(P, 22, 23);
P[22][22] = P[23][23] = trueAirspeedVariance;
windStatesAligned = true;

Loading…
Cancel
Save