mirror of https://github.com/ArduPilot/ardupilot
AP_InertialNav: remove dead get_hagl method
This commit is contained in:
parent
893b761533
commit
b77d4ad82a
|
@ -144,20 +144,6 @@ 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_hagl(height);
|
||||
// convert height from m to cm
|
||||
height *= 100.0f;
|
||||
return valid;
|
||||
}
|
||||
|
||||
/**
|
||||
* get_velocity_z - returns the current climbrate.
|
||||
*
|
||||
|
|
|
@ -88,12 +88,6 @@ 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.
|
||||
*
|
||||
|
|
Loading…
Reference in New Issue