mirror of https://github.com/ArduPilot/ardupilot
AP_NavEKF: Synchronise non-aiding mode state corrections
Synchronise with covariance prediction to improve numerical stability and accuracy of angle corrections. The 'noise' this produces in the position and velocity estimate is irrelevantbecause these are not used by the control loops during this mode of operation (they are nominally zero anyway).
This commit is contained in:
parent
ae6b85e63d
commit
81ee339e25
|
@ -788,7 +788,7 @@ void NavEKF::SelectVelPosFusion()
|
||||||
fuseVelData = false;
|
fuseVelData = false;
|
||||||
fusePosData = false;
|
fusePosData = false;
|
||||||
}
|
}
|
||||||
} else if (constPosMode ) {
|
} else if (constPosMode && covPredStep) {
|
||||||
// in constant position mode use synthetic position measurements set to zero
|
// in constant position mode use synthetic position measurements set to zero
|
||||||
// only fuse synthetic measurements when rate of change of velocity is less than 0.5g to reduce attitude errors due to launch acceleration
|
// only fuse synthetic measurements when rate of change of velocity is less than 0.5g to reduce attitude errors due to launch acceleration
|
||||||
// do not use velocity fusion to reduce the effect of movement on attitude
|
// do not use velocity fusion to reduce the effect of movement on attitude
|
||||||
|
@ -798,7 +798,7 @@ void NavEKF::SelectVelPosFusion()
|
||||||
fusePosData = false;
|
fusePosData = false;
|
||||||
}
|
}
|
||||||
fuseVelData = false;
|
fuseVelData = false;
|
||||||
} else if (constVelMode) {
|
} else if (constVelMode && covPredStep) {
|
||||||
// In constant velocity mode we fuse the last valid velocity vector
|
// In constant velocity mode we fuse the last valid velocity vector
|
||||||
// Reset the stored velocity vector when we enter the mode
|
// Reset the stored velocity vector when we enter the mode
|
||||||
if (constVelMode && !lastConstVelMode) {
|
if (constVelMode && !lastConstVelMode) {
|
||||||
|
|
Loading…
Reference in New Issue