AP_NavEKF3: minor restructure of how fusePosData and fuseVelData are set
this non-functional change slightly reduces the number of places we set these variables
This commit is contained in:
parent
2e85ba6f51
commit
0cebde0632
@ -407,6 +407,10 @@ void NavEKF3_core::SelectVelPosFusion()
|
|||||||
// get data that has now fallen behind the fusion time horizon
|
// get data that has now fallen behind the fusion time horizon
|
||||||
gpsDataToFuse = storedGPS.recall(gpsDataDelayed,imuDataDelayed.time_ms);
|
gpsDataToFuse = storedGPS.recall(gpsDataDelayed,imuDataDelayed.time_ms);
|
||||||
|
|
||||||
|
// initialise all possible data we may fuse
|
||||||
|
fusePosData = false;
|
||||||
|
fuseVelData = false;
|
||||||
|
|
||||||
// Determine if we need to fuse position and velocity data on this time step
|
// Determine if we need to fuse position and velocity data on this time step
|
||||||
if (gpsDataToFuse && (PV_AidingMode == AID_ABSOLUTE) && (frontend->_fusionModeGPS != 3)) {
|
if (gpsDataToFuse && (PV_AidingMode == AID_ABSOLUTE) && (frontend->_fusionModeGPS != 3)) {
|
||||||
|
|
||||||
@ -433,7 +437,6 @@ void NavEKF3_core::SelectVelPosFusion()
|
|||||||
// use external nav system for position
|
// use external nav system for position
|
||||||
extNavUsedForPos = true;
|
extNavUsedForPos = true;
|
||||||
activeHgtSource = HGT_SOURCE_EXTNAV;
|
activeHgtSource = HGT_SOURCE_EXTNAV;
|
||||||
fuseVelData = false;
|
|
||||||
fuseHgtData = true;
|
fuseHgtData = true;
|
||||||
fusePosData = true;
|
fusePosData = true;
|
||||||
|
|
||||||
@ -443,9 +446,6 @@ void NavEKF3_core::SelectVelPosFusion()
|
|||||||
velPosObs[3] = extNavDataDelayed.pos.x;
|
velPosObs[3] = extNavDataDelayed.pos.x;
|
||||||
velPosObs[4] = extNavDataDelayed.pos.y;
|
velPosObs[4] = extNavDataDelayed.pos.y;
|
||||||
velPosObs[5] = extNavDataDelayed.pos.z;
|
velPosObs[5] = extNavDataDelayed.pos.z;
|
||||||
} else {
|
|
||||||
fuseVelData = false;
|
|
||||||
fusePosData = false;
|
|
||||||
}
|
}
|
||||||
|
|
||||||
// fuse external navigation velocity data if available
|
// fuse external navigation velocity data if available
|
||||||
|
Loading…
Reference in New Issue
Block a user