mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-02 14:08:45 -04:00
AP_NavEKF2: fixed reset of coviariance matrix
This commit is contained in:
parent
888edcd709
commit
d799bacd7d
@ -413,13 +413,8 @@ bool NavEKF2_core::InitialiseFilterBootstrap(void)
|
||||
void NavEKF2_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));
|
||||
|
||||
// attitude error
|
||||
P[0][0] = 0.1f;
|
||||
P[1][1] = 0.1f;
|
||||
|
Loading…
Reference in New Issue
Block a user