mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-26 17:53:59 -04:00
AP_NavEKF: explicitly zeroed covariance matrix priro to setting initial values
This commit is contained in:
parent
6e6e3d923e
commit
7e026d41df
@ -1808,7 +1808,15 @@ void NavEKF::OnGroundCheck()
|
|||||||
|
|
||||||
void NavEKF::CovarianceInit()
|
void NavEKF::CovarianceInit()
|
||||||
{
|
{
|
||||||
// Calculate the initial covariance matrix P
|
// zero the matrix
|
||||||
|
for (uint8_t i=1; i<=20; i++)
|
||||||
|
{
|
||||||
|
for (uint8_t j=0; j<=20; j++)
|
||||||
|
{
|
||||||
|
P[i][j] = 0.0f;
|
||||||
|
}
|
||||||
|
}
|
||||||
|
// Set the diagonals
|
||||||
P[1][1] = 0.25f*sq(1.0f*DEG_TO_RAD);
|
P[1][1] = 0.25f*sq(1.0f*DEG_TO_RAD);
|
||||||
P[2][2] = 0.25f*sq(1.0f*DEG_TO_RAD);
|
P[2][2] = 0.25f*sq(1.0f*DEG_TO_RAD);
|
||||||
P[3][3] = 0.25f*sq(10.0f*DEG_TO_RAD);
|
P[3][3] = 0.25f*sq(10.0f*DEG_TO_RAD);
|
||||||
|
Loading…
Reference in New Issue
Block a user