AP_NavEKF3: fix getLLH when no GPS

This commit is contained in:
Randy Mackay 2020-05-02 11:51:54 +09:00 committed by Andrew Tridgell
parent b95bc9076b
commit 67903a29e2
1 changed files with 5 additions and 1 deletions

View File

@ -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;
}
}