AP_NavEKF : Fix bug in scaling of initial Z accel bias state variance

This commit is contained in:
Paul Riseborough 2015-03-20 16:54:35 -07:00 committed by Andrew Tridgell
parent 92df3adb5e
commit a976e9dad2
1 changed files with 1 additions and 1 deletions

View File

@ -3837,7 +3837,7 @@ void NavEKF::CovarianceInit()
P[11][11] = P[10][10];
P[12][12] = P[10][10];
// Z delta velocity bias
P[13][13] = sq(radians(INIT_ACCEL_BIAS_UNCERTAINTY * dtIMU));;
P[13][13] = sq(INIT_ACCEL_BIAS_UNCERTAINTY * dtIMU);
// wind velocities
P[14][14] = 0.0f;
P[15][15] = P[14][14];