From c3eff57f608b4ed3838e69d892a40479ac97bfa3 Mon Sep 17 00:00:00 2001 From: Peter Barker Date: Thu, 7 Dec 2017 15:27:56 +1100 Subject: [PATCH] AP_InertialNav: remove unused get_hgt_ctrl_limit --- libraries/AP_InertialNav/AP_InertialNav.h | 8 -------- .../AP_InertialNav/AP_InertialNav_NavEKF.cpp | 17 ----------------- .../AP_InertialNav/AP_InertialNav_NavEKF.h | 8 -------- 3 files changed, 33 deletions(-) diff --git a/libraries/AP_InertialNav/AP_InertialNav.h b/libraries/AP_InertialNav/AP_InertialNav.h index d34457c41d..afcdc62a4f 100644 --- a/libraries/AP_InertialNav/AP_InertialNav.h +++ b/libraries/AP_InertialNav/AP_InertialNav.h @@ -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. * diff --git a/libraries/AP_InertialNav/AP_InertialNav_NavEKF.cpp b/libraries/AP_InertialNav/AP_InertialNav_NavEKF.cpp index 9f87328292..9a3071a3ac 100644 --- a/libraries/AP_InertialNav/AP_InertialNav_NavEKF.cpp +++ b/libraries/AP_InertialNav/AP_InertialNav_NavEKF.cpp @@ -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. * diff --git a/libraries/AP_InertialNav/AP_InertialNav_NavEKF.h b/libraries/AP_InertialNav/AP_InertialNav_NavEKF.h index ecdb4d452f..b0376d9ece 100644 --- a/libraries/AP_InertialNav/AP_InertialNav_NavEKF.h +++ b/libraries/AP_InertialNav/AP_InertialNav_NavEKF.h @@ -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. *