PX4 Firmware
PX4 Autopilot Software http://px4.io
EstimatorInterface Class Referenceabstract

#include <estimator_interface.h>

Inheritance diagram for EstimatorInterface:
Collaboration diagram for EstimatorInterface:

Classes

struct  _gps_pos_prev
 
struct  _pos_ref
 

Public Types

typedef AlphaFilter< Vector3f > AlphaFilterVector3f
 

Public Member Functions

 EstimatorInterface ()=default
 
virtual ~EstimatorInterface ()=default
 
virtual bool init (uint64_t timestamp)=0
 
virtual void reset (uint64_t timestamp)=0
 
virtual void resetStates ()=0
 
virtual void resetStatesAndCovariances ()=0
 
virtual bool update ()=0
 
virtual void get_vel_pos_innov (float vel_pos_innov[6])=0
 
virtual void get_aux_vel_innov (float aux_vel_innov[2])=0
 
virtual void get_mag_innov (float mag_innov[3])=0
 
virtual void get_airspeed_innov (float *airspeed_innov)=0
 
virtual void get_beta_innov (float *beta_innov)=0
 
virtual void get_heading_innov (float *heading_innov)=0
 
virtual void get_vel_pos_innov_var (float vel_pos_innov_var[6])=0
 
virtual void get_mag_innov_var (float mag_innov_var[3])=0
 
virtual void get_airspeed_innov_var (float *get_airspeed_innov_var)=0
 
virtual void get_beta_innov_var (float *get_beta_innov_var)=0
 
virtual void get_heading_innov_var (float *heading_innov_var)=0
 
virtual void get_state_delayed (float *state)=0
 
virtual void get_wind_velocity (float *wind)=0
 
virtual void get_wind_velocity_var (float *wind_var)=0
 
virtual void get_true_airspeed (float *tas)=0
 
virtual void get_vel_var (Vector3f &vel_var)=0
 
virtual void get_pos_var (Vector3f &pos_var)=0
 
virtual void get_flow_innov_var (float flow_innov_var[2])=0
 
virtual void get_flow_innov (float flow_innov[2])=0
 
virtual void get_drag_innov_var (float drag_innov_var[2])=0
 
virtual void get_drag_innov (float drag_innov[2])=0
 
virtual void getHaglInnovVar (float *hagl_innov_var)=0
 
virtual void getHaglInnov (float *hagl_innov)=0
 
void get_hagl_innov_var (float *hagl_innov_var)
 
void get_hagl_innov (float *hagl_innov)
 
virtual void get_output_tracking_error (float error[3])=0
 
virtual void get_imu_vibe_metrics (float vibe[3])=0
 
virtual bool get_gps_drift_metrics (float drift[3], bool *blocked)=0
 
virtual bool get_ekf_origin (uint64_t *origin_time, map_projection_reference_s *origin_pos, float *origin_alt)=0
 
virtual void get_ekf_gpos_accuracy (float *ekf_eph, float *ekf_epv)=0
 
virtual void get_ekf_lpos_accuracy (float *ekf_eph, float *ekf_epv)=0
 
virtual void get_ekf_vel_accuracy (float *ekf_evh, float *ekf_evv)=0
 
virtual void get_ekf_ctrl_limits (float *vxy_max, float *vz_max, float *hagl_min, float *hagl_max)=0
 
virtual bool collect_gps (const gps_message &gps)=0
 
virtual bool collect_imu (const imuSample &imu)=0
 
void setIMUData (const imuSample &imu_sample)
 
void setIMUData (uint64_t time_usec, uint64_t delta_ang_dt, uint64_t delta_vel_dt, float(&delta_ang)[3], float(&delta_vel)[3])
 
void setMagData (uint64_t time_usec, float(&data)[3])
 
void setGpsData (uint64_t time_usec, const gps_message &gps)
 
void setBaroData (uint64_t time_usec, float data)
 
void setAirspeedData (uint64_t time_usec, float true_airspeed, float eas2tas)
 
void setRangeData (uint64_t time_usec, float data, int8_t quality)
 
void setOpticalFlowData (uint64_t time_usec, flow_message *flow)
 
void setExtVisionData (uint64_t time_usec, ext_vision_message *evdata)
 
void setAuxVelData (uint64_t time_usec, float(&data)[2], float(&variance)[2])
 
parametersgetParamHandle ()
 
void set_in_air_status (bool in_air)
 
virtual bool reset_imu_bias ()=0
 
bool attitude_valid ()
 
bool get_in_air_status ()
 
bool get_wind_status ()
 
void set_is_fixed_wing (bool is_fixed_wing)
 
void set_fuse_beta_flag (bool fuse_beta)
 
void set_gnd_effect_flag (bool gnd_effect)
 
void set_air_density (float air_density)
 
void set_rangefinder_limits (float min_distance, float max_distance)
 
void set_optical_flow_limits (float max_flow_rate, float min_distance, float max_distance)
 
virtual bool global_position_is_valid ()=0
 
bool inertial_dead_reckoning ()
 
virtual bool isTerrainEstimateValid () const =0
 
bool get_terrain_valid ()
 
virtual void getTerrainVertPos (float *ret)=0
 
void get_terrain_vert_pos (float *ret)
 
bool local_position_is_valid ()
 
const matrix::Quatfget_quaternion () const
 
virtual void get_ev2ekf_quaternion (float *quat)=0
 
void get_velocity (float *vel)
 
void get_vel_deriv_ned (float *vel_deriv)
 
void get_pos_d_deriv (float *pos_d_deriv)
 
void get_position (float *pos)
 
void copy_timestamp (uint64_t *time_us)
 
bool get_mag_decl_deg (float *val)
 
virtual void get_accel_bias (float bias[3])=0
 
virtual void get_gyro_bias (float bias[3])=0
 
void get_control_mode (uint32_t *val)
 
void get_filter_fault_status (uint16_t *val)
 
bool isVehicleAtRest () const
 
virtual void get_gps_check_status (uint16_t *val)=0
 
virtual void get_posD_reset (float *delta, uint8_t *counter)=0
 
virtual void get_velD_reset (float *delta, uint8_t *counter)=0
 
virtual void get_posNE_reset (float delta[2], uint8_t *counter)=0
 
virtual void get_velNE_reset (float delta[2], uint8_t *counter)=0
 
virtual void get_quat_reset (float delta_quat[4], uint8_t *counter)=0
 
virtual void get_innovation_test_status (uint16_t *status, float *mag, float *vel, float *pos, float *hgt, float *tas, float *hagl, float *beta)=0
 
virtual void get_ekf_soln_status (uint16_t *status)=0
 
float get_dt_imu_avg () const
 
imuSample get_imu_sample_delayed ()
 
baroSample get_baro_sample_delayed ()
 
void print_status ()
 

Static Public Attributes

static constexpr unsigned FILTER_UPDATE_PERIOD_MS {8}
 
static constexpr float FILTER_UPDATE_PERIOD_S {FILTER_UPDATE_PERIOD_MS * 0.001f}
 

Protected Member Functions

bool initialise_interface (uint64_t timestamp)
 
void unallocate_buffers ()
 
Vector3f cross_product (const Vector3f &vecIn1, const Vector3f &vecIn2)
 
