// Return the last calculated NED position relative to the reference point (m).
// if a calculated solution is not available, use the best available data and return false
boolNavEKF2_core::getPosNED(Vector3f&pos)const
{
// The EKF always has a height estimate regardless of mode of operation
pos.z=outputDataNew.position.z;
// There are three modes of operation, absolute position (GPS fusion), relative position (optical flow fusion) and constant position (no position estimate available)
nav_filter_statusstatus;
getFilterStatus(status);
if(PV_AidingMode!=AID_NONE){
// This is the normal mode of operation where we can use the EKF position states
pos.x=outputDataNew.position.x;
pos.y=outputDataNew.position.y;
returntrue;
}else{
// In constant position mode the EKF position states are at the origin, so we cannot use them as a position estimate