mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-22 08:38:36 -04:00
AP_NavEKF3: fixed reset of coviariance matrix
This commit is contained in:
parent
d799bacd7d
commit
18b66f9eed
@ -470,13 +470,7 @@ bool NavEKF3_core::InitialiseFilterBootstrap(void)
|
||||
void NavEKF3_core::CovarianceInit()
|
||||
{
|
||||
// zero the matrix
|
||||
for (uint8_t i=1; i<=stateIndexLim; i++)
|
||||
{
|
||||
for (uint8_t j=0; j<=stateIndexLim; j++)
|
||||
{
|
||||
P[i][j] = 0.0f;
|
||||
}
|
||||
}
|
||||
memset(P, 0, sizeof(P));
|
||||
|
||||
// define the initial angle uncertainty as variances for a rotation vector
|
||||
Vector3f rot_vec_var;
|
||||
|
Loading…
Reference in New Issue
Block a user