APM:Libraries
Public Types | Public Member Functions | Private Types | Private Member Functions | Private Attributes | List of all members
AP_AHRS_NavEKF Class Reference

#include <AP_AHRS_NavEKF.h>

Inheritance diagram for AP_AHRS_NavEKF:
[legend]
Collaboration diagram for AP_AHRS_NavEKF:
[legend]

Public Types

enum  Flags { FLAG_NONE = 0, FLAG_ALWAYS_USE_EKF = 0x1 }
 

Public Member Functions

 AP_AHRS_NavEKF (NavEKF2 &_EKF2, NavEKF3 &_EKF3, Flags flags=FLAG_NONE)
 
 AP_AHRS_NavEKF (const AP_AHRS_NavEKF &other)=delete
 
AP_AHRS_NavEKFoperator= (const AP_AHRS_NavEKF &)=delete
 
const Vector3fget_gyro (void) const override
 
const Matrix3fget_rotation_body_to_ned (void) const override
 
const Vector3fget_gyro_drift (void) const override
 
void reset_gyro_drift () override
 
void update (bool skip_ins_update=false) override
 
void reset (bool recover_eulers=false) override
 
void reset_attitude (const float &roll, const float &pitch, const float &yaw) override
 
bool get_position (struct Location &loc) const override
 
bool get_hagl (float &hagl) const override
 
float get_error_rp () const override
 
float get_error_yaw () const override
 
Vector3f wind_estimate () const override
 
bool airspeed_estimate (float *airspeed_ret) const override
 
bool use_compass () override
 
NavEKF2get_NavEKF2 (void)
 
const NavEKF2get_NavEKF2_const (void) const
 
NavEKF3get_NavEKF3 (void)
 
const NavEKF3get_NavEKF3_const (void) const
 
bool get_secondary_attitude (Vector3f &eulers) const override
 
bool get_secondary_quaternion (Quaternion &quat) const override
 
bool get_secondary_position (struct Location &loc) const override
 
Vector2f groundspeed_vector () override
 
const Vector3fget_accel_ef (uint8_t i) const override
 
const Vector3fget_accel_ef () const override
 
void getCorrectedDeltaVelocityNED (Vector3f &ret, float &dt) const override
 
const Vector3fget_accel_ef_blended () const override
 
bool set_origin (const Location &loc) override
 
bool get_origin (Location &ret) const override
 
bool have_inertial_nav () const override
 
bool get_velocity_NED (Vector3f &vec) const override
 
bool get_relative_position_NED_home (Vector3f &vec) const override
 
bool get_relative_position_NED_origin (Vector3f &vec) const override
 
bool get_relative_position_NE_home (Vector2f &posNE) const override
 
bool get_relative_position_NE_origin (Vector2f &posNE) const override
 
void get_relative_position_D_home (float &posD) const override
 
bool get_relative_position_D_origin (float &posD) const override
 
bool get_vert_pos_rate (float &velocity) const
 
void writeOptFlowMeas (uint8_t &rawFlowQuality, Vector2f &rawFlowRates, Vector2f &rawGyroRates, uint32_t &msecFlowMeas, const Vector3f &posOffset)
 
void writeBodyFrameOdom (float quality, const Vector3f &delPos, const Vector3f &delAng, float delTime, uint32_t timeStamp_ms, const Vector3f &posOffset)
 
void writeExtNavData (const Vector3f &sensOffset, const Vector3f &pos, const Quaternion &quat, float posErr, float angErr, uint32_t timeStamp_ms, uint32_t resetTime_ms) override
 
uint8_t setInhibitGPS (void)
 
void getEkfControlLimits (float &ekfGndSpdLimit, float &ekfNavVelGainScaler) const
 
void set_ekf_use (bool setting)
 
bool healthy () const override
 
bool initialised () const override
 
bool get_filter_status (nav_filter_status &status) const
 
bool getMagOffsets (uint8_t mag_idx, Vector3f &magOffsets) const
 
const char * prearm_failure_reason (void) const override
 
uint32_t getLastYawResetAngle (float &yawAng) const override
 
uint32_t getLastPosNorthEastReset (Vector2f &pos) const override
 
uint32_t getLastVelNorthEastReset (Vector2f &vel) const override
 
uint32_t getLastPosDownReset (float &posDelta) const override
 
bool resetHeightDatum () override
 
void send_ekf_status_report (mavlink_channel_t chan) const
 
bool get_hgt_ctrl_limit (float &limit) const override
 
bool get_location (struct Location &loc) const
 
bool get_variances (float &velVar, float &posVar, float &hgtVar, Vector3f &magVar, float &tasVar, Vector2f &offset) const override
 
bool get_mag_field_NED (Vector3f &ret) const
 
bool get_mag_field_correction (Vector3f &ret) const override
 
void setTakeoffExpected (bool val)
 
void setTouchdownExpected (bool val)
 
bool getGpsGlitchStatus () const
 
void force_ekf_start (void)
 
bool have_ekf_logging (void) const override
 
uint8_t get_primary_accel_index (void) const override
 
uint8_t get_primary_gyro_index (void) const override
 
