AP_NavEKF: Simplify nested logic - functionally equivalent

Additional if else statement was unnecessary
This commit is contained in:
priseborough 2015-01-10 04:36:27 +11:00 committed by Randy Mackay
parent 12c3368c4d
commit 6663d80176

View File

@ -759,14 +759,12 @@ void NavEKF::SelectVelPosFusion()
}
// command fusion of GPS data and reset states as required
if (newDataGps) {
if (newDataGps && (PV_AidingMode == AID_ABSOLUTE)) {
// reset data arrived flag
newDataGps = false;
// reset state updates and counter used to spread fusion updates across several frames to reduce 10Hz pulsing
memset(&gpsIncrStateDelta[0], 0, sizeof(gpsIncrStateDelta));
gpsUpdateCount = 0;
// select which of velocity and position measurements will be fused
if (PV_AidingMode == AID_ABSOLUTE) {
// use both if GPS use is enabled
fuseVelData = true;
fusePosData = true;
@ -784,10 +782,6 @@ void NavEKF::SelectVelPosFusion()
fuseVelData = false;
fusePosData = false;
}
} else {
fuseVelData = false;
fusePosData = false;
}
} else if (constPosMode && covPredStep) {
// 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