mirror of https://github.com/ArduPilot/ardupilot
AP_NavEKF3: fix wind speed covariance initialisation bug
This commit is contained in:
parent
ea15834401
commit
bc5efb6cd2
|
@ -88,11 +88,9 @@ void NavEKF3_core::setWindMagStateLearningMode()
|
||||||
}
|
}
|
||||||
|
|
||||||
// set the wind state variances to the measurement uncertainty
|
// set the wind state variances to the measurement uncertainty
|
||||||
for (uint8_t index=22; index<=23; index++) {
|
zeroCols(P, 22, 23);
|
||||||
zeroCols(P, 22, 23);
|
zeroRows(P, 22, 23);
|
||||||
zeroRows(P, 22, 23);
|
P[22][22] = P[23][23] = trueAirspeedVariance;
|
||||||
P[index][index] = trueAirspeedVariance;
|
|
||||||
}
|
|
||||||
|
|
||||||
windStatesAligned = true;
|
windStatesAligned = true;
|
||||||
|
|
||||||
|
|
Loading…
Reference in New Issue