mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-08 17:03:57 -04:00
AP_NavEKF: Bug fix in covariance error correction
This commit is contained in:
parent
43dc9bc055
commit
e69eea3086
@ -1812,7 +1812,7 @@ void NavEKF::FixCovarianceErrors()
|
|||||||
{
|
{
|
||||||
for (uint8_t j=0; j<=i-1; j++)
|
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[i][j] = temp;
|
||||||
P[j][i] = temp;
|
P[j][i] = temp;
|
||||||
}
|
}
|
||||||
|
Loading…
Reference in New Issue
Block a user