AP_InertialNav: remove unused get_hgt_ctrl_limit

This commit is contained in:
Peter Barker 2017-12-07 15:27:56 +11:00 committed by Randy Mackay
parent a1c982be4a
commit c3eff57f60
3 changed files with 0 additions and 33 deletions

View File

@ -104,14 +104,6 @@ public:
*/
virtual float get_altitude() const = 0;
/**
* 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
*/
virtual bool get_hgt_ctrl_limit(float& limit) const = 0;
/**
* get_velocity_z - returns the current climbrate.
*

View File

@ -158,23 +158,6 @@ 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
if (_ahrs_ekf.get_hgt_ctrl_limit(limit)) {
// convert height from m to cm
limit *= 100.0f;
return true;
}
return false;
}
/**
* get_velocity_z - returns the current climbrate.
*

View File

@ -94,14 +94,6 @@ 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.
*