From b77d4ad82abb74439c4a9d37796b3a694bce82f3 Mon Sep 17 00:00:00 2001 From: Peter Barker Date: Wed, 4 Apr 2018 22:48:28 +1000 Subject: [PATCH] AP_InertialNav: remove dead get_hagl method --- libraries/AP_InertialNav/AP_InertialNav_NavEKF.cpp | 14 -------------- libraries/AP_InertialNav/AP_InertialNav_NavEKF.h | 6 ------ 2 files changed, 20 deletions(-) diff --git a/libraries/AP_InertialNav/AP_InertialNav_NavEKF.cpp b/libraries/AP_InertialNav/AP_InertialNav_NavEKF.cpp index 9a3071a3ac..804e98ecf6 100644 --- a/libraries/AP_InertialNav/AP_InertialNav_NavEKF.cpp +++ b/libraries/AP_InertialNav/AP_InertialNav_NavEKF.cpp @@ -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. * diff --git a/libraries/AP_InertialNav/AP_InertialNav_NavEKF.h b/libraries/AP_InertialNav/AP_InertialNav_NavEKF.h index b0376d9ece..c9411f2f83 100644 --- a/libraries/AP_InertialNav/AP_InertialNav_NavEKF.h +++ b/libraries/AP_InertialNav/AP_InertialNav_NavEKF.h @@ -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. *