- Public Member Functions inherited from AP_AHRS_DCM
 AP_AHRS_DCM ()
 
 AP_AHRS_DCM (const AP_AHRS_DCM &other)=delete
 
AP_AHRS_DCMoperator= (const AP_AHRS_DCM &)=delete
 
void set_home (const Location &loc) override
 
void estimate_wind (void)
 
uint32_t uptime_ms () const override
 
- Public Member Functions inherited from AP_AHRS
 AP_AHRS ()
 
virtual ~AP_AHRS ()
 
virtual void init ()
 
void set_fly_forward (bool b)
 
bool get_fly_forward (void) const
 
void set_likely_flying (bool b)
 
bool get_likely_flying (void) const
 
uint32_t get_time_flying_ms (void) const
 
AHRS_VehicleClass get_vehicle_class (void) const
 
void set_vehicle_class (AHRS_VehicleClass vclass)
 
void set_wind_estimation (bool b)
 
void set_compass (Compass *compass)
 
const Compassget_compass () const
 
void set_optflow (const OpticalFlow *optflow)
 
const OpticalFlowget_optflow () const
 
void set_orientation ()
 
void set_airspeed (AP_Airspeed *airspeed)
 
void set_beacon (AP_Beacon *beacon)
 
const AP_Airspeedget_airspeed (void) const
 
const AP_Beaconget_beacon (void) const
 
float get_yaw_rate_earth (void) const
 
Vector3f get_gyro_latest (void) const
 
const Matrix3fget_rotation_autopilot_body_to_vehicle_body (void) const
 
const Matrix3fget_rotation_vehicle_body_to_autopilot_body (void) const
 
bool airspeed_estimate_true (float *airspeed_ret) const
 
float get_EAS2TAS (void) const
 
bool airspeed_sensor_enabled (void) const
 
virtual bool get_expected_mag_field_NED (Vector3f &ret) const
 
float groundspeed (void)
 
bool yaw_initialised (void) const
 
void set_correct_centrifugal (bool setting)
 
bool get_correct_centrifugal (void) const
 
const Vector3fget_trim () const
 
virtual void set_trim (Vector3f new_trim)
 
virtual void add_trim (float roll_in_radians, float pitch_in_radians, bool save_to_eeprom=true)
 
float cos_roll () const
 
float cos_pitch () const
 
float cos_yaw () const
 
float sin_roll () const
 
float sin_pitch () const
 
float sin_yaw () const
 
const struct Locationget_home (void) const
 
void lock_home ()
 
bool home_is_locked () const
 
bool home_is_set (void) const
 
void Log_Write_Home_And_Origin ()
 
uint8_t get_active_accel_instance (void) const
 
int8_t get_ekf_type (void) const
 
AP_AHRS_Viewcreate_view (enum Rotation rotation)
 
float getAOA (void)
 
float getSSA (void)
 
Vector2f rotate_earth_to_body2D (const Vector2f &ef_vector) const
 
Vector2f rotate_body_to_earth2D (const Vector2f &bf) const
 
virtual void update_AOA_SSA (void)
 

Private Types

enum  EKF_TYPE { EKF_TYPE_NONE =0, EKF_TYPE3 =3, EKF_TYPE2 =2, EKF_TYPE_SITL =10 }
 

Private Member Functions

EKF_TYPE active_EKF_type (void) const
 
bool always_use_EKF () const
 
uint8_t ekf_type (void) const
 
void update_DCM (bool skip_ins_update)
 
void update_EKF2 (void)
 
void update_EKF3 (void)
 
uint8_t get_primary_IMU_index (void) const
 
void update_SITL (void)
 

Private Attributes

NavEKF2EKF2
 
NavEKF3EKF3
 
bool _ekf2_started
 
bool _ekf3_started
 
bool _force_ekf
 
Matrix3f _dcm_matrix
 
Vector3f _dcm_attitude
 
Vector3f _gyro_drift
 
Vector3f _gyro_estimate
 
Vector3f _accel_ef_ekf [INS_MAX_INSTANCES]
 
Vector3f _accel_ef_ekf_blended
 
const uint16_t startup_delay_ms = 1000
 
uint32_t start_time_ms = 0
 
Flags _ekf_flags
 
SITL::SITL_sitl
 
uint32_t _last_body_odm_update_ms = 0
 

Additional Inherited Members

- Static Public Member Functions inherited from AP_AHRS
static AP_AHRSget_singleton ()
 
- Public Attributes inherited from AP_AHRS
float roll
 
float pitch
 
float yaw
 
int32_t roll_sensor
 
int32_t pitch_sensor
 
int32_t yaw_sensor
 
- Static Public Attributes inherited from AP_AHRS
static const struct AP_Param::GroupInfo var_info []
 
- Protected Member Functions inherited from AP_AHRS
void calc_trig (const Matrix3f &rot, float &cr, float &cp, float &cy, float &sr, float &sp, float &sy) const
 
void update_trig (void)
 
void update_cd_values (void)
 
- Protected Attributes inherited from AP_AHRS
AHRS_VehicleClass _vehicle_class
 
