AP_NavEKF: Add public method returning height above ground level

This commit is contained in:
priseborough 2014-11-30 20:26:11 +11:00 committed by Andrew Tridgell
parent d701cfcb75
commit a2bd3b4a42
2 changed files with 11 additions and 0 deletions

View File

@ -3693,6 +3693,13 @@ bool NavEKF::getLLH(struct Location &loc) const
return true;
}
// return the estimated height above ground level
bool NavEKF::getHAGL(float &HAGL) const
{
HAGL = flowStates[1] - state.position.z;
return !inhibitGndState;
}
// return data for debugging optical flow fusion
void NavEKF::getFlowDebug(float &scaleFactor, float &gndPos, float &flowInnovX, float &flowInnovY, float &augFlowInnovX, float &augFlowInnovY, float &rngInnov, float &range) const
{

View File

@ -144,6 +144,10 @@ public:
// return the last calculated latitude, longitude and height
bool getLLH(struct Location &loc) const;
// return estimated height above ground level
// return false if ground height is not being estimated.
bool getHAGL(float &HAGL) const;
// return the Euler roll, pitch and yaw angle in radians
void getEulerAngles(Vector3f &eulers) const;