AP_NavEKF2: getLLH fix when no GPS available

This commit is contained in:
Randy Mackay 2020-04-24 15:02:19 +09:00
parent 12c0d452e9
commit a6b825324a
1 changed files with 2 additions and 0 deletions

View File

@ -343,6 +343,8 @@ bool NavEKF2_core::getLLH(struct Location &loc) const
} else {
// if no GPS fix, provide last known position before entering the mode
// 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));
return false;
}