AP_InertialNav: Add method to return EKF height above ground estimate

AP_InertialNav: Add validity flag to height above ground estimate
This commit is contained in:
Paul Riseborough 2015-04-06 17:19:53 +10:00 committed by Randy Mackay
parent e98edaa6cb
commit cab171b580
2 changed files with 20 additions and 0 deletions

View File

@ -120,6 +120,20 @@ float AP_InertialNav_NavEKF::get_altitude() const
return _relpos_cm.z;
}
/**
* getHgtAboveGnd - get latest height above ground level estimate in cm and a validity flag
*
* @return
*/
bool AP_InertialNav_NavEKF::get_hagl(float height) const
{
// true when estimate is valid
bool valid = _ahrs_ekf.get_NavEKF().getHAGL(height);
// convert height from m to cm
height *= 100.0f;
return valid;
}
/**
* get_velocity_z - returns the current climbrate.
*

View File

@ -88,6 +88,12 @@ public:
*/
float get_altitude() const;
/**
* getHgtAboveGnd - get latest altitude estimate above ground level in centimetres and validity flag
* @return
*/
bool get_hagl(float hagl) const;
/**
* get_velocity_z - returns the current climbrate.
*