AP_NavEKF: Added public function to get NED position

This commit is contained in:
Paul Riseborough 2013-12-31 15:27:35 +11:00 committed by Andrew Tridgell
parent 2c567cd721
commit cb42e1e490
1 changed files with 8 additions and 0 deletions

View File

@ -1887,6 +1887,14 @@ void NavEKF::getVelNED(Vector3f &vel)
vel.z = states[6];
}
bool NavEKF::getPosNED(Vector3f &pos)
{
pos.x = states[7];
pos.y = states[8];
pos.z = states[9];
return true;
}
void NavEKF::calcposNE(float lat, float lon)
{
posNE[0] = RADIUS_OF_EARTH * (lat - latRef);