Matrix3f quat_to_invrotmat (const Quatf &quat)
 

Protected Attributes

parameters _params
 
uint8_t _obs_buffer_length {0}
 
uint8_t _imu_buffer_length {0}
 
unsigned _min_obs_interval_us {0}
 
float _dt_imu_avg {0.0f}
 
imuSample _imu_sample_delayed {}
 
magSample _mag_sample_delayed {}
 
baroSample _baro_sample_delayed {}
 
gpsSample _gps_sample_delayed {}
 
rangeSample _range_sample_delayed {}
 
airspeedSample _airspeed_sample_delayed {}
 
flowSample _flow_sample_delayed {}
 
extVisionSample _ev_sample_delayed {}
 
dragSample _drag_sample_delayed {}
 
dragSample _drag_down_sampled {}
 
auxVelSample _auxvel_sample_delayed {}
 
uint8_t _drag_sample_count {0}
 
float _drag_sample_time_dt {0.0f}
 
float _air_density {CONSTANTS_AIR_DENSITY_SEA_LEVEL_15C}
 
float _rng_valid_min_val {0.0f}
 minimum distance that the rangefinder can measure (m) More...
 
float _rng_valid_max_val {0.0f}
 maximum distance that the rangefinder can measure (m) More...
 
float _flow_max_rate {0.0f}
 maximum angular flow rate that the optical flow sensor can measure (rad/s) More...
 
float _flow_min_distance {0.0f}
 minimum distance that the optical flow sensor can operate at (m) More...
 
float _flow_max_distance {0.0f}
 maximum distance that the optical flow sensor can operate at (m) More...
 
outputSample _output_sample_delayed {}
 
outputSample _output_new {}
 
outputVert _output_vert_delayed {}
 
outputVert _output_vert_new {}
 
imuSample _imu_sample_new {}
 
Matrix3f _R_to_earth_now
 
Vector3f _vel_imu_rel_body_ned
 
Vector3f _vel_deriv_ned
 
bool _imu_updated {false}
 
bool _initialised {false}
 
bool _NED_origin_initialised {false}
 
bool _gps_speed_valid {false}
 
float _gps_origin_eph {0.0f}
 
float _gps_origin_epv {0.0f}
 
float _gps_alt_prev {0.0f}
 
float _gps_yaw_offset {0.0f}
 
float _yaw_test_ratio {0.0f}
 
float _mag_test_ratio [3] {}
 
float _vel_pos_test_ratio [6] {}
 
float _tas_test_ratio {0.0f}
 
float _terr_test_ratio {0.0f}
 
float _beta_test_ratio {0.0f}
 
float _drag_test_ratio [2] {}
 
innovation_fault_status_u _innov_check_fail_status {}
 
bool _is_dead_reckoning {false}
 
bool _deadreckon_time_exceeded {true}
 
bool _is_wind_dead_reckoning {false}
 
Vector3f _delta_ang_prev
 
Vector3f _delta_vel_prev
 
float _vibe_metrics [3] {}
 
float _gps_drift_metrics [3] {}
 
bool _vehicle_at_rest {false}
 
uint64_t _time_last_move_detect_us {0}
 
bool _gps_drift_updated {false}
 
RingBuffer< imuSample_imu_buffer
 
RingBuffer< gpsSample_gps_buffer
 
RingBuffer< magSample_mag_buffer
 
RingBuffer< baroSample_baro_buffer
 
RingBuffer< rangeSample_range_buffer
 
RingBuffer< airspeedSample_airspeed_buffer
 
RingBuffer< flowSample_flow_buffer
 
RingBuffer< extVisionSample_ext_vision_buffer
 
RingBuffer< outputSample_output_buffer
 
RingBuffer< outputVert_output_vert_buffer
 
RingBuffer< dragSample_drag_buffer
 
RingBuffer< auxVelSample_auxvel_buffer
 
bool _gps_buffer_fail {false}
 
bool _mag_buffer_fail {false}
 
bool _baro_buffer_fail {false}
 
bool _range_buffer_fail {false}
 
bool _airspeed_buffer_fail {false}
 
bool _flow_buffer_fail {false}
 
bool _ev_buffer_fail {false}
 
bool _drag_buffer_fail {false}
 
bool _auxvel_buffer_fail {false}
 
uint64_t _time_last_imu {0}
 
uint64_t _time_last_gps {0}
 
uint64_t _time_last_mag {0}
 
uint64_t _time_last_baro {0}
 
uint64_t _time_last_range {0}
 
uint64_t _time_last_airspeed {0}
 
uint64_t _time_last_ext_vision {0}
 
uint64_t _time_last_optflow {0}
 
uint64_t _time_last_gnd_effect_on {0}
 
uint64_t _time_last_auxvel {0}
 
fault_status_u _fault_status {}
 
float _mag_declination_gps {0.0f}
 
float _mag_inclination_gps {0.0f}
 
float _mag_strength_gps {0.0f}
 
filter_control_status_u _control_status {}
 
filter_control_status_u _control_status_prev {}
 

Detailed Description

Definition at line 55 of file estimator_interface.h.

Member Typedef Documentation

◆ AlphaFilterVector3f

Definition at line 59 of file estimator_interface.h.

Constructor & Destructor Documentation

◆ EstimatorInterface()

EstimatorInterface::EstimatorInterface ( )
default

◆ ~EstimatorInterface()

virtual EstimatorInterface::~EstimatorInterface ( )
virtualdefault

Member Function Documentation

◆ attitude_valid()

bool EstimatorInterface::attitude_valid ( )
inline

Definition at line 228 of file estimator_interface.h.

References ISFINITE.

Referenced by Ekf2::publish_attitude(), and TEST_F().

Here is the caller graph for this function:

◆ collect_gps()

virtual bool EstimatorInterface::collect_gps ( const gps_message gps)
pure virtual

Implemented in Ekf.

Referenced by setGpsData().

Here is the caller graph for this function:

◆ collect_imu()

virtual bool EstimatorInterface::collect_imu ( const imuSample imu)
pure virtual

Implemented in Ekf.

Referenced by setIMUData().

Here is the caller graph for this function:

◆ copy_timestamp()

void EstimatorInterface::copy_timestamp ( uint64_t *  time_us)
inline

Definition at line 328 of file estimator_interface.h.

◆ cross_product()

Vector3f EstimatorInterface::cross_product ( const Vector3f &  vecIn1,
const Vector3f &  vecIn2 
)
protected

Definition at line 1347 of file ekf_helper.cpp.

Referenced by Ekf::calculateOutputStates(), Ekf::controlExternalVisionFusion(), Ekf::controlGpsFusion(), Ekf::fuseFlowForTerrain(), Ekf::fuseOptFlow(), and setIMUData().

Here is the caller graph for this function:

◆ get_accel_bias()

virtual void EstimatorInterface::get_accel_bias ( float  bias[3])
pure virtual

Implemented in Ekf.

◆ get_airspeed_innov()

virtual void EstimatorInterface::get_airspeed_innov ( float *  airspeed_innov)
pure virtual

Implemented in Ekf.

◆ get_airspeed_innov_var()

virtual void EstimatorInterface::get_airspeed_innov_var ( float *  get_airspeed_innov_var)
pure virtual

