AP_InertialNav: Add function to return EKF height control limit

This commit is contained in:
Paul Riseborough 2015-04-23 13:27:51 +10:00 committed by Randy Mackay
parent cf04600710
commit 51624149e1
2 changed files with 23 additions and 0 deletions

View File

@ -134,6 +134,21 @@ bool AP_InertialNav_NavEKF::get_hagl(float height) const
return valid;
}
/**
* get_hgt_ctrl_limit - get maximum height to be observed by the control loops in cm and a validity flag
* this is used to limit height during optical flow navigation
* it will return invalid when no limiting is required
* @return
*/
bool AP_InertialNav_NavEKF::get_hgt_ctrl_limit(float limit) const
{
// true when estimate is valid
bool valid = _ahrs_ekf.get_NavEKF().getHeightControlLimit(limit);
// convert height from m to cm
limit *= 100.0f;
return valid;
}
/**
* get_velocity_z - returns the current climbrate.
*

View File

@ -94,6 +94,14 @@ public:
*/
bool get_hagl(float hagl) const;
/**
* get_hgt_ctrl_limit - get maximum height to be observed by the control loops in cm and a validity flag
* this is used to limit height during optical flow navigation
* it will return invalid when no limiting is required
* @return
*/
bool get_hgt_ctrl_limit(float limit) const;
/**
* get_velocity_z - returns the current climbrate.
*