APM:Libraries
Public Member Functions | Static Public Attributes | Private Member Functions | Private Attributes | Friends | List of all members
NavEKF3 Class Reference

#include <AP_NavEKF3.h>

Collaboration diagram for NavEKF3:
[legend]

Public Member Functions

 NavEKF3 (const AP_AHRS *ahrs, const RangeFinder &rng)
 
 NavEKF3 (const NavEKF3 &other)=delete
 
NavEKF3operator= (const NavEKF3 &)=delete
 
uint8_t activeCores (void) const
 
bool InitialiseFilter (void)
 
void UpdateFilter (void)
 
void check_log_write (void)
 
bool healthy (void) const
 
int8_t getPrimaryCoreIndex (void) const
 
int8_t getPrimaryCoreIMUIndex (void) const
 
bool getPosNE (int8_t instance, Vector2f &posNE) const
 
bool getPosD (int8_t instance, float &posD) const
 
void getVelNED (int8_t instance, Vector3f &vel) const
 
float getPosDownDerivative (int8_t instance) const
 
void getAccelNED (Vector3f &accelNED) const
 
void getGyroBias (int8_t instance, Vector3f &gyroBias) const
 
void getAccelBias (int8_t instance, Vector3f &accelBias) const
 
void getTiltError (int8_t instance, float &ang) const
 
void resetGyroBias (void)
 
bool resetHeightDatum (void)
 
uint8_t setInhibitGPS (void)
 
void setInhibitGpsVertVelUse (const bool varIn)
 
void getEkfControlLimits (float &ekfGndSpdLimit, float &ekfNavVelGainScaler) const
 
void getWind (int8_t instance, Vector3f &wind) const
 
void getMagNED (int8_t instance, Vector3f &magNED) const
 
void getMagXYZ (int8_t instance, Vector3f &magXYZ) const
 
uint8_t getActiveMag (int8_t instance) const
 
bool getMagOffsets (uint8_t mag_idx, Vector3f &magOffsets) const
 
bool getLLH (struct Location &loc) const
 
bool getOriginLLH (int8_t instance, struct Location &loc) const
 
bool setOriginLLH (const Location &loc)
 
bool getHAGL (float &HAGL) const
 
void getEulerAngles (int8_t instance, Vector3f &eulers) const
 
void getRotationBodyToNED (Matrix3f &mat) const
 
void getQuaternion (int8_t instance, Quaternion &quat) const
 
void getInnovations (int8_t index, Vector3f &velInnov, Vector3f &posInnov, Vector3f &magInnov, float &tasInnov, float &yawInnov) const
 
void getOutputTrackingError (int8_t instance, Vector3f &error) const
 
void getVariances (int8_t instance, float &velVar, float &posVar, float &hgtVar, Vector3f &magVar, float &tasVar, Vector2f &offset) const
 
void getStateVariances (int8_t instance, float stateVar[24]) const
 
bool use_compass (void) 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 writeWheelOdom (float delAng, float delTime, uint32_t timeStamp_ms, const Vector3f &posOffset, float radius)
 
uint32_t getBodyFrameOdomDebug (int8_t instance, Vector3f &velInnov, Vector3f &velInnovVar) const
 
void getFlowDebug (int8_t instance, float &varFlow, float &gndOffset, float &flowInnovX, float &flowInnovY, float &auxInnov, float &HAGL, float &rngInnov, float &range, float &gndOffsetErr) const
 
bool getRangeBeaconDebug (int8_t instance, uint8_t &ID, float &rng, float &innov, float &innovVar, float &testRatio, Vector3f &beaconPosNED, float &offsetHigh, float &offsetLow, Vector3f &posNED) const
 
void setTakeoffExpected (bool val)
 
void setTouchdownExpected (bool val)
 
void setTerrainHgtStable (bool val)
 
void getFilterFaults (int8_t instance, uint16_t &faults) const
 
void getFilterTimeouts (int8_t instance, uint8_t &timeouts) const
 
void getFilterGpsStatus (int8_t instance, nav_gps_status &faults) const
 
void getFilterStatus (int8_t instance, nav_filter_status &status) const
 
void send_status_report (mavlink_channel_t chan)
 
bool getHeightControlLimit (float &height) const
 
uint32_t getLastYawResetAngle (float &yawAngDelta)
 
uint32_t getLastPosNorthEastReset (Vector2f &posDelta)
 
uint32_t getLastVelNorthEastReset (Vector2f &vel) const
 
uint32_t getLastPosDownReset (float &posDelta)
 
const char * prearm_failure_reason (void) const
 
void set_baro_alt_noise (float noise)
 
void set_enable (bool enable)
 
bool have_ekf_logging (void) const
 
void getTimingStatistics (int8_t instance, struct ekf_timing &timing) const
 

Static Public Attributes

static const struct AP_Param::GroupInfo var_info []
 

Private Member Functions

void updateLaneSwitchYawResetData (uint8_t new_primary, uint8_t old_primary)
 
void updateLaneSwitchPosResetData (uint8_t new_primary, uint8_t old_primary)
 
void updateLaneSwitchPosDownResetData (uint8_t new_primary, uint8_t old_primary)
 

Private Attributes

uint8_t num_cores
 
uint8_t primary
 
NavEKF3_corecore = nullptr
 
const AP_AHRS_ahrs
 
const RangeFinder_rng
 
uint32_t _frameTimeUsec
 
uint8_t _framesPerPrediction
 
AP_Int8 _enable
 
AP_Float _gpsHorizVelNoise
 
AP_Float _gpsVertVelNoise
 
AP_Float _gpsHorizPosNoise
 
AP_Float _baroAltNoise
 
AP_Float _magNoise
 
AP_Float _easNoise
 
AP_Float _windVelProcessNoise
 
AP_Float _wndVarHgtRateScale
 
AP_Float _magEarthProcessNoise
 
AP_Float _magBodyProcessNoise
 
AP_Float _gyrNoise
 
AP_Float _accNoise
 
AP_Float _gyroBiasProcessNoise
 
AP_Float _accelBiasProcessNoise
 
AP_Int16 _hgtDelay_ms
 
AP_Int8 _fusionModeGPS
 
