mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-23 16:23:56 -04:00
AP_NavEKF2: Adjust attitude variance values used after a heading reset
Because these errors are in body frame, a spherical error should be used to accommodate different orientations
This commit is contained in:
parent
5ec8d523f6
commit
581c1aa0d4
@ -108,8 +108,7 @@ void NavEKF2_core::realignYawGPS()
|
|||||||
zeroRows(P,0,2);
|
zeroRows(P,0,2);
|
||||||
|
|
||||||
// Set the initial attitude error covariances
|
// Set the initial attitude error covariances
|
||||||
P[1][1] = P[0][0] = sq(radians(5.0f));
|
P[2][2] = P[1][1] = P[0][0] = sq(radians(5.0f));
|
||||||
P[2][2] = sq(radians(45.0f));
|
|
||||||
|
|
||||||
// reset tposition fusion timer to cause the states to be reset to the GPS on the next GPS fusion cycle
|
// reset tposition fusion timer to cause the states to be reset to the GPS on the next GPS fusion cycle
|
||||||
lastPosPassTime_ms = 0;
|
lastPosPassTime_ms = 0;
|
||||||
|
Loading…
Reference in New Issue
Block a user