mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-10 18:08:30 -04:00
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;
|
return true;
|
||||||
} else {
|
} else {
|
||||||
// if no GPS fix, provide last known position before entering the mode
|
// 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);
|
loc.offset(lastKnownPositionNE.x, lastKnownPositionNE.y);
|
||||||
return false;
|
return false;
|
||||||
}
|
}
|
||||||
|
Loading…
Reference in New Issue
Block a user