Implemented in Ekf.

◆ get_aux_vel_innov()

virtual void EstimatorInterface::get_aux_vel_innov ( float  aux_vel_innov[2])
pure virtual

Implemented in Ekf.

◆ get_baro_sample_delayed()

baroSample EstimatorInterface::get_baro_sample_delayed ( )
inline

Definition at line 403 of file estimator_interface.h.

References print_status().

Here is the call graph for this function:

◆ get_beta_innov()

virtual void EstimatorInterface::get_beta_innov ( float *  beta_innov)
pure virtual

Implemented in Ekf.

◆ get_beta_innov_var()

virtual void EstimatorInterface::get_beta_innov_var ( float *  get_beta_innov_var)
pure virtual

Implemented in Ekf.

◆ get_control_mode()

void EstimatorInterface::get_control_mode ( uint32_t *  val)
inline

Definition at line 352 of file estimator_interface.h.

Referenced by Ekf2::Run(), and TEST_F().

Here is the caller graph for this function:

◆ get_drag_innov()

virtual void EstimatorInterface::get_drag_innov ( float  drag_innov[2])
pure virtual

Implemented in Ekf.

◆ get_drag_innov_var()

virtual void EstimatorInterface::get_drag_innov_var ( float  drag_innov_var[2])
pure virtual

Implemented in Ekf.

◆ get_dt_imu_avg()

float EstimatorInterface::get_dt_imu_avg ( ) const
inline

Definition at line 394 of file estimator_interface.h.

◆ get_ekf_ctrl_limits()

virtual void EstimatorInterface::get_ekf_ctrl_limits ( float *  vxy_max,
float *  vz_max,
float *  hagl_min,
float *  hagl_max 
)
pure virtual

Implemented in Ekf.

◆ get_ekf_gpos_accuracy()

virtual void EstimatorInterface::get_ekf_gpos_accuracy ( float *  ekf_eph,
float *  ekf_epv 
)
pure virtual

Implemented in Ekf.

◆ get_ekf_lpos_accuracy()

virtual void EstimatorInterface::get_ekf_lpos_accuracy ( float *  ekf_eph,
float *  ekf_epv 
)
pure virtual

Implemented in Ekf.

◆ get_ekf_origin()

virtual bool EstimatorInterface::get_ekf_origin ( uint64_t *  origin_time,
map_projection_reference_s origin_pos,
float *  origin_alt 
)
pure virtual

Implemented in Ekf.

◆ get_ekf_soln_status()

virtual void EstimatorInterface::get_ekf_soln_status ( uint16_t *  status)
pure virtual

Implemented in Ekf.

◆ get_ekf_vel_accuracy()

virtual void EstimatorInterface::get_ekf_vel_accuracy ( float *  ekf_evh,
float *  ekf_evv 
)
pure virtual

Implemented in Ekf.

◆ get_ev2ekf_quaternion()

virtual void EstimatorInterface::get_ev2ekf_quaternion ( float *  quat)
pure virtual

Implemented in Ekf.

◆ get_filter_fault_status()

void EstimatorInterface::get_filter_fault_status ( uint16_t *  val)
inline

Definition at line 358 of file estimator_interface.h.

Referenced by Ekf2::Run().

Here is the caller graph for this function:

◆ get_flow_innov()

virtual void EstimatorInterface::get_flow_innov ( float  flow_innov[2])
pure virtual

Implemented in Ekf.

◆ get_flow_innov_var()

virtual void EstimatorInterface::get_flow_innov_var ( float  flow_innov_var[2])
pure virtual

Implemented in Ekf.

◆ get_gps_check_status()

virtual void EstimatorInterface::get_gps_check_status ( uint16_t *  val)
pure virtual

Implemented in Ekf.

◆ get_gps_drift_metrics()

virtual bool EstimatorInterface::get_gps_drift_metrics ( float  drift[3],
bool *  blocked 
)
pure virtual

Implemented in Ekf.

◆ get_gyro_bias()

virtual void EstimatorInterface::get_gyro_bias ( float  bias[3])
pure virtual

Implemented in Ekf.

◆ get_hagl_innov()

void EstimatorInterface::get_hagl_innov ( float *  hagl_innov)
inline

Definition at line 136 of file estimator_interface.h.

References data, and gps.

Referenced by Ekf2::Run().

Here is the caller graph for this function:

◆ get_hagl_innov_var()

void EstimatorInterface::get_hagl_innov_var ( float *  hagl_innov_var)
inline

Definition at line 134 of file estimator_interface.h.

Referenced by Ekf2::Run().

Here is the caller graph for this function:

◆ get_heading_innov()

virtual void EstimatorInterface::get_heading_innov ( float *  heading_innov)
pure virtual

Implemented in Ekf.

◆ get_heading_innov_var()

virtual void EstimatorInterface::get_heading_innov_var ( float *  heading_innov_var)
pure virtual

Implemented in Ekf.

◆ get_imu_sample_delayed()

imuSample EstimatorInterface::get_imu_sample_delayed ( )
inline

Definition at line 397 of file estimator_interface.h.

Referenced by TEST_P().

Here is the caller graph for this function:

◆ get_imu_vibe_metrics()

virtual void EstimatorInterface::get_imu_vibe_metrics ( float  vibe[3])
pure virtual

Implemented in Ekf.

◆ get_in_air_status()

bool EstimatorInterface::get_in_air_status ( )
inline

Definition at line 231 of file estimator_interface.h.

◆ get_innovation_test_status()

virtual void EstimatorInterface::get_innovation_test_status ( uint16_t *  status,
float *  mag,
float *  vel,
float *  pos,
float *  hgt,
float *  tas,
float *  hagl,
float *  beta 
)
pure virtual

Implemented in Ekf.

◆ get_mag_decl_deg()

bool EstimatorInterface::get_mag_decl_deg ( float *  val)
inline

Definition at line 336 of file estimator_interface.h.

References math::degrees(), and MASK_SAVE_GEO_DECL.

Referenced by Ekf2::update_mag_decl().

Here is the call graph for this function:
Here is the caller graph for this function:

◆ get_mag_innov()

virtual void EstimatorInterface::get_mag_innov ( float  mag_innov[3])
pure virtual

Implemented in Ekf.

◆ get_mag_innov_var()

virtual void EstimatorInterface::get_mag_innov_var ( float  mag_innov_var[3])
pure virtual

Implemented in Ekf.

◆ get_output_tracking_error()

virtual void EstimatorInterface::get_output_tracking_error ( float  error[3])
pure virtual

Implemented in Ekf.

◆ get_pos_d_deriv()

void EstimatorInterface::get_pos_d_deriv ( float *  pos_d_deriv)
inline

Definition at line 311 of file estimator_interface.h.

Referenced by Ekf2::Run().

Here is the caller graph for this function:

◆ get_pos_var()

virtual void EstimatorInterface::get_pos_var ( Vector3f &  pos_var)
pure virtual

Implemented in Ekf.

◆ get_posD_reset()

virtual void EstimatorInterface::get_posD_reset ( float *  delta,
uint8_t *  counter 
)
pure virtual

Implemented in Ekf.

◆ get_position()

