AP_NavEKF3: fix getLLH when no GPS
This commit is contained in:
parent
b95bc9076b
commit
67903a29e2
@ -347,7 +347,11 @@ bool NavEKF3_core::getLLH(struct Location &loc) const
|
||||
// if no GPS fix, provide last known position before entering the mode
|
||||
loc.lat = EKF_origin.lat;
|
||||
loc.lng = EKF_origin.lng;
|
||||
loc.offset(lastKnownPositionNE.x, lastKnownPositionNE.y);
|
||||
if (PV_AidingMode == AID_NONE) {
|
||||
loc.offset(lastKnownPositionNE.x, lastKnownPositionNE.y);
|
||||
} else {
|
||||
loc.offset(outputDataNew.position.x, outputDataNew.position.y);
|
||||
}
|
||||
return false;
|
||||
}
|
||||
}
|
||||
|
Loading…
Reference in New Issue
Block a user