AP_NavEKF: Bug fix in covariance error correction

This commit is contained in:
Paul Riseborough 2014-01-03 19:20:10 +11:00 committed by Andrew Tridgell
parent 43dc9bc055
commit e69eea3086

View File

@ -1812,7 +1812,7 @@ void NavEKF::FixCovarianceErrors()
{
for (uint8_t j=0; j<=i-1; j++)
{
float temp = 0.5f*(P[i][j] + P[j][i]);
float temp = 0.5f*(nextP[i][j] + nextP[j][i]);
P[i][j] = temp;
P[j][i] = temp;
}