mirror of https://github.com/ArduPilot/ardupilot
AP_NavEKF3: getLLH fix when no GPS available
This commit is contained in:
parent
59adb2adda
commit
0da8f39fd6
|
@ -339,6 +339,8 @@ bool NavEKF3_core::getLLH(struct Location &loc) const
|
|||
return true;
|
||||
} else {
|
||||
// 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);
|
||||
return false;
|
||||
}
|
||||
|
|
Loading…
Reference in New Issue