AP_Float _kp_yaw
 
AP_Float _kp
 
AP_Float gps_gain
 
AP_Float beta
 
AP_Int8 _gps_use
 
AP_Int8 _wind_max
 
AP_Int8 _board_orientation
 
AP_Int8 _gps_minsats
 
AP_Int8 _gps_delay
 
AP_Int8 _ekf_type
 
AP_Float _custom_roll
 
AP_Float _custom_pitch
 
AP_Float _custom_yaw
 
Matrix3f _custom_rotation
 
struct AP_AHRS::ahrs_flags _flags
 
uint32_t _last_flying_ms
 
Compass_compass
 
const OpticalFlow_optflow
 
AP_Airspeed_airspeed
 
AP_Beacon_beacon
 
uint32_t _compass_last_update
 
AP_Vector3f _trim
 
Vector3f _last_trim
 
Matrix3f _rotation_autopilot_body_to_vehicle_body
 
Matrix3f _rotation_vehicle_body_to_autopilot_body
 
float _gyro_drift_limit
 
Vector3f _accel_ef [INS_MAX_INSTANCES]
 
Vector3f _accel_ef_blended
 
Vector2f _lp
 
Vector2f _hp
 
Vector2f _lastGndVelADS
 
struct Location _home
 
bool _home_is_set:1
 
bool _home_locked:1
 
float _cos_roll
 
float _cos_pitch
 
float _cos_yaw
 
float _sin_roll
 
float _sin_pitch
 
float _sin_yaw
 
uint8_t _active_accel_instance
 
AP_AHRS_View_view
 
float _AOA
 
float _SSA
 
uint32_t _last_AOA_update_ms
 

Detailed Description

Definition at line 41 of file AP_AHRS_NavEKF.h.

Member Enumeration Documentation

◆ EKF_TYPE

Enumerator
EKF_TYPE_NONE 
EKF_TYPE3 
EKF_TYPE2 
EKF_TYPE_SITL 

Definition at line 259 of file AP_AHRS_NavEKF.h.

◆ Flags

Enumerator
FLAG_NONE 
FLAG_ALWAYS_USE_EKF 

Definition at line 43 of file AP_AHRS_NavEKF.h.

Constructor & Destructor Documentation

◆ AP_AHRS_NavEKF() [1/2]

AP_AHRS_NavEKF::AP_AHRS_NavEKF ( NavEKF2 _EKF2,
NavEKF3 _EKF3,
Flags  flags = FLAG_NONE 
)

Definition at line 33 of file AP_AHRS_NavEKF.cpp.

Here is the call graph for this function:

◆ AP_AHRS_NavEKF() [2/2]

AP_AHRS_NavEKF::AP_AHRS_NavEKF ( const AP_AHRS_NavEKF other)
delete

Member Function Documentation

◆ active_EKF_type()

AP_AHRS_NavEKF::EKF_TYPE AP_AHRS_NavEKF::active_EKF_type ( void  ) const
private

Definition at line 929 of file AP_AHRS_NavEKF.cpp.

Referenced by get_accel_ef(), get_accel_ef_blended(), get_gyro(), get_gyro_drift(), get_hagl(), get_mag_field_correction(), get_mag_field_NED(), get_position(), get_relative_position_D_origin(), get_relative_position_NE_origin(), get_relative_position_NED_origin(), get_rotation_body_to_ned(), get_secondary_attitude(), get_secondary_position(), get_secondary_quaternion(), get_velocity_NED(), get_vert_pos_rate(), getCorrectedDeltaVelocityNED(), groundspeed_vector(), have_inertial_nav(), healthy(), set_origin(), update_EKF2(), update_EKF3(), update_SITL(), use_compass(), and wind_estimate().

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

◆ airspeed_estimate()

bool AP_AHRS_NavEKF::airspeed_estimate ( float *  airspeed_ret) const
overridevirtual

Reimplemented from AP_AHRS_DCM.

Definition at line 476 of file AP_AHRS_NavEKF.cpp.

Here is the call graph for this function:

◆ always_use_EKF()

bool AP_AHRS_NavEKF::always_use_EKF ( ) const
inlineprivate

Definition at line 268 of file AP_AHRS_NavEKF.h.

Referenced by active_EKF_type(), and ekf_type().

Here is the caller graph for this function:

◆ ekf_type()

uint8_t AP_AHRS_NavEKF::ekf_type ( void  ) const
private

Definition at line 915 of file AP_AHRS_NavEKF.cpp.

Referenced by active_EKF_type(), get_filter_status(), get_hgt_ctrl_limit(), get_location(), get_origin(), get_primary_accel_index(), get_primary_gyro_index(), get_primary_IMU_index(), get_variances(), getEkfControlLimits(), getLastPosDownReset(), getLastPosNorthEastReset(), getLastVelNorthEastReset(), getLastYawResetAngle(), getMagOffsets(), have_ekf_logging(), healthy(), initialised(), prearm_failure_reason(), resetHeightDatum(), send_ekf_status_report(), setInhibitGPS(), setTakeoffExpected(), and setTouchdownExpected().

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

