AP_NavEKF2: Enable GPS velocity fusion to be inhibited
This commit is contained in:
parent
012b632d09
commit
ef624199f9
@ -304,8 +304,16 @@ void NavEKF2_core::SelectVelPosFusion()
|
|||||||
// check for and read new GPS data
|
// check for and read new GPS data
|
||||||
readGpsData();
|
readGpsData();
|
||||||
|
|
||||||
|
// Determine if we need to fuse position and velocity data on this time step
|
||||||
if (RecallGPS() && PV_AidingMode != AID_RELATIVE) {
|
if (RecallGPS() && PV_AidingMode != AID_RELATIVE) {
|
||||||
fuseVelData = true;
|
// Don't fuse velocity data if GPS doesn't support it
|
||||||
|
// If no aiding is avaialble, then we use zeroed GPS position and elocity data to constrain
|
||||||
|
// tilt errors assuming that the vehicle is not accelerating
|
||||||
|
if (frontend._fusionModeGPS <= 1 || PV_AidingMode == AID_NONE) {
|
||||||
|
fuseVelData = true;
|
||||||
|
} else {
|
||||||
|
fuseVelData = false;
|
||||||
|
}
|
||||||
fusePosData = true;
|
fusePosData = true;
|
||||||
} else {
|
} else {
|
||||||
fuseVelData = false;
|
fuseVelData = false;
|
||||||
|
Loading…
Reference in New Issue
Block a user