AP_NavEKF2: fix getLLH when no GPS

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

View File

@ -351,7 +351,11 @@ bool NavEKF2_core::getLLH(struct Location &loc) const
// correct for IMU offset (EKF calculations are at the IMU position)
loc.lat = EKF_origin.lat;
loc.lng = EKF_origin.lng;
loc.offset((lastKnownPositionNE.x + posOffsetNED.x), (lastKnownPositionNE.y + posOffsetNED.y));
if (PV_AidingMode == AID_NONE) {
loc.offset((lastKnownPositionNE.x + posOffsetNED.x), (lastKnownPositionNE.y + posOffsetNED.y));
} else {
loc.offset((outputDataNew.position.x + posOffsetNED.x), (outputDataNew.position.y + posOffsetNED.y));
}
return false;
}
}