AP_Int16 _gpsVelInnovGate
 
AP_Int16 _gpsPosInnovGate
 
AP_Int16 _hgtInnovGate
 
AP_Int16 _magInnovGate
 
AP_Int16 _tasInnovGate
 
AP_Int8 _magCal
 
AP_Int8 _gpsGlitchRadiusMax
 
AP_Float _flowNoise
 
AP_Int16 _flowInnovGate
 
AP_Int8 _flowDelay_ms
 
AP_Int16 _rngInnovGate
 
AP_Float _maxFlowRate
 
AP_Int8 _altSource
 
AP_Float _rngNoise
 
AP_Int8 _gpsCheck
 
AP_Int8 _imuMask
 
AP_Int16 _gpsCheckScaler
 
AP_Float _noaidHorizNoise
 
AP_Int8 _logging_mask
 
AP_Float _yawNoise
 
AP_Int16 _yawInnovGate
 
AP_Int8 _tauVelPosOutput
 
AP_Int8 _useRngSwHgt
 
AP_Float _terrGradMax
 
AP_Float _rngBcnNoise
 
AP_Int16 _rngBcnInnovGate
 
AP_Int8 _rngBcnDelay_ms
 
AP_Float _useRngSwSpd
 
AP_Float _accBiasLim
 
AP_Int8 _magMask
 
AP_Int8 _originHgtMode
 
AP_Float _visOdmVelErrMax
 
AP_Float _visOdmVelErrMin
 
AP_Float _wencOdmVelErr
 
const float gpsNEVelVarAccScale = 0.05f
 
const float gpsDVelVarAccScale = 0.07f
 
const float gpsPosVarAccScale = 0.05f
 
const uint16_t magDelay_ms = 60
 
const uint16_t tasDelay_ms = 100
 
const uint16_t tiltDriftTimeMax_ms = 15000
 
const uint16_t posRetryTimeUseVel_ms = 10000
 
const uint16_t posRetryTimeNoVel_ms = 7000
 
const uint16_t hgtRetryTimeMode0_ms = 10000
 
const uint16_t hgtRetryTimeMode12_ms = 5000
 
const uint16_t tasRetryTime_ms = 5000
 
const uint32_t magFailTimeLimit_ms = 10000
 
const float magVarRateScale = 0.005f
 
const float gyroBiasNoiseScaler = 2.0f
 
const uint16_t hgtAvg_ms = 100
 
const uint16_t betaAvg_ms = 100
 
const float covTimeStepMax = 0.1f
 
const float covDelAngMax = 0.05f
 
const float DCM33FlowMin = 0.71f
 
const float fScaleFactorPnoise = 1e-10f
 
const uint8_t flowTimeDeltaAvg_ms = 100
 
const uint32_t flowIntervalMax_ms = 100
 
const uint16_t gndEffectTimeout_ms = 1000
 
const float gndEffectBaroScaler = 4.0f
 
const uint8_t gndGradientSigma = 50
 
const uint16_t fusionTimeStep_ms = 10
 
const uint8_t sensorIntervalMin_ms = 50
 
struct {
   bool   enabled:1
 
   bool   log_compass:1
 
   bool   log_gps:1
 
   bool   log_baro:1
 
   bool   log_imu:1
 
logging
 
uint64_t imuSampleTime_us
 
struct {
   uint32_t   last_function_call
 
   bool   core_changed
 
   uint32_t   last_primary_change
 
   float   core_delta
 
yaw_reset_data
 
struct {
   uint32_t   last_function_call
 
   bool   core_changed
 
   uint32_t   last_primary_change
 
   Vector2f   core_delta
 
pos_reset_data
 
struct {
   uint32_t   last_function_call
 
   bool   core_changed
 
   uint32_t   last_primary_change
 
