AP_NavEKF: Track baro alt when pre-armed

This will help prevent spurious alt disparity warning messages for copter
This commit is contained in:
priseborough 2014-10-12 22:17:38 +11:00 committed by Randy Mackay
parent f866bf979e
commit 2bc74934b8

View File

@ -702,6 +702,18 @@ void NavEKF::SelectVelPosFusion()
fusePosData = false;
}
} else {
// in static 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
// do not use velocity fusion to reduce the effect of movement on attitude
if (accNavMag < 4.9f) {
fusePosData = true;
} else {
fusePosData = false;
}
fuseVelData = false;
}
// check for and read new height data
readHgtData();
@ -719,19 +731,6 @@ void NavEKF::SelectVelPosFusion()
fuseHgtData = false;
}
} else {
// in static 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
// do not use velocity fusion to reduce the effect of movement on attitude
if (accNavMag < 4.9f) {
fusePosData = true;
} else {
fusePosData = false;
}
fuseVelData = false;
fuseHgtData = true;
}
// perform fusion
if (fuseVelData || fusePosData || fuseHgtData) {
FuseVelPosNED();