diff --git a/libraries/AP_NavEKF/AP_NavEKF.cpp b/libraries/AP_NavEKF/AP_NavEKF.cpp index ac87d7a42b..06ddc7c4f4 100644 --- a/libraries/AP_NavEKF/AP_NavEKF.cpp +++ b/libraries/AP_NavEKF/AP_NavEKF.cpp @@ -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 { diff --git a/libraries/AP_NavEKF/AP_NavEKF.h b/libraries/AP_NavEKF/AP_NavEKF.h index f72f0f3967..7a12896cb7 100644 --- a/libraries/AP_NavEKF/AP_NavEKF.h +++ b/libraries/AP_NavEKF/AP_NavEKF.h @@ -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;