   float   core_delta
 
pos_down_reset_data
 
bool runCoreSelection
 
bool coreSetupRequired [7]
 
uint8_t coreImuIndex [7]
 
bool inhibitGpsVertVelUse
 

Friends

class NavEKF3_core
 

Detailed Description

Definition at line 34 of file AP_NavEKF3.h.

Constructor & Destructor Documentation

◆ NavEKF3() [1/2]

NavEKF3::NavEKF3 ( const AP_AHRS ahrs,
const RangeFinder rng 
)

Definition at line 582 of file AP_NavEKF3.cpp.

Here is the call graph for this function:

◆ NavEKF3() [2/2]

NavEKF3::NavEKF3 ( const NavEKF3 other)
delete

Member Function Documentation

◆ activeCores()

uint8_t NavEKF3::activeCores ( void  ) const
inline

Definition at line 47 of file AP_NavEKF3.h.

Referenced by DataFlash_Class::Log_Write_POS().

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

◆ check_log_write()

void NavEKF3::check_log_write ( void  )

Definition at line 592 of file AP_NavEKF3.cpp.

Referenced by activeCores(), InitialiseFilter(), and UpdateFilter().

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

◆ getAccelBias()

void NavEKF3::getAccelBias ( int8_t  instance,
Vector3f accelBias 
) const

Definition at line 878 of file AP_NavEKF3.cpp.

Referenced by activeCores(), AP_AHRS_NavEKF::getCorrectedDeltaVelocityNED(), DataFlash_Class::Log_Write_POS(), and AP_AHRS_NavEKF::update_EKF3().

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

◆ getAccelNED()

void NavEKF3::getAccelNED ( Vector3f accelNED) const

Definition at line 861 of file AP_NavEKF3.cpp.

Referenced by activeCores().

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

◆ getActiveMag()

uint8_t NavEKF3::getActiveMag ( int8_t  instance) const

Definition at line 974 of file AP_NavEKF3.cpp.

Referenced by DataFlash_Class::Log_Write_POS(), and setInhibitGpsVertVelUse().

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

◆ getBodyFrameOdomDebug()

uint32_t NavEKF3::getBodyFrameOdomDebug ( int8_t  instance,
Vector3f velInnov,
Vector3f velInnovVar 
) const

Definition at line 1185 of file AP_NavEKF3.cpp.

Referenced by DataFlash_Class::Log_Write_POS(), and setInhibitGpsVertVelUse().

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

◆ getEkfControlLimits()

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

Definition at line 939 of file AP_NavEKF3.cpp.

Referenced by AP_AHRS_NavEKF::getEkfControlLimits(), and setInhibitGpsVertVelUse().

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

◆ getEulerAngles()

void NavEKF3::getEulerAngles ( int8_t  instance,
Vector3f eulers 
) const

Definition at line 1051 of file AP_NavEKF3.cpp.

Referenced by DataFlash_Class::Log_Write_POS(), setInhibitGpsVertVelUse(), and AP_AHRS_NavEKF::update_EKF3().

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

◆ getFilterFaults()

void NavEKF3::getFilterFaults ( int8_t  instance,
uint16_t &  faults 
) const

Definition at line 1257 of file AP_NavEKF3.cpp.

Referenced by AP_AHRS_NavEKF::active_EKF_type(), DataFlash_Class::Log_Write_POS(), and setInhibitGpsVertVelUse().

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

◆ getFilterGpsStatus()

void NavEKF3::getFilterGpsStatus ( int8_t  instance,
nav_gps_status faults 
) const

Definition at line 1304 of file AP_NavEKF3.cpp.

Referenced by DataFlash_Class::Log_Write_POS(), and setInhibitGpsVertVelUse().

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

◆ getFilterStatus()

void NavEKF3::getFilterStatus ( int8_t  instance,
nav_filter_status status 
) const

Definition at line 1291 of file AP_NavEKF3.cpp.

Referenced by AP_AHRS_NavEKF::active_EKF_type(), AP_AHRS_NavEKF::get_filter_status(), DataFlash_Class::Log_Write_POS(), setInhibitGpsVertVelUse(), and AP_AHRS_NavEKF::update_EKF3().

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

◆ getFilterTimeouts()

void NavEKF3::getFilterTimeouts ( int8_t  instance,
uint8_t &  timeouts 
) const

Definition at line 1278 of file AP_NavEKF3.cpp.

Referenced by DataFlash_Class::Log_Write_POS(), and setInhibitGpsVertVelUse().

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

◆ getFlowDebug()

void NavEKF3::getFlowDebug ( int8_t  instance,
float &  varFlow,
float &  gndOffset,
float &  flowInnovX,
float &  flowInnovY,
float &  auxInnov,
float &  HAGL,
float &  rngInnov,
float &  range,
float &  gndOffsetErr 
) const

Definition at line 1139 of file AP_NavEKF3.cpp.

Referenced by DataFlash_Class::Log_Write_POS(), and setInhibitGpsVertVelUse().

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

◆ getGyroBias()

void NavEKF3::getGyroBias ( int8_t  instance,
Vector3f gyroBias 
) const

Definition at line 869 of file AP_NavEKF3.cpp.

Referenced by activeCores(), DataFlash_Class::Log_Write_POS(), and AP_AHRS_NavEKF::update_EKF3().

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

◆ getHAGL()

bool NavEKF3::getHAGL ( float &  HAGL) const

Definition at line 1042 of file AP_NavEKF3.cpp.

Referenced by AP_AHRS_NavEKF::get_hagl(), and setInhibitGpsVertVelUse().

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

◆ getHeightControlLimit()

bool NavEKF3::getHeightControlLimit ( float &  height) const

Definition at line 1325 of file AP_NavEKF3.cpp.

Referenced by AP_AHRS_NavEKF::get_hgt_ctrl_limit(), and setInhibitGpsVertVelUse().

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

◆ getInnovations()

void NavEKF3::getInnovations ( int8_t  index,
Vector3f velInnov,
Vector3f posInnov,
Vector3f magInnov,
float &  tasInnov,
float &  yawInnov 
) const

Definition at line 1077 of file AP_NavEKF3.cpp.

Referenced by DataFlash_Class::Log_Write_POS(), and setInhibitGpsVertVelUse().

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

◆ getLastPosDownReset()

uint32_t NavEKF3::getLastPosDownReset ( float &  posDelta)

Definition at line 1431 of file AP_NavEKF3.cpp.

Referenced by AP_AHRS_NavEKF::getLastPosDownReset(), setInhibitGpsVertVelUse(), and updateLaneSwitchPosDownResetData().

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

◆ getLastPosNorthEastReset()

uint32_t NavEKF3::getLastPosNorthEastReset ( Vector2f posDelta)

Definition at line 1374 of file AP_NavEKF3.cpp.

Referenced by AP_AHRS_NavEKF::getLastPosNorthEastReset(), setInhibitGpsVertVelUse(), and updateLaneSwitchPosResetData().

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

◆ getLastVelNorthEastReset()

uint32_t NavEKF3::getLastVelNorthEastReset ( Vector2f vel) const

Definition at line 1411 of file AP_NavEKF3.cpp.

Referenced by AP_AHRS_NavEKF::getLastVelNorthEastReset(), and setInhibitGpsVertVelUse().

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

◆ getLastYawResetAngle()

uint32_t NavEKF3::getLastYawResetAngle ( float &  yawAngDelta)

Definition at line 1336 of file AP_NavEKF3.cpp.

Referenced by AP_AHRS_NavEKF::getLastYawResetAngle(), setInhibitGpsVertVelUse(), and updateLaneSwitchYawResetData().

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

◆ getLLH()

bool NavEKF3::getLLH ( struct Location loc) const

Definition at line 1007 of file AP_NavEKF3.cpp.

Referenced by AP_AHRS_NavEKF::get_location(), AP_AHRS_NavEKF::get_position(), and setInhibitGpsVertVelUse().

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

◆ getMagNED()

void NavEKF3::getMagNED ( int8_t  instance,
Vector3f magNED 
) const

Definition at line 956 of file AP_NavEKF3.cpp.

Referenced by AP_AHRS_NavEKF::get_mag_field_NED(), DataFlash_Class::Log_Write_POS(), and setInhibitGpsVertVelUse().

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

◆ getMagOffsets()

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

Definition at line 986 of file AP_NavEKF3.cpp.

Referenced by AP_AHRS_NavEKF::getMagOffsets(), and setInhibitGpsVertVelUse().

Here is the caller graph for this function:

◆ getMagXYZ()

void NavEKF3::getMagXYZ ( int8_t  instance,
Vector3f magXYZ 
) const

Definition at line 965 of file AP_NavEKF3.cpp.

Referenced by AP_AHRS_NavEKF::get_mag_field_correction(), DataFlash_Class::Log_Write_POS(), and setInhibitGpsVertVelUse().

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

◆ getOriginLLH()

bool NavEKF3::getOriginLLH ( int8_t  instance,
struct Location loc 
) const

Definition at line 1019 of file AP_NavEKF3.cpp.

Referenced by AP_AHRS_NavEKF::get_origin(), AP_AHRS_NavEKF::get_position(), DataFlash_Class::Log_Write_POS(), and setInhibitGpsVertVelUse().

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

◆ getOutputTrackingError()

void NavEKF3::getOutputTrackingError ( int8_t  instance,
Vector3f error 
) const

Definition at line 1086 of file AP_NavEKF3.cpp.

Referenced by DataFlash_Class::Log_Write_POS(), and setInhibitGpsVertVelUse().

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

◆ getPosD()

bool NavEKF3::getPosD ( int8_t  instance,
float &  posD 
) const

Definition at line 831 of file AP_NavEKF3.cpp.

Referenced by activeCores(), AP_AHRS_NavEKF::get_position(), AP_AHRS_NavEKF::get_relative_position_D_origin(), AP_AHRS_NavEKF::get_relative_position_NED_origin(), and DataFlash_Class::Log_Write_POS().

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

◆ getPosDownDerivative()

float NavEKF3::getPosDownDerivative ( int8_t  instance) const

Definition at line 850 of file AP_NavEKF3.cpp.

Referenced by activeCores(), AP_AHRS_NavEKF::get_vert_pos_rate(), and DataFlash_Class::Log_Write_POS().

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

◆ getPosNE()

bool NavEKF3::getPosNE ( int8_t  instance,
Vector2f posNE 
) const

Definition at line 819 of file AP_NavEKF3.cpp.

Referenced by activeCores(), AP_AHRS_NavEKF::get_relative_position_NE_origin(), AP_AHRS_NavEKF::get_relative_position_NED_origin(), and DataFlash_Class::Log_Write_POS().

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

◆ getPrimaryCoreIMUIndex()

int8_t NavEKF3::getPrimaryCoreIMUIndex ( void  ) const

Definition at line 808 of file AP_NavEKF3.cpp.

Referenced by activeCores(), AP_AHRS_NavEKF::get_primary_IMU_index(), AP_AHRS_NavEKF::getCorrectedDeltaVelocityNED(), and AP_AHRS_NavEKF::update_EKF3().

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

◆ getPrimaryCoreIndex()

int8_t NavEKF3::getPrimaryCoreIndex ( void  ) const

Definition at line 798 of file AP_NavEKF3.cpp.

Referenced by activeCores(), and DataFlash_Class::Log_Write_POS().

Here is the caller graph for this function:

◆ getQuaternion()

void NavEKF3::getQuaternion ( int8_t  instance,
Quaternion quat 
) const

Definition at line 1068 of file AP_NavEKF3.cpp.

Referenced by DataFlash_Class::Log_Write_POS(), and setInhibitGpsVertVelUse().

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

◆ getRangeBeaconDebug()

bool NavEKF3::getRangeBeaconDebug ( int8_t  instance,
uint8_t &  ID,
float &  rng,
float &  innov,
float &  innovVar,
float &  testRatio,
Vector3f beaconPosNED,
float &  offsetHigh,
float &  offsetLow,
Vector3f posNED 
) const

Definition at line 1200 of file AP_NavEKF3.cpp.

Referenced by DataFlash_Class::Log_Write_POS(), and setInhibitGpsVertVelUse().

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

◆ getRotationBodyToNED()

void NavEKF3::getRotationBodyToNED ( Matrix3f mat) const

Definition at line 1060 of file AP_NavEKF3.cpp.

Referenced by setInhibitGpsVertVelUse(), and AP_AHRS_NavEKF::update_EKF3().

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

◆ getStateVariances()

void NavEKF3::getStateVariances ( int8_t  instance,
float  stateVar[24] 
) const

Definition at line 1104 of file AP_NavEKF3.cpp.

Referenced by DataFlash_Class::Log_Write_POS(), and setInhibitGpsVertVelUse().

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

◆ getTiltError()

void NavEKF3::getTiltError ( int8_t  instance,
float &  ang 
) const

Definition at line 887 of file AP_NavEKF3.cpp.

Referenced by activeCores(), and DataFlash_Class::Log_Write_POS().

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

◆ getTimingStatistics()

void NavEKF3::getTimingStatistics ( int8_t  instance,
struct ekf_timing timing 
) const

Definition at line 1547 of file AP_NavEKF3.cpp.

Referenced by have_ekf_logging(), and DataFlash_Class::Log_Write_POS().

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

◆ getVariances()

void NavEKF3::getVariances ( int8_t  instance,
float &  velVar,
float &  posVar,
float &  hgtVar,
Vector3f magVar,
float &  tasVar,
Vector2f offset 
) const

Definition at line 1095 of file AP_NavEKF3.cpp.

Referenced by AP_AHRS_NavEKF::get_variances(), DataFlash_Class::Log_Write_POS(), and setInhibitGpsVertVelUse().

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

◆ getVelNED()

void NavEKF3::getVelNED ( int8_t  instance,
Vector3f vel 
) const

Definition at line 841 of file AP_NavEKF3.cpp.

Referenced by activeCores(), AP_AHRS_NavEKF::get_velocity_NED(), AP_AHRS_NavEKF::groundspeed_vector(), and DataFlash_Class::Log_Write_POS().

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

◆ getWind()

void NavEKF3::getWind ( int8_t  instance,
Vector3f wind 
) const

Definition at line 947 of file AP_NavEKF3.cpp.

Referenced by DataFlash_Class::Log_Write_POS(), setInhibitGpsVertVelUse(), and AP_AHRS_NavEKF::wind_estimate().

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

◆ have_ekf_logging()

bool NavEKF3::have_ekf_logging ( void  ) const
inline

Definition at line 352 of file AP_NavEKF3.h.

Referenced by check_log_write(), and AP_AHRS_NavEKF::have_ekf_logging().

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

◆ healthy()

bool NavEKF3::healthy ( void  ) const

Definition at line 788 of file AP_NavEKF3.cpp.

Referenced by AP_AHRS_NavEKF::active_EKF_type(), activeCores(), AP_AHRS_NavEKF::healthy(), and UpdateFilter().

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

◆ InitialiseFilter()

bool NavEKF3::InitialiseFilter ( void  )

Definition at line 620 of file AP_NavEKF3.cpp.

Referenced by activeCores(), AP_AHRS_NavEKF::reset(), AP_AHRS_NavEKF::reset_attitude(), and AP_AHRS_NavEKF::update_EKF3().

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

◆ operator=()

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

◆ prearm_failure_reason()

const char * NavEKF3::prearm_failure_reason ( void  ) const

Definition at line 1420 of file AP_NavEKF3.cpp.

Referenced by AP_AHRS_NavEKF::prearm_failure_reason(), and setInhibitGpsVertVelUse().

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

◆ resetGyroBias()

void NavEKF3::resetGyroBias ( void  )

Definition at line 896 of file AP_NavEKF3.cpp.

Referenced by activeCores(), and AP_AHRS_NavEKF::reset_gyro_drift().

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

◆ resetHeightDatum()

bool NavEKF3::resetHeightDatum ( void  )

Definition at line 910 of file AP_NavEKF3.cpp.

Referenced by activeCores(), and AP_AHRS_NavEKF::resetHeightDatum().

Here is the caller graph for this function:

◆ send_status_report()

void NavEKF3::send_status_report ( mavlink_channel_t  chan)

Definition at line 1315 of file AP_NavEKF3.cpp.

Referenced by AP_AHRS_NavEKF::send_ekf_status_report(), and setInhibitGpsVertVelUse().

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

◆ set_baro_alt_noise()

void NavEKF3::set_baro_alt_noise ( float  noise)
inline

Definition at line 346 of file AP_NavEKF3.h.

◆ set_enable()

void NavEKF3::set_enable ( bool  enable)
inline

Definition at line 349 of file AP_NavEKF3.h.

◆ setInhibitGPS()

uint8_t NavEKF3::setInhibitGPS ( void  )

Definition at line 929 of file AP_NavEKF3.cpp.

Referenced by activeCores(), and AP_AHRS_NavEKF::setInhibitGPS().

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

◆ setInhibitGpsVertVelUse()

void NavEKF3::setInhibitGpsVertVelUse ( const bool  varIn)
inline

Definition at line 126 of file AP_NavEKF3.h.

Here is the call graph for this function:

◆ setOriginLLH()

bool NavEKF3::setOriginLLH ( const Location loc)

Definition at line 1032 of file AP_NavEKF3.cpp.

Referenced by AP_AHRS_NavEKF::set_origin(), and setInhibitGpsVertVelUse().

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

◆ setTakeoffExpected()

void NavEKF3::setTakeoffExpected ( bool  val)

Definition at line 1213 of file AP_NavEKF3.cpp.

Referenced by setInhibitGpsVertVelUse(), and AP_AHRS_NavEKF::setTakeoffExpected().

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

◆ setTerrainHgtStable()

void NavEKF3::setTerrainHgtStable ( bool  val)

Definition at line 1236 of file AP_NavEKF3.cpp.

Referenced by setInhibitGpsVertVelUse().

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

◆ setTouchdownExpected()

void NavEKF3::setTouchdownExpected ( bool  val)

Definition at line 1224 of file AP_NavEKF3.cpp.

Referenced by setInhibitGpsVertVelUse(), and AP_AHRS_NavEKF::setTouchdownExpected().

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

◆ UpdateFilter()

void NavEKF3::UpdateFilter ( void  )

Definition at line 720 of file AP_NavEKF3.cpp.

Referenced by activeCores(), and AP_AHRS_NavEKF::update_EKF3().

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

◆ updateLaneSwitchPosDownResetData()

void NavEKF3::updateLaneSwitchPosDownResetData ( uint8_t  new_primary,
uint8_t  old_primary 
)
private

Definition at line 1520 of file AP_NavEKF3.cpp.

Referenced by UpdateFilter().

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

◆ updateLaneSwitchPosResetData()

void NavEKF3::updateLaneSwitchPosResetData ( uint8_t  new_primary,
uint8_t  old_primary 
)
private

Definition at line 1493 of file AP_NavEKF3.cpp.

Referenced by UpdateFilter().

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

◆ updateLaneSwitchYawResetData()

void NavEKF3::updateLaneSwitchYawResetData ( uint8_t  new_primary,
uint8_t  old_primary 
)
private

Definition at line 1467 of file AP_NavEKF3.cpp.

Referenced by UpdateFilter().

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

◆ use_compass()

bool NavEKF3::use_compass ( void  ) const

Definition at line 1114 of file AP_NavEKF3.cpp.

Referenced by setInhibitGpsVertVelUse(), and AP_AHRS_NavEKF::use_compass().

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

◆ writeBodyFrameOdom()

void NavEKF3::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_NavEKF3.cpp.

Referenced by setInhibitGpsVertVelUse(), AP_AHRS_NavEKF::update_SITL(), and AP_AHRS_NavEKF::writeBodyFrameOdom().

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

◆ writeOptFlowMeas()

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

Definition at line 1129 of file AP_NavEKF3.cpp.

Referenced by setInhibitGpsVertVelUse(), and AP_AHRS_NavEKF::writeOptFlowMeas().

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

◆ writeWheelOdom()

void NavEKF3::writeWheelOdom ( float  delAng,
float  delTime,
uint32_t  timeStamp_ms,
const Vector3f posOffset,
float  radius 
)

Definition at line 1175 of file AP_NavEKF3.cpp.

Referenced by setInhibitGpsVertVelUse().

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

Friends And Related Function Documentation

◆ NavEKF3_core

friend class NavEKF3_core
friend

Definition at line 35 of file AP_NavEKF3.h.

Referenced by InitialiseFilter().

Member Data Documentation

◆ _accBiasLim

AP_Float NavEKF3::_accBiasLim
private

◆ _accelBiasProcessNoise

AP_Float NavEKF3::_accelBiasProcessNoise
private

Definition at line 382 of file AP_NavEKF3.h.

◆ _accNoise

AP_Float NavEKF3::_accNoise
private

Definition at line 380 of file AP_NavEKF3.h.

◆ _ahrs

const AP_AHRS* NavEKF3::_ahrs
private

Definition at line 361 of file AP_NavEKF3.h.

Referenced by check_log_write(), and NavEKF3_core::setup_core().

◆ _altSource

AP_Int8 NavEKF3::_altSource
private

◆ _baroAltNoise

AP_Float NavEKF3::_baroAltNoise
private

◆ _easNoise

AP_Float NavEKF3::_easNoise
private

◆ _enable

AP_Int8 NavEKF3::_enable
private

Definition at line 368 of file AP_NavEKF3.h.

Referenced by InitialiseFilter(), and set_enable().

◆ _flowDelay_ms

AP_Int8 NavEKF3::_flowDelay_ms
private

Definition at line 394 of file AP_NavEKF3.h.

Referenced by NavEKF3_core::setup_core(), and NavEKF3_core::writeOptFlowMeas().

◆ _flowInnovGate

AP_Int16 NavEKF3::_flowInnovGate
private

Definition at line 393 of file AP_NavEKF3.h.

Referenced by NavEKF3_core::EstimateTerrainOffset(), and NavEKF3_core::FuseOptFlow().

◆ _flowNoise

AP_Float NavEKF3::_flowNoise
private

Definition at line 392 of file AP_NavEKF3.h.

Referenced by NavEKF3_core::SelectFlowFusion().

◆ _framesPerPrediction

uint8_t NavEKF3::_framesPerPrediction
private

Definition at line 365 of file AP_NavEKF3.h.

Referenced by InitialiseFilter(), and UpdateFilter().

◆ _frameTimeUsec

uint32_t NavEKF3::_frameTimeUsec
private

Definition at line 364 of file AP_NavEKF3.h.

Referenced by InitialiseFilter(), and UpdateFilter().

◆ _fusionModeGPS

AP_Int8 NavEKF3::_fusionModeGPS
private

◆ _gpsCheck

AP_Int8 NavEKF3::_gpsCheck
private

Definition at line 399 of file AP_NavEKF3.h.

Referenced by NavEKF3_core::calcGpsGoodToAlign().

◆ _gpsCheckScaler

AP_Int16 NavEKF3::_gpsCheckScaler
private

Definition at line 401 of file AP_NavEKF3.h.

Referenced by NavEKF3_core::calcGpsGoodToAlign().

◆ _gpsGlitchRadiusMax

AP_Int8 NavEKF3::_gpsGlitchRadiusMax
private

Definition at line 391 of file AP_NavEKF3.h.

Referenced by NavEKF3_core::FuseVelPosNED().

◆ _gpsHorizPosNoise

AP_Float NavEKF3::_gpsHorizPosNoise
private

◆ _gpsHorizVelNoise

AP_Float NavEKF3::_gpsHorizVelNoise
private

◆ _gpsPosInnovGate

AP_Int16 NavEKF3::_gpsPosInnovGate
private

Definition at line 386 of file AP_NavEKF3.h.

Referenced by NavEKF3_core::FuseVelPosNED().

◆ _gpsVelInnovGate

AP_Int16 NavEKF3::_gpsVelInnovGate
private

Definition at line 385 of file AP_NavEKF3.h.

Referenced by NavEKF3_core::FuseVelPosNED().

◆ _gpsVertVelNoise

AP_Float NavEKF3::_gpsVertVelNoise
private

◆ _gyrNoise

AP_Float NavEKF3::_gyrNoise
private

Definition at line 379 of file AP_NavEKF3.h.

◆ _gyroBiasProcessNoise

AP_Float NavEKF3::_gyroBiasProcessNoise
private

Definition at line 381 of file AP_NavEKF3.h.

◆ _hgtDelay_ms

AP_Int16 NavEKF3::_hgtDelay_ms
private

Definition at line 383 of file AP_NavEKF3.h.

Referenced by NavEKF3_core::readBaroData(), and NavEKF3_core::setup_core().

◆ _hgtInnovGate

AP_Int16 NavEKF3::_hgtInnovGate
private

Definition at line 387 of file AP_NavEKF3.h.

Referenced by NavEKF3_core::FuseVelPosNED().

◆ _imuMask

AP_Int8 NavEKF3::_imuMask
private

Definition at line 400 of file AP_NavEKF3.h.

Referenced by InitialiseFilter().

◆ _logging_mask

AP_Int8 NavEKF3::_logging_mask
private

Definition at line 403 of file AP_NavEKF3.h.

Referenced by check_log_write(), and have_ekf_logging().

◆ _magBodyProcessNoise

AP_Float NavEKF3::_magBodyProcessNoise
private

Definition at line 378 of file AP_NavEKF3.h.

◆ _magCal

AP_Int8 NavEKF3::_magCal
private

Definition at line 390 of file AP_NavEKF3.h.

Referenced by NavEKF3_core::effective_magCal().

◆ _magEarthProcessNoise

AP_Float NavEKF3::_magEarthProcessNoise
private

Definition at line 377 of file AP_NavEKF3.h.

◆ _magInnovGate

AP_Int16 NavEKF3::_magInnovGate
private

Definition at line 388 of file AP_NavEKF3.h.

Referenced by NavEKF3_core::FuseMagnetometer().

◆ _magMask

AP_Int8 NavEKF3::_magMask
private

Definition at line 414 of file AP_NavEKF3.h.

Referenced by NavEKF3_core::effective_magCal().

◆ _magNoise

AP_Float NavEKF3::_magNoise
private

◆ _maxFlowRate

AP_Float NavEKF3::_maxFlowRate
private

◆ _noaidHorizNoise

AP_Float NavEKF3::_noaidHorizNoise
private

Definition at line 402 of file AP_NavEKF3.h.

Referenced by NavEKF3_core::FuseVelPosNED().

◆ _originHgtMode

AP_Int8 NavEKF3::_originHgtMode
private

◆ _rng

const RangeFinder& NavEKF3::_rng
private

◆ _rngBcnDelay_ms

AP_Int8 NavEKF3::_rngBcnDelay_ms
private

Definition at line 411 of file AP_NavEKF3.h.

Referenced by NavEKF3_core::readRngBcnData(), and NavEKF3_core::setup_core().

◆ _rngBcnInnovGate

AP_Int16 NavEKF3::_rngBcnInnovGate
private

Definition at line 410 of file AP_NavEKF3.h.

Referenced by NavEKF3_core::FuseRngBcn(), and NavEKF3_core::FuseRngBcnStatic().

◆ _rngBcnNoise

AP_Float NavEKF3::_rngBcnNoise
private

Definition at line 409 of file AP_NavEKF3.h.

Referenced by NavEKF3_core::readRngBcnData().

◆ _rngInnovGate

AP_Int16 NavEKF3::_rngInnovGate
private

Definition at line 395 of file AP_NavEKF3.h.

Referenced by NavEKF3_core::EstimateTerrainOffset().

◆ _rngNoise

AP_Float NavEKF3::_rngNoise
private

◆ _tasInnovGate

AP_Int16 NavEKF3::_tasInnovGate
private

Definition at line 389 of file AP_NavEKF3.h.

Referenced by NavEKF3_core::FuseAirspeed().

◆ _tauVelPosOutput

AP_Int8 NavEKF3::_tauVelPosOutput
private

Definition at line 406 of file AP_NavEKF3.h.

Referenced by NavEKF3_core::calcOutputStates().

◆ _terrGradMax

AP_Float NavEKF3::_terrGradMax
private

Definition at line 408 of file AP_NavEKF3.h.

Referenced by NavEKF3_core::selectHeightForFusion().

◆ _useRngSwHgt

AP_Int8 NavEKF3::_useRngSwHgt
private

◆ _useRngSwSpd

AP_Float NavEKF3::_useRngSwSpd
private

Definition at line 412 of file AP_NavEKF3.h.

Referenced by NavEKF3_core::selectHeightForFusion().

◆ _visOdmVelErrMax

AP_Float NavEKF3::_visOdmVelErrMax
private

Definition at line 416 of file AP_NavEKF3.h.

Referenced by NavEKF3_core::writeBodyFrameOdom().

◆ _visOdmVelErrMin

AP_Float NavEKF3::_visOdmVelErrMin
private

Definition at line 417 of file AP_NavEKF3.h.

Referenced by NavEKF3_core::writeBodyFrameOdom().

◆ _wencOdmVelErr

AP_Float NavEKF3::_wencOdmVelErr
private

Definition at line 418 of file AP_NavEKF3.h.

Referenced by NavEKF3_core::SelectBodyOdomFusion().

◆ _windVelProcessNoise

AP_Float NavEKF3::_windVelProcessNoise
private

Definition at line 375 of file AP_NavEKF3.h.

◆ _wndVarHgtRateScale

AP_Float NavEKF3::_wndVarHgtRateScale
private

Definition at line 376 of file AP_NavEKF3.h.

◆ _yawInnovGate

AP_Int16 NavEKF3::_yawInnovGate
private

Definition at line 405 of file AP_NavEKF3.h.

Referenced by NavEKF3_core::fuseEulerYaw().

◆ _yawNoise

AP_Float NavEKF3::_yawNoise
private

Definition at line 404 of file AP_NavEKF3.h.

Referenced by NavEKF3_core::controlMagYawReset(), and NavEKF3_core::fuseEulerYaw().

◆ betaAvg_ms

const uint16_t NavEKF3::betaAvg_ms = 100
private

Definition at line 437 of file AP_NavEKF3.h.

Referenced by NavEKF3_core::SelectBetaFusion().

◆ core

NavEKF3_core* NavEKF3::core = nullptr
private

◆ core_changed

bool NavEKF3::core_changed

Definition at line 463 of file AP_NavEKF3.h.

◆ core_delta [1/2]

float NavEKF3::core_delta

Definition at line 465 of file AP_NavEKF3.h.

◆ core_delta [2/2]

Vector2f NavEKF3::core_delta

Definition at line 472 of file AP_NavEKF3.h.

◆ coreImuIndex

uint8_t NavEKF3::coreImuIndex[7]
private

Definition at line 484 of file AP_NavEKF3.h.

Referenced by InitialiseFilter().

◆ coreSetupRequired

bool NavEKF3::coreSetupRequired[7]
private

Definition at line 483 of file AP_NavEKF3.h.

Referenced by InitialiseFilter().

◆ covDelAngMax

const float NavEKF3::covDelAngMax = 0.05f
private

Definition at line 439 of file AP_NavEKF3.h.

◆ covTimeStepMax

const float NavEKF3::covTimeStepMax = 0.1f
private

Definition at line 438 of file AP_NavEKF3.h.

◆ DCM33FlowMin

const float NavEKF3::DCM33FlowMin = 0.71f
private

Definition at line 440 of file AP_NavEKF3.h.

Referenced by NavEKF3_core::SelectFlowFusion().

◆ enabled

bool NavEKF3::enabled

Definition at line 451 of file AP_NavEKF3.h.

◆ flowIntervalMax_ms

const uint32_t NavEKF3::flowIntervalMax_ms = 100
private

Definition at line 443 of file AP_NavEKF3.h.

◆ flowTimeDeltaAvg_ms

const uint8_t NavEKF3::flowTimeDeltaAvg_ms = 100
private

Definition at line 442 of file AP_NavEKF3.h.

Referenced by NavEKF3_core::writeOptFlowMeas().

◆ fScaleFactorPnoise

const float NavEKF3::fScaleFactorPnoise = 1e-10f
private

Definition at line 441 of file AP_NavEKF3.h.

◆ fusionTimeStep_ms

const uint16_t NavEKF3::fusionTimeStep_ms = 10
private

Definition at line 447 of file AP_NavEKF3.h.

◆ gndEffectBaroScaler

const float NavEKF3::gndEffectBaroScaler = 4.0f
private

Definition at line 445 of file AP_NavEKF3.h.

Referenced by NavEKF3_core::selectHeightForFusion().

◆ gndEffectTimeout_ms

const uint16_t NavEKF3::gndEffectTimeout_ms = 1000
private

◆ gndGradientSigma

const uint8_t NavEKF3::gndGradientSigma = 50
private

Definition at line 446 of file AP_NavEKF3.h.

Referenced by NavEKF3_core::EstimateTerrainOffset().

◆ gpsDVelVarAccScale

const float NavEKF3::gpsDVelVarAccScale = 0.07f
private

Definition at line 423 of file AP_NavEKF3.h.

Referenced by NavEKF3_core::FuseVelPosNED().

◆ gpsNEVelVarAccScale

const float NavEKF3::gpsNEVelVarAccScale = 0.05f
private

Definition at line 422 of file AP_NavEKF3.h.

Referenced by NavEKF3_core::FuseVelPosNED().

◆ gpsPosVarAccScale

const float NavEKF3::gpsPosVarAccScale = 0.05f
private

Definition at line 424 of file AP_NavEKF3.h.

Referenced by NavEKF3_core::FuseVelPosNED().

◆ gyroBiasNoiseScaler

const float NavEKF3::gyroBiasNoiseScaler = 2.0f
private

Definition at line 435 of file AP_NavEKF3.h.

◆ hgtAvg_ms

const uint16_t NavEKF3::hgtAvg_ms = 100
private

Definition at line 436 of file AP_NavEKF3.h.

Referenced by NavEKF3_core::selectHeightForFusion().

◆ hgtRetryTimeMode0_ms

const uint16_t NavEKF3::hgtRetryTimeMode0_ms = 10000
private

Definition at line 430 of file AP_NavEKF3.h.

Referenced by NavEKF3_core::selectHeightForFusion().

◆ hgtRetryTimeMode12_ms

const uint16_t NavEKF3::hgtRetryTimeMode12_ms = 5000
private

Definition at line 431 of file AP_NavEKF3.h.

Referenced by NavEKF3_core::selectHeightForFusion().

◆ imuSampleTime_us

uint64_t NavEKF3::imuSampleTime_us
private

◆ inhibitGpsVertVelUse

bool NavEKF3::inhibitGpsVertVelUse
private

◆ last_function_call

uint32_t NavEKF3::last_function_call

Definition at line 462 of file AP_NavEKF3.h.

◆ last_primary_change

uint32_t NavEKF3::last_primary_change

Definition at line 464 of file AP_NavEKF3.h.

◆ log_baro

bool NavEKF3::log_baro

Definition at line 454 of file AP_NavEKF3.h.

Referenced by NavEKF3_core::readBaroData().

◆ log_compass

bool NavEKF3::log_compass

Definition at line 452 of file AP_NavEKF3.h.

Referenced by NavEKF3_core::readMagData().

◆ log_gps

bool NavEKF3::log_gps

Definition at line 453 of file AP_NavEKF3.h.

Referenced by NavEKF3_core::readGpsData().

◆ log_imu

bool NavEKF3::log_imu

Definition at line 455 of file AP_NavEKF3.h.

Referenced by NavEKF3_core::readDeltaAngle().

◆ logging

struct { ... } NavEKF3::logging

◆ magDelay_ms

const uint16_t NavEKF3::magDelay_ms = 60
private

Definition at line 425 of file AP_NavEKF3.h.

Referenced by NavEKF3_core::readMagData(), and NavEKF3_core::setup_core().

◆ magFailTimeLimit_ms

const uint32_t NavEKF3::magFailTimeLimit_ms = 10000
private

Definition at line 433 of file AP_NavEKF3.h.

Referenced by NavEKF3_core::SelectMagFusion().

◆ magVarRateScale

const float NavEKF3::magVarRateScale = 0.005f
private

Definition at line 434 of file AP_NavEKF3.h.

Referenced by NavEKF3_core::FuseMagnetometer().

◆ num_cores

uint8_t NavEKF3::num_cores
private

◆ pos_down_reset_data

struct { ... } NavEKF3::pos_down_reset_data

◆ pos_reset_data

struct { ... } NavEKF3::pos_reset_data

◆ posRetryTimeNoVel_ms

const uint16_t NavEKF3::posRetryTimeNoVel_ms = 7000
private

Definition at line 429 of file AP_NavEKF3.h.

Referenced by NavEKF3_core::SelectBetaFusion(), and NavEKF3_core::setAidingMode().

◆ posRetryTimeUseVel_ms

const uint16_t NavEKF3::posRetryTimeUseVel_ms = 10000
private

Definition at line 428 of file AP_NavEKF3.h.

Referenced by NavEKF3_core::setAidingMode().

◆ primary

uint8_t NavEKF3::primary
private

◆ runCoreSelection

bool NavEKF3::runCoreSelection
private

Definition at line 482 of file AP_NavEKF3.h.

Referenced by UpdateFilter().

◆ sensorIntervalMin_ms

const uint8_t NavEKF3::sensorIntervalMin_ms = 50
private

◆ tasDelay_ms

const uint16_t NavEKF3::tasDelay_ms = 100
private

Definition at line 426 of file AP_NavEKF3.h.

Referenced by NavEKF3_core::readAirSpdData(), and NavEKF3_core::setup_core().

◆ tasRetryTime_ms

const uint16_t NavEKF3::tasRetryTime_ms = 5000
private

Definition at line 432 of file AP_NavEKF3.h.

Referenced by NavEKF3_core::FuseAirspeed(), and NavEKF3_core::SelectTasFusion().

◆ tiltDriftTimeMax_ms

const uint16_t NavEKF3::tiltDriftTimeMax_ms = 15000
private

Definition at line 427 of file AP_NavEKF3.h.

Referenced by NavEKF3_core::setAidingMode().

◆ var_info

const AP_Param::GroupInfo NavEKF3::var_info
static

Definition at line 44 of file AP_NavEKF3.h.

Referenced by NavEKF3().

◆ yaw_reset_data

struct { ... } NavEKF3::yaw_reset_data

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