void EstimatorInterface::get_position ( float *  pos)
inline

Definition at line 318 of file estimator_interface.h.

Referenced by Ekf2::Run(), and TEST_F().

Here is the caller graph for this function:

◆ get_posNE_reset()

virtual void EstimatorInterface::get_posNE_reset ( float  delta[2],
uint8_t *  counter 
)
pure virtual

Implemented in Ekf.

◆ get_quat_reset()

virtual void EstimatorInterface::get_quat_reset ( float  delta_quat[4],
uint8_t *  counter 
)
pure virtual

Implemented in Ekf.

◆ get_quaternion()

const matrix::Quatf& EstimatorInterface::get_quaternion ( ) const
inline

Definition at line 287 of file estimator_interface.h.

Referenced by Ekf2::get_vel_body_wind(), and Ekf2::Run().

Here is the caller graph for this function:

◆ get_state_delayed()

virtual void EstimatorInterface::get_state_delayed ( float *  state)
pure virtual

Implemented in Ekf.

◆ get_terrain_valid()

bool EstimatorInterface::get_terrain_valid ( )
inline

Definition at line 277 of file estimator_interface.h.

Referenced by Ekf2::Run().

Here is the caller graph for this function:

◆ get_terrain_vert_pos()

void EstimatorInterface::get_terrain_vert_pos ( float *  ret)
inline

Definition at line 282 of file estimator_interface.h.

Referenced by Ekf2::Run().

Here is the caller graph for this function:

◆ get_true_airspeed()

virtual void EstimatorInterface::get_true_airspeed ( float *  tas)
pure virtual

Implemented in Ekf.

◆ get_vel_deriv_ned()

void EstimatorInterface::get_vel_deriv_ned ( float *  vel_deriv)
inline

Definition at line 303 of file estimator_interface.h.

Referenced by Ekf2::Run().

Here is the caller graph for this function:

◆ get_vel_pos_innov()

virtual void EstimatorInterface::get_vel_pos_innov ( float  vel_pos_innov[6])
pure virtual

Implemented in Ekf.

◆ get_vel_pos_innov_var()

virtual void EstimatorInterface::get_vel_pos_innov_var ( float  vel_pos_innov_var[6])
pure virtual

Implemented in Ekf.

◆ get_vel_var()

virtual void EstimatorInterface::get_vel_var ( Vector3f &  vel_var)
pure virtual

Implemented in Ekf.

◆ get_velD_reset()

virtual void EstimatorInterface::get_velD_reset ( float *  delta,
uint8_t *  counter 
)
pure virtual

Implemented in Ekf.

◆ get_velNE_reset()

virtual void EstimatorInterface::get_velNE_reset ( float  delta[2],
uint8_t *  counter 
)
pure virtual

Implemented in Ekf.

◆ get_velocity()

void EstimatorInterface::get_velocity ( float *  vel)
inline

Definition at line 293 of file estimator_interface.h.

Referenced by Ekf2::get_vel_body_wind(), Ekf2::Run(), and TEST_F().

Here is the caller graph for this function:

◆ get_wind_status()

bool EstimatorInterface::get_wind_status ( )
inline

Definition at line 234 of file estimator_interface.h.

Referenced by Ekf2::publish_wind_estimate().

Here is the caller graph for this function:

◆ get_wind_velocity()

virtual void EstimatorInterface::get_wind_velocity ( float *  wind)
pure virtual

Implemented in Ekf.

◆ get_wind_velocity_var()

virtual void EstimatorInterface::get_wind_velocity_var ( float *  wind_var)
pure virtual

Implemented in Ekf.

◆ getHaglInnov()

virtual void EstimatorInterface::getHaglInnov ( float *  hagl_innov)
pure virtual

Implemented in Ekf.

◆ getHaglInnovVar()

virtual void EstimatorInterface::getHaglInnovVar ( float *  hagl_innov_var)
pure virtual

Implemented in Ekf.

◆ getParamHandle()

parameters* EstimatorInterface::getParamHandle ( )
inline

Definition at line 215 of file estimator_interface.h.

◆ getTerrainVertPos()

virtual void EstimatorInterface::getTerrainVertPos ( float *  ret)
pure virtual

Implemented in Ekf.

◆ global_position_is_valid()

virtual bool EstimatorInterface::global_position_is_valid ( )
pure virtual

Implemented in Ekf.

Referenced by print_status().

Here is the caller graph for this function:

◆ inertial_dead_reckoning()

bool EstimatorInterface::inertial_dead_reckoning ( )
inline

Definition at line 273 of file estimator_interface.h.

Referenced by Ekf2::Run().

Here is the caller graph for this function:

◆ init()

virtual bool EstimatorInterface::init ( uint64_t  timestamp)
pure virtual

Implemented in Ekf.

Referenced by setIMUData().

Here is the caller graph for this function:

◆ initialise_interface()

◆ isTerrainEstimateValid()

virtual bool EstimatorInterface::isTerrainEstimateValid ( ) const
pure virtual

Implemented in Ekf.

◆ isVehicleAtRest()

bool EstimatorInterface::isVehicleAtRest ( ) const
inline

Definition at line 363 of file estimator_interface.h.

References counter, and status.

◆ local_position_is_valid()

bool EstimatorInterface::local_position_is_valid ( )

Definition at line 564 of file estimator_interface.cpp.

References _deadreckon_time_exceeded.

Referenced by Ekf2::print_status(), print_status(), and Ekf2::Run().

Here is the caller graph for this function:

◆ print_status()

void EstimatorInterface::print_status ( )

Definition at line 570 of file estimator_interface.cpp.

References _airspeed_buffer, _baro_buffer, _drag_buffer, _ext_vision_buffer, _flow_buffer, _gps_buffer, _imu_buffer, _mag_buffer, _output_buffer, _output_vert_buffer, _range_buffer, ECL_INFO, RingBuffer< data_type >::get_length(), RingBuffer< data_type >::get_total_size(), global_position_is_valid(), and local_position_is_valid().

Here is the call graph for this function:

◆ quat_to_invrotmat()

Matrix3f EstimatorInterface::quat_to_invrotmat ( const Quatf &  quat)
protected

Definition at line 1358 of file ekf_helper.cpp.

Referenced by Ekf::fuseDrag(), Ekf::fuseFlowForTerrain(), Ekf::fuseMag(), Ekf::fuseOptFlow(), and Ekf::fuseSideslip().

Here is the caller graph for this function:

◆ reset()

virtual void EstimatorInterface::reset ( uint64_t  timestamp)
pure virtual

Implemented in Ekf.

◆ reset_imu_bias()

virtual bool EstimatorInterface::reset_imu_bias ( )
pure virtual

Implemented in Ekf.

◆ resetStates()

virtual void EstimatorInterface::resetStates ( )
pure virtual

Implemented in Ekf.

◆ resetStatesAndCovariances()

virtual void EstimatorInterface::resetStatesAndCovariances ( )
pure virtual

Implemented in Ekf.

◆ set_air_density()

void EstimatorInterface::set_air_density ( float  air_density)
inline

Definition at line 252 of file estimator_interface.h.

Referenced by Ekf2::Run().

Here is the caller graph for this function:

◆ set_fuse_beta_flag()