◆ force_ekf_start()

void AP_AHRS_NavEKF::force_ekf_start ( void  )
inline

Definition at line 247 of file AP_AHRS_NavEKF.h.

Here is the call graph for this function:

◆ get_accel_ef() [1/2]

const Vector3f & AP_AHRS_NavEKF::get_accel_ef ( uint8_t  i) const
overridevirtual

Reimplemented from AP_AHRS.

Definition at line 352 of file AP_AHRS_NavEKF.cpp.

Here is the call graph for this function:

◆ get_accel_ef() [2/2]

const Vector3f & AP_AHRS_NavEKF::get_accel_ef ( void  ) const
overridevirtual

Reimplemented from AP_AHRS.

Definition at line 1621 of file AP_AHRS_NavEKF.cpp.

Referenced by get_NavEKF3_const().

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

◆ get_accel_ef_blended()

const Vector3f & AP_AHRS_NavEKF::get_accel_ef_blended ( void  ) const
overridevirtual

Reimplemented from AP_AHRS.

Definition at line 361 of file AP_AHRS_NavEKF.cpp.

Referenced by get_NavEKF3_const().

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

◆ get_error_rp()

float AP_AHRS_NavEKF::get_error_rp ( void  ) const
overridevirtual

Reimplemented from AP_AHRS_DCM.

Definition at line 437 of file AP_AHRS_NavEKF.cpp.

Here is the call graph for this function:

◆ get_error_yaw()

float AP_AHRS_NavEKF::get_error_yaw ( void  ) const
overridevirtual

Reimplemented from AP_AHRS_DCM.

Definition at line 442 of file AP_AHRS_NavEKF.cpp.

Here is the call graph for this function:

◆ get_filter_status()

bool AP_AHRS_NavEKF::get_filter_status ( nav_filter_status status) const

Definition at line 1117 of file AP_AHRS_NavEKF.cpp.

Referenced by active_EKF_type(), SoloGimbalEKF::fuseVelocity(), get_NavEKF3_const(), getGpsGlitchStatus(), SoloGimbalEKF::RunEKF(), and AC_PrecLand::update().

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

◆ get_gyro()

const Vector3f & AP_AHRS_NavEKF::get_gyro ( void  ) const
overridevirtual

Reimplemented from AP_AHRS_DCM.

Definition at line 45 of file AP_AHRS_NavEKF.cpp.

Referenced by AC_PrecLand::run_estimator(), AC_PrecLand::run_output_prediction(), and AP_OpticalFlow_Pixart::timer().

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

◆ get_gyro_drift()

const Vector3f & AP_AHRS_NavEKF::get_gyro_drift ( void  ) const
overridevirtual

Reimplemented from AP_AHRS_DCM.

Definition at line 61 of file AP_AHRS_NavEKF.cpp.

Referenced by loop(), and update().

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

◆ get_hagl()

bool AP_AHRS_NavEKF::get_hagl ( float &  hagl) const
overridevirtual

Reimplemented from AP_AHRS.

Definition at line 725 of file AP_AHRS_NavEKF.cpp.

Here is the call graph for this function:

◆ get_hgt_ctrl_limit()

bool AP_AHRS_NavEKF::get_hgt_ctrl_limit ( float &  limit) const
overridevirtual

Reimplemented from AP_AHRS.

Definition at line 1456 of file AP_AHRS_NavEKF.cpp.

Referenced by get_NavEKF3_const().

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

◆ get_location()

bool AP_AHRS_NavEKF::get_location ( struct Location loc) const

Definition at line 1479 of file AP_AHRS_NavEKF.cpp.

Referenced by get_NavEKF3_const(), and AC_Fence::load_polygon_from_eeprom().

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

◆ get_mag_field_correction()

bool AP_AHRS_NavEKF::get_mag_field_correction ( Vector3f ret) const
overridevirtual

Reimplemented from AP_AHRS.

Definition at line 675 of file AP_AHRS_NavEKF.cpp.

Referenced by SoloGimbalEKF::calcMagHeadingInnov(), and get_NavEKF3_const().

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

◆ get_mag_field_NED()

bool AP_AHRS_NavEKF::get_mag_field_NED ( Vector3f ret) const

Definition at line 652 of file AP_AHRS_NavEKF.cpp.

Referenced by SoloGimbalEKF::calcMagHeadingInnov(), and get_NavEKF3_const().

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

◆ get_NavEKF2()

NavEKF2& AP_AHRS_NavEKF::get_NavEKF2 ( void  )
inline

Definition at line 93 of file AP_AHRS_NavEKF.h.

Referenced by DataFlash_Class::Log_Write_POS().

Here is the caller graph for this function:

◆ get_NavEKF2_const()

const NavEKF2& AP_AHRS_NavEKF::get_NavEKF2_const ( void  ) const
inline

Definition at line 96 of file AP_AHRS_NavEKF.h.

Referenced by GCS_MAVLINK::send_ahrs2().

Here is the caller graph for this function:

◆ get_NavEKF3()

