AP_NavEKF: Use compensation for baro delay in position hold mode

This commit is contained in:
priseborough 2014-12-21 15:08:40 +11:00 committed by Randy Mackay
parent 4dc1ee2d66
commit 5bd4ee9715

View File

@ -1850,7 +1850,6 @@ void NavEKF::FuseVelPosNED()
// because there may be no stored states due to lack of real measurements.
if (posHoldMode) {
statesAtPosTime = state;
statesAtHgtTime = state;
} else if (velHoldMode) {
statesAtVelTime = state;
}