void EstimatorInterface::set_fuse_beta_flag ( bool  fuse_beta)
inline

Definition at line 240 of file estimator_interface.h.

Referenced by Ekf2::Run().

Here is the caller graph for this function:

◆ set_gnd_effect_flag()

void EstimatorInterface::set_gnd_effect_flag ( bool  gnd_effect)
inline

Definition at line 245 of file estimator_interface.h.

Referenced by Ekf2::Run().

Here is the caller graph for this function:

◆ set_in_air_status()

void EstimatorInterface::set_in_air_status ( bool  in_air)
inline

Definition at line 218 of file estimator_interface.h.

Referenced by Ekf2::Run().

Here is the caller graph for this function:

◆ set_is_fixed_wing()

void EstimatorInterface::set_is_fixed_wing ( bool  is_fixed_wing)
inline

Definition at line 237 of file estimator_interface.h.

References is_fixed_wing().

Referenced by Ekf2::Run().

Here is the call graph for this function:
Here is the caller graph for this function:

◆ set_optical_flow_limits()

void EstimatorInterface::set_optical_flow_limits ( float  max_flow_rate,
float  min_distance,
float  max_distance 
)
inline

Definition at line 262 of file estimator_interface.h.

Referenced by Ekf2::Run().

Here is the caller graph for this function:

◆ set_rangefinder_limits()

void EstimatorInterface::set_rangefinder_limits ( float  min_distance,
float  max_distance 
)
inline

Definition at line 255 of file estimator_interface.h.

Referenced by Ekf2::Run().

Here is the caller graph for this function:

◆ setAirspeedData()

void EstimatorInterface::setAirspeedData ( uint64_t  time_usec,
float  true_airspeed,
float  eas2tas 
)

Definition at line 287 of file estimator_interface.cpp.

References _airspeed_buffer, _airspeed_buffer_fail, _initialised, _min_obs_interval_us, _obs_buffer_length, _params, _time_last_airspeed, estimator::parameters::airspeed_delay_ms, RingBuffer< data_type >::allocate(), estimator::airspeedSample::eas2tas, ECL_ERR_TIMESTAMPED, FILTER_UPDATE_PERIOD_MS, RingBuffer< data_type >::get_length(), RingBuffer< data_type >::push(), estimator::airspeedSample::time_us, and estimator::airspeedSample::true_airspeed.

Referenced by Ekf2::Run().

Here is the call graph for this function:
Here is the caller graph for this function:

◆ setAuxVelData()

void EstimatorInterface::setAuxVelData ( uint64_t  time_usec,
float(&)  data[2],
float(&)  variance[2] 
)

Definition at line 459 of file estimator_interface.cpp.

References _auxvel_buffer, _auxvel_buffer_fail, _initialised, _min_obs_interval_us, _obs_buffer_length, _params, _time_last_auxvel, RingBuffer< data_type >::allocate(), estimator::parameters::auxvel_delay_ms, data, ECL_ERR_TIMESTAMPED, FILTER_UPDATE_PERIOD_MS, RingBuffer< data_type >::get_length(), RingBuffer< data_type >::push(), estimator::auxVelSample::time_us, estimator::auxVelSample::velNE, and estimator::auxVelSample::velVarNE.

Referenced by Ekf2::Run().

Here is the call graph for this function:
Here is the caller graph for this function:

◆ setBaroData()

void EstimatorInterface::setBaroData ( uint64_t  time_usec,
float  data 
)

Definition at line 254 of file estimator_interface.cpp.

References _baro_buffer, _baro_buffer_fail, _imu_sample_delayed, _initialised, _min_obs_interval_us, _obs_buffer_length, _params, _time_last_baro, RingBuffer< data_type >::allocate(), estimator::parameters::baro_delay_ms, data, ECL_ERR_TIMESTAMPED, FILTER_UPDATE_PERIOD_MS, RingBuffer< data_type >::get_length(), estimator::baroSample::hgt, math::max(), RingBuffer< data_type >::push(), estimator::imuSample::time_us, and estimator::baroSample::time_us.

Referenced by Ekf2::Run(), and EkfInitializationTest::update_with_const_sensors().

Here is the call graph for this function:
Here is the caller graph for this function:

◆ setExtVisionData()

◆ setGpsData()

void EstimatorInterface::setGpsData ( uint64_t  time_usec,
const gps_message gps 
)

Definition at line 193 of file estimator_interface.cpp.

References _gps_buffer, _gps_buffer_fail, _gps_speed_valid, _gps_yaw_offset, _imu_sample_delayed, _initialised, _min_obs_interval_us, _obs_buffer_length, _params, _time_last_gps, RingBuffer< data_type >::allocate(), estimator::gps_message::alt, collect_gps(), ECL_ERR_TIMESTAMPED, estimator::gps_message::eph, estimator::gps_message::epv, f(), FILTER_UPDATE_PERIOD_MS, estimator::gps_message::fix_type, estimator::parameters::fusion_mode, RingBuffer< data_type >::get_length(), estimator::parameters::gps_delay_ms, estimator::gpsSample::hacc, estimator::gpsSample::hgt, ISFINITE, estimator::gps_message::lat, estimator::gps_message::lon, map_projection_project(), MASK_USE_GPS, math::max(), estimator::gpsSample::pos, RingBuffer< data_type >::push(), estimator::gps_message::sacc, estimator::gpsSample::sacc, estimator::imuSample::time_us, estimator::gpsSample::time_us, estimator::gps_message::time_usec, estimator::gpsSample::vacc, VDIST_SENSOR_GPS, estimator::parameters::vdist_sensor_type, estimator::gpsSample::vel, estimator::gps_message::vel_ned, estimator::gps_message::vel_ned_valid, estimator::gps_message::yaw, estimator::gpsSample::yaw, and estimator::gps_message::yaw_offset.

Referenced by Ekf2::Run(), and EkfInitializationTest::update_with_const_sensors().

Here is the call graph for this function:
Here is the caller graph for this function:

◆ setIMUData() [1/2]

◆ setIMUData() [2/2]

void EstimatorInterface::setIMUData ( uint64_t  time_usec,
uint64_t  delta_ang_dt,
uint64_t  delta_vel_dt,
float(&)  delta_ang[3],
float(&)  delta_vel[3] 
)

Definition at line 146 of file estimator_interface.cpp.

References estimator::imuSample::delta_ang, estimator::imuSample::delta_ang_dt, estimator::imuSample::delta_vel, estimator::imuSample::delta_vel_dt, setIMUData(), and estimator::imuSample::time_us.

Here is the call graph for this function:

◆ setMagData()

void EstimatorInterface::setMagData ( uint64_t  time_usec,
float(&)  data[3] 
)

Definition at line 161 of file estimator_interface.cpp.

References _initialised, _mag_buffer, _mag_buffer_fail, _min_obs_interval_us, _obs_buffer_length, _params, _time_last_mag, RingBuffer< data_type >::allocate(), data, ECL_ERR_TIMESTAMPED, FILTER_UPDATE_PERIOD_MS, RingBuffer< data_type >::get_length(), estimator::magSample::mag, estimator::parameters::mag_delay_ms, RingBuffer< data_type >::push(), and estimator::magSample::time_us.

