mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-22 00:28:30 -04:00
AP_NavEKF2: getLLH fix when no GPS available
This commit is contained in:
parent
a41c846a8c
commit
59adb2adda
@ -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;
|
||||
}
|
||||
|
Loading…
Reference in New Issue
Block a user