InertialNav_EKF: get_filter_status replaces position_ok
This commit is contained in:
parent
5d80481723
commit
f35efc56e0
@ -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
|
||||
|
@ -10,6 +10,8 @@
|
||||
#ifndef __AP_INERTIALNAV_NAVEKF_H__
|
||||
#define __AP_INERTIALNAV_NAVEKF_H__
|
||||
|
||||
#include <AP_Nav_Common.h> // 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
|
||||
|
Loading…
Reference in New Issue
Block a user