Referenced by Ekf2::Run(), and EkfInitializationTest::update_with_const_sensors().

Here is the call graph for this function:
Here is the caller graph for this function:

◆ setOpticalFlowData()

◆ setRangeData()

void EstimatorInterface::setRangeData ( uint64_t  time_usec,
float  data,
int8_t  quality 
)

Definition at line 317 of file estimator_interface.cpp.

References _initialised, _min_obs_interval_us, _obs_buffer_length, _params, _range_buffer, _range_buffer_fail, _time_last_range, RingBuffer< data_type >::allocate(), data, ECL_ERR_TIMESTAMPED, RingBuffer< data_type >::get_length(), RingBuffer< data_type >::push(), estimator::rangeSample::quality, estimator::parameters::range_delay_ms, estimator::rangeSample::rng, and estimator::rangeSample::time_us.

Referenced by Ekf2::Run().

Here is the call graph for this function:
Here is the caller graph for this function:

◆ unallocate_buffers()

void EstimatorInterface::unallocate_buffers ( )
protected

Definition at line 547 of file estimator_interface.cpp.

References _airspeed_buffer, _auxvel_buffer, _baro_buffer, _drag_buffer, _ext_vision_buffer, _flow_buffer, _gps_buffer, _imu_buffer, _mag_buffer, _output_buffer, _output_vert_buffer, _range_buffer, and RingBuffer< data_type >::unallocate().

Referenced by initialise_interface().

Here is the call graph for this function:
Here is the caller graph for this function:

◆ update()

virtual bool EstimatorInterface::update ( )
pure virtual

Implemented in Ekf.

Member Data Documentation

◆ _air_density

float EstimatorInterface::_air_density {CONSTANTS_AIR_DENSITY_SEA_LEVEL_15C}
protected

Definition at line 455 of file estimator_interface.h.

Referenced by Ekf::fuseDrag().

◆ _airspeed_buffer

RingBuffer<airspeedSample> EstimatorInterface::_airspeed_buffer
protected

◆ _airspeed_buffer_fail

bool EstimatorInterface::_airspeed_buffer_fail {false}
protected

Definition at line 534 of file estimator_interface.h.

Referenced by setAirspeedData().

◆ _airspeed_sample_delayed

airspeedSample EstimatorInterface::_airspeed_sample_delayed {}
protected

◆ _auxvel_buffer

RingBuffer<auxVelSample> EstimatorInterface::_auxvel_buffer
protected

◆ _auxvel_buffer_fail

bool EstimatorInterface::_auxvel_buffer_fail {false}
protected

Definition at line 538 of file estimator_interface.h.

Referenced by setAuxVelData().

◆ _auxvel_sample_delayed

auxVelSample EstimatorInterface::_auxvel_sample_delayed {}
protected

Definition at line 450 of file estimator_interface.h.

Referenced by Ekf::controlAuxVelFusion().

◆ _baro_buffer

◆ _baro_buffer_fail

bool EstimatorInterface::_baro_buffer_fail {false}
protected

Definition at line 532 of file estimator_interface.h.

Referenced by setBaroData().

◆ _baro_sample_delayed

baroSample EstimatorInterface::_baro_sample_delayed {}
protected

◆ _beta_test_ratio

float EstimatorInterface::_beta_test_ratio {0.0f}
protected

Definition at line 492 of file estimator_interface.h.

Referenced by Ekf::fuseSideslip(), and Ekf::get_innovation_test_status().

◆ _control_status

filter_control_status_u EstimatorInterface::_control_status {}
protected

Definition at line 564 of file estimator_interface.h.

Referenced by Ekf::canRealignYawUsingGps(), Ekf::canRunMagFusion(), Ekf::canUse3DMagFusion(), Ekf::checkHaglYawResetReq(), Ekf::checkMagDeclRequired(), Ekf::checkMagFieldStrength(), Ekf::checkRangeAidSuitability(), Ekf::checkYawAngleObservability(), Ekf::collect_gps(), Ekf::controlAirDataFusion(), Ekf::controlAuxVelFusion(), Ekf::controlBetaFusion(), Ekf::controlDragFusion(), Ekf::controlExternalVisionFusion(), Ekf::controlFusionModes(), Ekf::controlGpsFusion(), Ekf::controlHeightFusion(), Ekf::controlHeightSensorTimeouts(), Ekf::controlMagFusion(), Ekf::controlOpticalFlowFusion(), Ekf::controlVelPosFusion(), Ekf::fixCovarianceErrors(), Ekf::fuseGpsAntYaw(), Ekf::fuseHeading(), Ekf::fuseMag(), Ekf::fuseSideslip(), Ekf::fuseVelPosHeight(), Ekf::get_ekf_ctrl_limits(), Ekf::get_ekf_gpos_accuracy(), Ekf::get_ekf_lpos_accuracy(), Ekf::get_ekf_soln_status(), Ekf::get_ekf_vel_accuracy(), Ekf::getMagDeclination(), Ekf::gps_is_good(), Ekf::initHagl(), Ekf::initialiseCovariance(), Ekf::initialiseFilter(), Ekf::isStrongMagneticDisturbance(), Ekf::predictCovariance(), Ekf::realignYawGPS(), Ekf::reset(), Ekf::resetGpsAntYaw(), Ekf::resetHeight(), Ekf::resetMagHeading(), Ekf::resetPosition(), Ekf::resetVelocity(), Ekf::run3DMagAndDeclFusions(), Ekf::runInAirYawReset(), Ekf::runMagAndMagDeclFusions(), Ekf::runTerrainEstimator(), Ekf::setControlBaroHeight(), Ekf::setControlEVHeight(), Ekf::setControlGPSHeight(), Ekf::setControlRangeHeight(), setIMUData(), setOpticalFlowData(), Ekf::shouldInhibitMag(), Ekf::startMag3DFusion(), Ekf::startMagHdgFusion(), Ekf::stopMag3DFusion(), Ekf::stopMagHdgFusion(), Ekf::update_deadreckoning_status(), Ekf::updateRangeDataStuck(), Ekf::updateRangeDataValidity(), and Ekf::updateTerrainValidity().

◆ _control_status_prev

filter_control_status_u EstimatorInterface::_control_status_prev {}
protected

◆ _deadreckon_time_exceeded

bool EstimatorInterface::_deadreckon_time_exceeded {true}
protected

◆ _delta_ang_prev

Vector3f EstimatorInterface::_delta_ang_prev
protected

Definition at line 501 of file estimator_interface.h.

Referenced by setIMUData().

◆ _delta_vel_prev

Vector3f EstimatorInterface::_delta_vel_prev
protected

Definition at line 502 of file estimator_interface.h.

Referenced by setIMUData().

◆ _drag_buffer

RingBuffer<dragSample> EstimatorInterface::_drag_buffer
protected

◆ _drag_buffer_fail

bool EstimatorInterface::_drag_buffer_fail {false}
protected

Definition at line 537 of file estimator_interface.h.

Referenced by setIMUData().

◆ _drag_down_sampled

dragSample EstimatorInterface::_drag_down_sampled {}
protected

Definition at line 449 of file estimator_interface.h.

Referenced by setIMUData().

◆ _drag_sample_count