NavEKF3& AP_AHRS_NavEKF::get_NavEKF3 ( void  )
inline

Definition at line 100 of file AP_AHRS_NavEKF.h.

Referenced by DataFlash_Class::Log_Write_POS().

Here is the caller graph for this function:

◆ get_NavEKF3_const()

const NavEKF3& AP_AHRS_NavEKF::get_NavEKF3_const ( void  ) const
inline

Definition at line 103 of file AP_AHRS_NavEKF.h.

Here is the call graph for this function:

◆ get_origin()

bool AP_AHRS_NavEKF::get_origin ( Location ret) const
overridevirtual

Reimplemented from AP_AHRS.

Definition at line 1425 of file AP_AHRS_NavEKF.cpp.

Referenced by Location_Class::get_alt_cm(), get_NavEKF3_const(), get_relative_position_D_home(), get_relative_position_NE_home(), get_relative_position_NED_home(), Location_Class::get_vector_xy_from_origin_NE(), AC_Fence::load_polygon_from_eeprom(), and Location_Class::Location_Class().

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

◆ get_position()

bool AP_AHRS_NavEKF::get_position ( struct Location loc) const
overridevirtual

Reimplemented from AP_AHRS_DCM.

Definition at line 395 of file AP_AHRS_NavEKF.cpp.

Referenced by get_location(), get_relative_position_NE_origin(), and get_relative_position_NED_origin().

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

◆ get_primary_accel_index()

uint8_t AP_AHRS_NavEKF::get_primary_accel_index ( void  ) const
overridevirtual

Reimplemented from AP_AHRS.

Definition at line 1628 of file AP_AHRS_NavEKF.cpp.

Referenced by AC_PrecLand::construct_pos_meas_using_rangefinder(), force_ekf_start(), get_accel_ef(), and AC_PrecLand::run_output_prediction().

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

◆ get_primary_gyro_index()

uint8_t AP_AHRS_NavEKF::get_primary_gyro_index ( void  ) const
overridevirtual

Reimplemented from AP_AHRS.

Definition at line 1637 of file AP_AHRS_NavEKF.cpp.

Referenced by force_ekf_start().

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

◆ get_primary_IMU_index()

uint8_t AP_AHRS_NavEKF::get_primary_IMU_index ( void  ) const
private

Definition at line 1599 of file AP_AHRS_NavEKF.cpp.

Referenced by get_primary_accel_index(), and get_primary_gyro_index().

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

◆ get_relative_position_D_home()

void AP_AHRS_NavEKF::get_relative_position_D_home ( float &  posD) const
overridevirtual

Reimplemented from AP_AHRS_DCM.

Definition at line 898 of file AP_AHRS_NavEKF.cpp.

Referenced by AC_Fence::check_fence_alt_max(), and get_NavEKF3_const().

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

◆ get_relative_position_D_origin()

bool AP_AHRS_NavEKF::get_relative_position_D_origin ( float &  posD) const
overridevirtual

Reimplemented from AP_AHRS.

Definition at line 869 of file AP_AHRS_NavEKF.cpp.

Referenced by get_NavEKF3_const(), and get_relative_position_D_home().

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

◆ get_relative_position_NE_home()

bool AP_AHRS_NavEKF::get_relative_position_NE_home ( Vector2f posNE) const
overridevirtual

Reimplemented from AP_AHRS.

Definition at line 848 of file AP_AHRS_NavEKF.cpp.

Referenced by AC_Fence::check_fence_circle(), get_NavEKF3_const(), AC_Fence::pre_arm_check(), and AC_Fence::sys_status_failed().

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

◆ get_relative_position_NE_origin()

bool AP_AHRS_NavEKF::get_relative_position_NE_origin ( Vector2f posNE) const
overridevirtual

Reimplemented from AP_AHRS.

Definition at line 818 of file AP_AHRS_NavEKF.cpp.

Referenced by AC_Fence::check_fence_polygon(), get_NavEKF3_const(), get_relative_position_NE_home(), and AC_PrecLand::get_target_position_cm().

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

◆ get_relative_position_NED_home()

bool AP_AHRS_NavEKF::get_relative_position_NED_home ( Vector3f vec) const
overridevirtual

Reimplemented from AP_AHRS.

Definition at line 799 of file AP_AHRS_NavEKF.cpp.

Referenced by get_NavEKF3_const(), and AC_PrecLand_SITL::update().

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

◆ get_relative_position_NED_origin()

bool AP_AHRS_NavEKF::get_relative_position_NED_origin ( Vector3f vec) const
overridevirtual

Reimplemented from AP_AHRS.

Definition at line 750 of file AP_AHRS_NavEKF.cpp.

Referenced by get_NavEKF3_const(), and get_relative_position_NED_home().

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

◆ get_rotation_body_to_ned()

const Matrix3f & AP_AHRS_NavEKF::get_rotation_body_to_ned ( void  ) const
overridevirtual

Reimplemented from AP_AHRS_DCM.

Definition at line 53 of file AP_AHRS_NavEKF.cpp.

Referenced by loop(), AC_PrecLand::run_output_prediction(), SoloGimbalEKF::RunEKF(), AC_PrecLand_SITL::update(), and AC_PrecLand::update().

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

