mirror of https://github.com/ArduPilot/ardupilot
InertialNav: get_filter_status replaces position_ok
altitude_ok also replaced.
This commit is contained in:
parent
7f5243026d
commit
5d80481723
|
@ -120,16 +120,30 @@ void AP_InertialNav::update(float dt)
|
|||
}
|
||||
}
|
||||
|
||||
/**
|
||||
* get_filter_status : returns filter status as a series of flags
|
||||
*/
|
||||
nav_filter_status AP_InertialNav::get_filter_status() const
|
||||
{
|
||||
nav_filter_status ret;
|
||||
ret.value = 0; // initialise to zero
|
||||
ret.flags.attitude = true;
|
||||
ret.flags.horiz_pos_abs = _xy_enabled;
|
||||
ret.flags.horiz_pos_rel = false;
|
||||
ret.flags.horiz_vel = _xy_enabled;
|
||||
ret.flags.terrain_alt = false;
|
||||
ret.flags.vert_pos = true;
|
||||
ret.flags.vert_vel = true;
|
||||
ret.flags.const_pos_mode = false;
|
||||
ret.flags.pred_horiz_pos_rel = false;
|
||||
ret.flags.pred_horiz_pos_abs = _xy_enabled;
|
||||
return ret;
|
||||
}
|
||||
|
||||
//
|
||||
// XY Axis specific methods
|
||||
//
|
||||
|
||||
// position_ok - return true if position has been initialised and have received gps data within 3 seconds
|
||||
bool AP_InertialNav::position_ok() const
|
||||
{
|
||||
return _xy_enabled;
|
||||
}
|
||||
|
||||
// check_home - checks if the home position has moved and offsets everything so it still lines up
|
||||
void AP_InertialNav::check_home() {
|
||||
if (!_xy_enabled) {
|
||||
|
|
|
@ -9,6 +9,7 @@
|
|||
#include <AP_Buffer.h> // FIFO buffer library
|
||||
#include <AP_GPS_Glitch.h> // GPS Glitch detection library
|
||||
#include <AP_Baro_Glitch.h> // Baro Glitch detection library
|
||||
#include <AP_Nav_Common.h> // definitions shared by inertial and ekf nav filters
|
||||
|
||||
#define AP_INTERTIALNAV_TC_XY 2.5f // default time constant for complementary filter's X & Y axis
|
||||
#define AP_INTERTIALNAV_TC_Z 5.0f // default time constant for complementary filter's Z axis
|
||||
|
@ -73,16 +74,15 @@ public:
|
|||
*/
|
||||
virtual void update(float dt);
|
||||
|
||||
/**
|
||||
* get_filter_status : returns filter status as a series of flags
|
||||
*/
|
||||
virtual nav_filter_status get_filter_status() const;
|
||||
|
||||
//
|
||||
// XY Axis specific methods
|
||||
//
|
||||
|
||||
/**
|
||||
* position_ok - true if inertial based altitude and position can be trusted
|
||||
* @return
|
||||
*/
|
||||
virtual bool position_ok() const;
|
||||
|
||||
/**
|
||||
* get_position - returns the current position relative to the home location in cm.
|
||||
*
|
||||
|
@ -150,12 +150,6 @@ public:
|
|||
// Z Axis methods
|
||||
//
|
||||
|
||||
/**
|
||||
* altitude_ok - returns true if inertial based altitude and position can be trusted
|
||||
* @return
|
||||
*/
|
||||
virtual bool altitude_ok() const { return true; }
|
||||
|
||||
/**
|
||||
* get_altitude - get latest altitude estimate in cm above the
|
||||
* reference position
|
||||
|
|
Loading…
Reference in New Issue