uint8_t EstimatorInterface::_drag_sample_count {0}
protected

Definition at line 453 of file estimator_interface.h.

Referenced by setIMUData().

◆ _drag_sample_delayed

dragSample EstimatorInterface::_drag_sample_delayed {}
protected

Definition at line 448 of file estimator_interface.h.

Referenced by Ekf::controlDragFusion(), and Ekf::fuseDrag().

◆ _drag_sample_time_dt

float EstimatorInterface::_drag_sample_time_dt {0.0f}
protected

Definition at line 454 of file estimator_interface.h.

Referenced by setIMUData().

◆ _drag_test_ratio

float EstimatorInterface::_drag_test_ratio[2] {}
protected

Definition at line 493 of file estimator_interface.h.

Referenced by Ekf::fuseDrag().

◆ _dt_imu_avg

float EstimatorInterface::_dt_imu_avg {0.0f}
protected

◆ _ev_buffer_fail

bool EstimatorInterface::_ev_buffer_fail {false}
protected

Definition at line 536 of file estimator_interface.h.

Referenced by setExtVisionData().

◆ _ev_sample_delayed

◆ _ext_vision_buffer

◆ _fault_status

◆ _flow_buffer

RingBuffer<flowSample> EstimatorInterface::_flow_buffer
protected

◆ _flow_buffer_fail

bool EstimatorInterface::_flow_buffer_fail {false}
protected

Definition at line 535 of file estimator_interface.h.

Referenced by setOpticalFlowData().

◆ _flow_max_distance

float EstimatorInterface::_flow_max_distance {0.0f}
protected

maximum distance that the optical flow sensor can operate at (m)

Definition at line 462 of file estimator_interface.h.

Referenced by Ekf::get_ekf_ctrl_limits().

◆ _flow_max_rate

float EstimatorInterface::_flow_max_rate {0.0f}
protected

maximum angular flow rate that the optical flow sensor can measure (rad/s)

Definition at line 460 of file estimator_interface.h.

Referenced by Ekf::controlOpticalFlowFusion(), Ekf::fuseOptFlow(), Ekf::get_ekf_ctrl_limits(), and setOpticalFlowData().

◆ _flow_min_distance

float EstimatorInterface::_flow_min_distance {0.0f}
protected

minimum distance that the optical flow sensor can operate at (m)

Definition at line 461 of file estimator_interface.h.

Referenced by Ekf::get_ekf_ctrl_limits().

◆ _flow_sample_delayed

◆ _gps_alt_prev

float EstimatorInterface::_gps_alt_prev {0.0f}
protected

Definition at line 483 of file estimator_interface.h.

Referenced by Ekf::gps_is_good().

◆ _gps_buffer

◆ _gps_buffer_fail

bool EstimatorInterface::_gps_buffer_fail {false}
protected

Definition at line 530 of file estimator_interface.h.

Referenced by setGpsData().

◆ _gps_drift_metrics

float EstimatorInterface::_gps_drift_metrics[3] {}
protected

Definition at line 507 of file estimator_interface.h.

Referenced by Ekf::get_gps_drift_metrics(), and Ekf::gps_is_good().

◆ _gps_drift_updated

bool EstimatorInterface::_gps_drift_updated {false}
protected

Definition at line 513 of file estimator_interface.h.

Referenced by Ekf::get_gps_drift_metrics(), and Ekf::gps_is_good().

◆ _gps_origin_eph

float EstimatorInterface::_gps_origin_eph {0.0f}
protected

Definition at line 479 of file estimator_interface.h.

Referenced by Ekf::collect_gps(), and Ekf::get_ekf_gpos_accuracy().

◆ _gps_origin_epv

float EstimatorInterface::_gps_origin_epv {0.0f}
protected

Definition at line 480 of file estimator_interface.h.

Referenced by Ekf::collect_gps(), and Ekf::get_ekf_gpos_accuracy().

◆ _gps_sample_delayed

◆ _gps_speed_valid

bool EstimatorInterface::_gps_speed_valid {false}
protected

Definition at line 478 of file estimator_interface.h.

Referenced by Ekf::reset(), and setGpsData().

◆ _gps_yaw_offset

float EstimatorInterface::_gps_yaw_offset {0.0f}
protected

Definition at line 484 of file estimator_interface.h.

Referenced by Ekf::fuseGpsAntYaw(), Ekf::resetGpsAntYaw(), and setGpsData().

◆ _imu_buffer

RingBuffer<imuSample> EstimatorInterface::_imu_buffer
protected

◆ _imu_buffer_length

uint8_t EstimatorInterface::_imu_buffer_length {0}
protected

◆ _imu_sample_delayed

◆ _imu_sample_new

imuSample EstimatorInterface::_imu_sample_new {}
protected

◆ _imu_updated

bool EstimatorInterface::_imu_updated {false}
protected

◆ _initialised

bool EstimatorInterface::_initialised {false}
protected

◆ _innov_check_fail_status

◆ _is_dead_reckoning

bool EstimatorInterface::_is_dead_reckoning {false}
protected

◆ _is_wind_dead_reckoning

bool EstimatorInterface::_is_wind_dead_reckoning {false}
protected

◆ _mag_buffer

RingBuffer<magSample> EstimatorInterface::_mag_buffer
protected

◆ _mag_buffer_fail

bool EstimatorInterface::_mag_buffer_fail {false}
protected

Definition at line 531 of file estimator_interface.h.

Referenced by setMagData().

◆ _mag_declination_gps

float EstimatorInterface::_mag_declination_gps {0.0f}
protected

◆ _mag_inclination_gps

float EstimatorInterface::_mag_inclination_gps {0.0f}
protected

◆ _mag_sample_delayed

◆ _mag_strength_gps

float EstimatorInterface::_mag_strength_gps {0.0f}
protected

◆ _mag_test_ratio

float EstimatorInterface::_mag_test_ratio[3] {}
protected

◆ _min_obs_interval_us

unsigned EstimatorInterface::_min_obs_interval_us {0}
protected

◆ _NED_origin_initialised

◆ _obs_buffer_length

◆ _output_buffer

◆ _output_new

◆ _output_sample_delayed

outputSample EstimatorInterface::_output_sample_delayed {}
protected

Definition at line 465 of file estimator_interface.h.

Referenced by Ekf::alignOutputFilter(), and Ekf::calculateOutputStates().

◆ _output_vert_buffer

RingBuffer<outputVert> EstimatorInterface::_output_vert_buffer
protected

◆ _output_vert_delayed

outputVert EstimatorInterface::_output_vert_delayed {}
protected

Definition at line 467 of file estimator_interface.h.

Referenced by Ekf::calculateOutputStates(), and Ekf::resetHeight().

◆ _output_vert_new

outputVert EstimatorInterface::_output_vert_new {}
protected

Definition at line 468 of file estimator_interface.h.

Referenced by Ekf::calculateOutputStates(), and Ekf::resetHeight().

◆ _params

parameters EstimatorInterface::_params
protected

Definition at line 415 of file estimator_interface.h.