◆ get_secondary_attitude()

bool AP_AHRS_NavEKF::get_secondary_attitude ( Vector3f eulers) const
overridevirtual

Reimplemented from AP_AHRS.

Definition at line 503 of file AP_AHRS_NavEKF.cpp.

Referenced by get_NavEKF3_const().

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

◆ get_secondary_position()

bool AP_AHRS_NavEKF::get_secondary_position ( struct Location loc) const
overridevirtual

Reimplemented from AP_AHRS.

Definition at line 544 of file AP_AHRS_NavEKF.cpp.

Referenced by get_NavEKF3_const().

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

◆ get_secondary_quaternion()

bool AP_AHRS_NavEKF::get_secondary_quaternion ( Quaternion quat) const
overridevirtual

Reimplemented from AP_AHRS.

Definition at line 524 of file AP_AHRS_NavEKF.cpp.

Referenced by get_NavEKF3_const().

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

◆ get_variances()

bool AP_AHRS_NavEKF::get_variances ( float &  velVar,
float &  posVar,
float &  hgtVar,
Vector3f magVar,
float &  tasVar,
Vector2f offset 
) const
overridevirtual

Reimplemented from AP_AHRS.

Definition at line 1504 of file AP_AHRS_NavEKF.cpp.

Referenced by get_NavEKF3_const().

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

◆ get_velocity_NED()

bool AP_AHRS_NavEKF::get_velocity_NED ( Vector3f vec) const
overridevirtual

Reimplemented from AP_AHRS.

Definition at line 627 of file AP_AHRS_NavEKF.cpp.

Referenced by SoloGimbalEKF::fuseVelocity(), get_NavEKF3_const(), and AC_PrecLand::update().

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

◆ get_vert_pos_rate()

bool AP_AHRS_NavEKF::get_vert_pos_rate ( float &  velocity) const

Definition at line 699 of file AP_AHRS_NavEKF.cpp.

Referenced by get_NavEKF3_const().

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

◆ getCorrectedDeltaVelocityNED()

void AP_AHRS_NavEKF::getCorrectedDeltaVelocityNED ( Vector3f ret,
float &  dt 
) const
overridevirtual

Reimplemented from AP_AHRS.

Definition at line 1237 of file AP_AHRS_NavEKF.cpp.

Referenced by get_NavEKF3_const(), and AC_PrecLand::update().

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

◆ getEkfControlLimits()

void AP_AHRS_NavEKF::getEkfControlLimits ( float &  ekfGndSpdLimit,
float &  ekfNavVelGainScaler 
) const

Definition at line 1191 of file AP_AHRS_NavEKF.cpp.

Referenced by get_NavEKF3_const().

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

◆ getGpsGlitchStatus()

bool AP_AHRS_NavEKF::getGpsGlitchStatus ( ) const

Definition at line 1573 of file AP_AHRS_NavEKF.cpp.

Referenced by get_NavEKF3_const().

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

◆ getLastPosDownReset()

uint32_t AP_AHRS_NavEKF::getLastPosDownReset ( float &  posDelta) const
overridevirtual

Reimplemented from AP_AHRS.

Definition at line 1352 of file AP_AHRS_NavEKF.cpp.

Referenced by get_NavEKF3_const().

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

◆ getLastPosNorthEastReset()

uint32_t AP_AHRS_NavEKF::getLastPosNorthEastReset ( Vector2f pos) const
overridevirtual

Reimplemented from AP_AHRS.

Definition at line 1309 of file AP_AHRS_NavEKF.cpp.

Referenced by get_NavEKF3_const().

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

◆ getLastVelNorthEastReset()

uint32_t AP_AHRS_NavEKF::getLastVelNorthEastReset ( Vector2f vel) const
overridevirtual

Reimplemented from AP_AHRS.

Definition at line 1330 of file AP_AHRS_NavEKF.cpp.

Referenced by get_NavEKF3_const().

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

◆ getLastYawResetAngle()

uint32_t AP_AHRS_NavEKF::getLastYawResetAngle ( float &  yawAng) const
overridevirtual

Reimplemented from AP_AHRS.

Definition at line 1288 of file AP_AHRS_NavEKF.cpp.

Referenced by get_NavEKF3_const().

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

◆ getMagOffsets()

bool AP_AHRS_NavEKF::getMagOffsets ( uint8_t  mag_idx,
Vector3f magOffsets 
) const

Definition at line 1216 of file AP_AHRS_NavEKF.cpp.

Referenced by get_NavEKF3_const().

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

◆ groundspeed_vector()

Vector2f AP_AHRS_NavEKF::groundspeed_vector ( void  )
overridevirtual

Reimplemented from AP_AHRS.

Definition at line 564 of file AP_AHRS_NavEKF.cpp.

Referenced by get_NavEKF3_const().

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

◆ have_ekf_logging()

bool AP_AHRS_NavEKF::have_ekf_logging ( void  ) const
overridevirtual

Reimplemented from AP_AHRS.

Definition at line 1583 of file AP_AHRS_NavEKF.cpp.

Referenced by force_ekf_start().

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

◆ have_inertial_nav()

bool AP_AHRS_NavEKF::have_inertial_nav ( void  ) const
overridevirtual

Reimplemented from AP_AHRS.

Definition at line 620 of file AP_AHRS_NavEKF.cpp.

Referenced by SoloGimbalEKF::fuseVelocity(), and get_NavEKF3_const().

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

◆ healthy()

bool AP_AHRS_NavEKF::healthy ( void  ) const
overridevirtual

Reimplemented from AP_AHRS_DCM.

Definition at line 1040 of file AP_AHRS_NavEKF.cpp.

Referenced by get_NavEKF3_const().

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

◆ initialised()

bool AP_AHRS_NavEKF::initialised ( void  ) const
overridevirtual

Reimplemented from AP_AHRS.

Definition at line 1094 of file AP_AHRS_NavEKF.cpp.

Referenced by get_NavEKF3_const().

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

◆ operator=()

AP_AHRS_NavEKF& AP_AHRS_NavEKF::operator= ( const AP_AHRS_NavEKF )
delete

◆ prearm_failure_reason()

const char * AP_AHRS_NavEKF::prearm_failure_reason ( void  ) const
overridevirtual

Reimplemented from AP_AHRS.

Definition at line 1269 of file AP_AHRS_NavEKF.cpp.

Referenced by get_NavEKF3_const().

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

◆ reset()

void AP_AHRS_NavEKF::reset ( bool  recover_eulers = false)
overridevirtual

Reimplemented from AP_AHRS_DCM.

Definition at line 369 of file AP_AHRS_NavEKF.cpp.

Here is the call graph for this function:

◆ reset_attitude()

void AP_AHRS_NavEKF::reset_attitude ( const float &  roll,
const float &  pitch,
const float &  yaw 
)
overridevirtual

Reimplemented from AP_AHRS_DCM.

Definition at line 382 of file AP_AHRS_NavEKF.cpp.

Here is the call graph for this function:

◆ reset_gyro_drift()

void AP_AHRS_NavEKF::reset_gyro_drift ( void  )
overridevirtual

Reimplemented from AP_AHRS_DCM.

Definition at line 71 of file AP_AHRS_NavEKF.cpp.

Here is the call graph for this function:

◆ resetHeightDatum()

bool AP_AHRS_NavEKF::resetHeightDatum ( void  )
overridevirtual

Reimplemented from AP_AHRS.

Definition at line 1374 of file AP_AHRS_NavEKF.cpp.

Referenced by get_NavEKF3_const().

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

◆ send_ekf_status_report()

void AP_AHRS_NavEKF::send_ekf_status_report ( mavlink_channel_t  chan) const

Definition at line 1398 of file AP_AHRS_NavEKF.cpp.

Referenced by get_NavEKF3_const().

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

◆ set_ekf_use()

void AP_AHRS_NavEKF::set_ekf_use ( bool  setting)

Definition at line 1088 of file AP_AHRS_NavEKF.cpp.

Referenced by get_NavEKF3_const().

Here is the caller graph for this function:

◆ set_origin()

bool AP_AHRS_NavEKF::set_origin ( const Location loc)
overridevirtual

Reimplemented from AP_AHRS.

Definition at line 593 of file AP_AHRS_NavEKF.cpp.

Referenced by get_NavEKF3_const().

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

◆ setInhibitGPS()

uint8_t AP_AHRS_NavEKF::setInhibitGPS ( void  )

Definition at line 1171 of file AP_AHRS_NavEKF.cpp.

Referenced by get_NavEKF3_const().

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

◆ setTakeoffExpected()

void AP_AHRS_NavEKF::setTakeoffExpected ( bool  val)

Definition at line 1535 of file AP_AHRS_NavEKF.cpp.

Referenced by get_NavEKF3_const().

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

◆ setTouchdownExpected()

void AP_AHRS_NavEKF::setTouchdownExpected ( bool  val)

Definition at line 1554 of file AP_AHRS_NavEKF.cpp.

Referenced by get_NavEKF3_const().

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

◆ update()

void AP_AHRS_NavEKF::update ( bool  skip_ins_update = false)
overridevirtual

Reimplemented from AP_AHRS_DCM.

Definition at line 81 of file AP_AHRS_NavEKF.cpp.

Referenced by loop().

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

◆ update_DCM()

void AP_AHRS_NavEKF::update_DCM ( bool  skip_ins_update)
private

Definition at line 125 of file AP_AHRS_NavEKF.cpp.

Referenced by update().

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

◆ update_EKF2()

void AP_AHRS_NavEKF::update_EKF2 ( void  )
private

Definition at line 141 of file AP_AHRS_NavEKF.cpp.

Referenced by update().

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

◆ update_EKF3()

void AP_AHRS_NavEKF::update_EKF3 ( void  )
private

Definition at line 214 of file AP_AHRS_NavEKF.cpp.

Referenced by update().

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

◆ update_SITL()

void AP_AHRS_NavEKF::update_SITL ( void  )
private

Definition at line 289 of file AP_AHRS_NavEKF.cpp.

Referenced by update().

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

◆ use_compass()

bool AP_AHRS_NavEKF::use_compass ( void  )
overridevirtual

Reimplemented from AP_AHRS_DCM.

Definition at line 482 of file AP_AHRS_NavEKF.cpp.

Here is the call graph for this function:

◆ wind_estimate()

Vector3f AP_AHRS_NavEKF::wind_estimate ( void  ) const
overridevirtual

Reimplemented from AP_AHRS_DCM.

Definition at line 448 of file AP_AHRS_NavEKF.cpp.

Here is the call graph for this function:

◆ writeBodyFrameOdom()

void AP_AHRS_NavEKF::writeBodyFrameOdom ( float  quality,
const Vector3f delPos,
const Vector3f delAng,
float  delTime,
uint32_t  timeStamp_ms,
const Vector3f posOffset 
)

Definition at line 1158 of file AP_AHRS_NavEKF.cpp.

Referenced by get_NavEKF3_const().

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

◆ writeExtNavData()

void AP_AHRS_NavEKF::writeExtNavData ( const Vector3f sensOffset,
const Vector3f pos,
const Quaternion quat,
float  posErr,
float  angErr,
uint32_t  timeStamp_ms,
uint32_t  resetTime_ms 
)
overridevirtual

Reimplemented from AP_AHRS.

Definition at line 1164 of file AP_AHRS_NavEKF.cpp.

Referenced by get_NavEKF3_const().

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

◆ writeOptFlowMeas()

void AP_AHRS_NavEKF::writeOptFlowMeas ( uint8_t &  rawFlowQuality,
Vector2f rawFlowRates,
Vector2f rawGyroRates,
uint32_t &  msecFlowMeas,
const Vector3f posOffset 
)

Definition at line 1151 of file AP_AHRS_NavEKF.cpp.

Referenced by get_NavEKF3_const().

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

Member Data Documentation

◆ _accel_ef_ekf

Vector3f AP_AHRS_NavEKF::_accel_ef_ekf[INS_MAX_INSTANCES]
private

Definition at line 281 of file AP_AHRS_NavEKF.h.

Referenced by get_accel_ef(), update_EKF2(), update_EKF3(), and update_SITL().

◆ _accel_ef_ekf_blended

Vector3f AP_AHRS_NavEKF::_accel_ef_ekf_blended
private

Definition at line 282 of file AP_AHRS_NavEKF.h.

Referenced by get_accel_ef_blended(), update_EKF2(), update_EKF3(), and update_SITL().

◆ _dcm_attitude

Vector3f AP_AHRS_NavEKF::_dcm_attitude
private

Definition at line 278 of file AP_AHRS_NavEKF.h.

Referenced by get_secondary_attitude(), reset(), reset_attitude(), and update_DCM().

◆ _dcm_matrix

Matrix3f AP_AHRS_NavEKF::_dcm_matrix
private

◆ _ekf2_started

bool AP_AHRS_NavEKF::_ekf2_started
private

◆ _ekf3_started

bool AP_AHRS_NavEKF::_ekf3_started
private

◆ _ekf_flags

Flags AP_AHRS_NavEKF::_ekf_flags
private

Definition at line 285 of file AP_AHRS_NavEKF.h.

Referenced by always_use_EKF().

◆ _force_ekf

bool AP_AHRS_NavEKF::_force_ekf
private

Definition at line 276 of file AP_AHRS_NavEKF.h.

Referenced by force_ekf_start(), update_EKF2(), and update_EKF3().

◆ _gyro_drift

Vector3f AP_AHRS_NavEKF::_gyro_drift
private

Definition at line 279 of file AP_AHRS_NavEKF.h.

Referenced by get_gyro_drift(), update_EKF2(), update_EKF3(), and update_SITL().

◆ _gyro_estimate

Vector3f AP_AHRS_NavEKF::_gyro_estimate
private

Definition at line 280 of file AP_AHRS_NavEKF.h.

Referenced by get_gyro(), update_EKF2(), update_EKF3(), and update_SITL().

◆ _last_body_odm_update_ms

uint32_t AP_AHRS_NavEKF::_last_body_odm_update_ms = 0
private

Definition at line 297 of file AP_AHRS_NavEKF.h.

Referenced by update_SITL().

◆ _sitl

SITL::SITL* AP_AHRS_NavEKF::_sitl
private

◆ EKF2

NavEKF2& AP_AHRS_NavEKF::EKF2
private

◆ EKF3

NavEKF3& AP_AHRS_NavEKF::EKF3
private

◆ start_time_ms

uint32_t AP_AHRS_NavEKF::start_time_ms = 0
private

Definition at line 284 of file AP_AHRS_NavEKF.h.

Referenced by initialised(), update_EKF2(), and update_EKF3().

◆ startup_delay_ms

const uint16_t AP_AHRS_NavEKF::startup_delay_ms = 1000
private

Definition at line 283 of file AP_AHRS_NavEKF.h.

Referenced by update_EKF2(), and update_EKF3().


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