From f35efc56e084bc9ab827dc16f68430d58b50401e Mon Sep 17 00:00:00 2001 From: Randy Mackay Date: Fri, 2 Jan 2015 17:06:22 +0900 Subject: [PATCH] InertialNav_EKF: get_filter_status replaces position_ok --- .../AP_InertialNav/AP_InertialNav_NavEKF.cpp | 25 ++++++------------- .../AP_InertialNav/AP_InertialNav_NavEKF.h | 13 +++------- 2 files changed, 11 insertions(+), 27 deletions(-) diff --git a/libraries/AP_InertialNav/AP_InertialNav_NavEKF.cpp b/libraries/AP_InertialNav/AP_InertialNav_NavEKF.cpp index 585c82f873..b51ffc28bb 100644 --- a/libraries/AP_InertialNav/AP_InertialNav_NavEKF.cpp +++ b/libraries/AP_InertialNav/AP_InertialNav_NavEKF.cpp @@ -39,15 +39,16 @@ void AP_InertialNav_NavEKF::update(float dt) } /** - * position_ok - true if inertial based altitude and position can be trusted - * @return + * get_filter_status : returns filter status as a series of flags */ -bool AP_InertialNav_NavEKF::position_ok() const +nav_filter_status AP_InertialNav_NavEKF::get_filter_status() const { - if (_ahrs.have_inertial_nav() && _haveabspos) { - return true; + if (_ahrs.have_inertial_nav()) { + nav_filter_status ret; + _ahrs_ekf.get_NavEKF().getFilterStatus(ret); + return ret; } - return AP_InertialNav::position_ok(); + return AP_InertialNav::get_filter_status(); } /** @@ -143,18 +144,6 @@ float AP_InertialNav_NavEKF::get_velocity_xy() const return AP_InertialNav::get_velocity_xy(); } -/** - * altitude_ok - returns true if inertial based altitude and position can be trusted - * @return - */ -bool AP_InertialNav_NavEKF::altitude_ok() const -{ - if (_ahrs.have_inertial_nav() && _haveabspos) { - return true; - } - return AP_InertialNav::altitude_ok(); -} - /** * get_altitude - get latest altitude estimate in cm * @return diff --git a/libraries/AP_InertialNav/AP_InertialNav_NavEKF.h b/libraries/AP_InertialNav/AP_InertialNav_NavEKF.h index 4f2170434b..b77d29412b 100644 --- a/libraries/AP_InertialNav/AP_InertialNav_NavEKF.h +++ b/libraries/AP_InertialNav/AP_InertialNav_NavEKF.h @@ -10,6 +10,8 @@ #ifndef __AP_INERTIALNAV_NAVEKF_H__ #define __AP_INERTIALNAV_NAVEKF_H__ +#include // definitions shared by inertial and ekf nav filters + class AP_InertialNav_NavEKF : public AP_InertialNav { public: @@ -32,10 +34,9 @@ public: void update(float dt); /** - * position_ok - true if inertial based altitude and position can be trusted - * @return + * get_filter_status - returns filter status as a series of flags */ - bool position_ok() const; + nav_filter_status get_filter_status() const; /** * get_position - returns the current position relative to the home location in cm. @@ -88,12 +89,6 @@ public: */ float get_velocity_xy() const; - /** - * altitude_ok - returns true if inertial based altitude and position can be trusted - * @return - */ - bool altitude_ok() const; - /** * get_altitude - get latest altitude estimate in cm * @return