Referenced by Ekf::calcOptFlowMeasVar(), Ekf::calculateOutputStates(), Ekf::checkMagBiasObservability(), Ekf::checkMagDeclRequired(), Ekf::checkMagFieldStrength(), Ekf::checkRangeAidSuitability(), Ekf::checkYawAngleObservability(), Ekf::constrainStates(), Ekf::controlAirDataFusion(), Ekf::controlAuxVelFusion(), Ekf::controlBetaFusion(), Ekf::controlDragFusion(), Ekf::controlExternalVisionFusion(), Ekf::controlFusionModes(), Ekf::controlGpsFusion(), Ekf::controlHeightFusion(), Ekf::controlHeightSensorTimeouts(), Ekf::controlMagFusion(), Ekf::controlOpticalFlowFusion(), Ekf::controlVelPosFusion(), Ekf::fixCovarianceErrors(), Ekf::fuseAirspeed(), Ekf::fuseDrag(), Ekf::fuseFlowForTerrain(), Ekf::fuseGpsAntYaw(), Ekf::fuseHagl(), Ekf::fuseHeading(), Ekf::fuseMag(), Ekf::fuseOptFlow(), Ekf::fuseSideslip(), Ekf::fuseVelPosHeight(), Ekf::get_ekf_ctrl_limits(), Ekf::get_ekf_vel_accuracy(), Ekf::getMagDeclination(), Ekf::gps_is_good(), Ekf::initHagl(), initialise_interface(), Ekf::initialiseCovariance(), Ekf::initialiseFilter(), Ekf::limitDeclination(), Ekf::predictCovariance(), Ekf::realignYawGPS(), Ekf::reset(), Ekf::reset_imu_bias(), Ekf::resetGpsAntYaw(), Ekf::resetHeight(), Ekf::resetMagHeading(), Ekf::resetMagRelatedCovariances(), Ekf::resetPosition(), Ekf::resetVelocity(), Ekf::resetWindCovariance(), Ekf::runTerrainEstimator(), setAirspeedData(), setAuxVelData(), setBaroData(), setExtVisionData(), setGpsData(), setIMUData(), setMagData(), setOpticalFlowData(), setRangeData(), Ekf::shouldInhibitMag(), Ekf::update_deadreckoning_status(), Ekf::updateRangeDataStuck(), and Ekf::updateRangeDataValidity().

◆ _R_to_earth_now

Matrix3f EstimatorInterface::_R_to_earth_now
protected

Definition at line 470 of file estimator_interface.h.

Referenced by Ekf::calculateOutputStates().

◆ _range_buffer

RingBuffer<rangeSample> EstimatorInterface::_range_buffer
protected

◆ _range_buffer_fail

bool EstimatorInterface::_range_buffer_fail {false}
protected

Definition at line 533 of file estimator_interface.h.

Referenced by setRangeData().

◆ _range_sample_delayed

◆ _rng_valid_max_val

float EstimatorInterface::_rng_valid_max_val {0.0f}
protected

maximum distance that the rangefinder can measure (m)

Definition at line 459 of file estimator_interface.h.

Referenced by Ekf::get_ekf_ctrl_limits(), and Ekf::updateRangeDataValidity().

◆ _rng_valid_min_val

float EstimatorInterface::_rng_valid_min_val {0.0f}
protected

minimum distance that the rangefinder can measure (m)

Definition at line 458 of file estimator_interface.h.

Referenced by Ekf::get_ekf_ctrl_limits(), and Ekf::updateRangeDataValidity().

◆ _tas_test_ratio

float EstimatorInterface::_tas_test_ratio {0.0f}
protected

Definition at line 490 of file estimator_interface.h.

Referenced by Ekf::fuseAirspeed(), and Ekf::get_innovation_test_status().

◆ _terr_test_ratio

float EstimatorInterface::_terr_test_ratio {0.0f}
protected

Definition at line 491 of file estimator_interface.h.

Referenced by Ekf::fuseHagl(), and Ekf::get_innovation_test_status().

◆ _time_last_airspeed

uint64_t EstimatorInterface::_time_last_airspeed {0}
protected

Definition at line 545 of file estimator_interface.h.

Referenced by initialise_interface(), and setAirspeedData().

◆ _time_last_auxvel

uint64_t EstimatorInterface::_time_last_auxvel {0}
protected

Definition at line 549 of file estimator_interface.h.

Referenced by setAuxVelData().

◆ _time_last_baro

uint64_t EstimatorInterface::_time_last_baro {0}
protected

Definition at line 543 of file estimator_interface.h.

Referenced by initialise_interface(), and setBaroData().

◆ _time_last_ext_vision

uint64_t EstimatorInterface::_time_last_ext_vision {0}
protected

◆ _time_last_gnd_effect_on

uint64_t EstimatorInterface::_time_last_gnd_effect_on {0}
protected

Definition at line 548 of file estimator_interface.h.

Referenced by Ekf::controlHeightFusion().

◆ _time_last_gps

uint64_t EstimatorInterface::_time_last_gps {0}
protected

Definition at line 541 of file estimator_interface.h.

Referenced by Ekf::controlGpsFusion(), initialise_interface(), and setGpsData().

◆ _time_last_imu

◆ _time_last_mag

uint64_t EstimatorInterface::_time_last_mag {0}
protected

Definition at line 542 of file estimator_interface.h.

Referenced by initialise_interface(), and setMagData().

◆ _time_last_move_detect_us

uint64_t EstimatorInterface::_time_last_move_detect_us {0}
protected

Definition at line 512 of file estimator_interface.h.

Referenced by setIMUData().

◆ _time_last_optflow

uint64_t EstimatorInterface::_time_last_optflow {0}
protected

Definition at line 547 of file estimator_interface.h.

Referenced by initialise_interface(), and setOpticalFlowData().

◆ _time_last_range

uint64_t EstimatorInterface::_time_last_range {0}
protected

Definition at line 544 of file estimator_interface.h.

Referenced by initialise_interface(), and setRangeData().

◆ _vehicle_at_rest

bool EstimatorInterface::_vehicle_at_rest {false}
protected

◆ _vel_deriv_ned

Vector3f EstimatorInterface::_vel_deriv_ned
protected

Definition at line 472 of file estimator_interface.h.

Referenced by Ekf::calculateOutputStates().

◆ _vel_imu_rel_body_ned

Vector3f EstimatorInterface::_vel_imu_rel_body_ned
protected

Definition at line 471 of file estimator_interface.h.

Referenced by Ekf::calculateOutputStates().

◆ _vel_pos_test_ratio

float EstimatorInterface::_vel_pos_test_ratio[6] {}
protected

◆ _vibe_metrics

float EstimatorInterface::_vibe_metrics[3] {}
protected

Definition at line 503 of file estimator_interface.h.

Referenced by Ekf::get_imu_vibe_metrics(), and setIMUData().

◆ _yaw_test_ratio

float EstimatorInterface::_yaw_test_ratio {0.0f}
protected

◆ FILTER_UPDATE_PERIOD_MS

constexpr unsigned EstimatorInterface::FILTER_UPDATE_PERIOD_MS {8}
static

◆ FILTER_UPDATE_PERIOD_S

constexpr float EstimatorInterface::FILTER_UPDATE_PERIOD_S {FILTER_UPDATE_PERIOD_MS * 0.001f}
static

The documentation for this class was generated from the following files: