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

#include <AP_NavEKF2.h>

Collaboration diagram for NavEKF2:
[legend]

Public Member Functions

 NavEKF2 (const AP_AHRS *ahrs, const RangeFinder &rng)
 
 NavEKF2 (const NavEKF2 &other)=delete
 
NavEKF2operator= (const NavEKF2 &)=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 getGyroScaleErrorPercentage (int8_t instance, Vector3f &gyroScale) 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 getAccelZBias (int8_t instance, float &zbias) 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
 
bool use_compass (void) const
 
void writeOptFlowMeas (uint8_t &rawFlowQuality, Vector2f &rawFlowRates, Vector2f &rawGyroRates, uint32_t &msecFlowMeas, const Vector3f &posOffset)
 
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) 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
 
void writeExtNavData (const Vector3f &sensOffset, const Vector3f &pos, const Quaternion &quat, float posErr, float angErr, uint32_t timeStamp_ms, uint32_t resetTime_ms)
 

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
 
NavEKF2_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 _gpsDelay_ms
 
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 _gyroScaleProcessNoise
 
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_Int8 _magMask
 
AP_Int8 _originHgtMode
 
const float gpsNEVelVarAccScale = 0.05f
 
const float gpsDVelVarAccScale = 0.07f
 
const float gpsPosVarAccScale = 0.05f
 
const uint8_t magDelay_ms = 60
 
const uint8_t tasDelay_ms = 240
 
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 uint16_t magFailTimeLimit_ms = 10000
 
const float magVarRateScale = 0.005f
 
const float gyroBiasNoiseScaler = 2.0f
 
const uint8_t hgtAvg_ms = 100
 
const uint8_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 uint8_t flowIntervalMax_ms = 100
 
const uint16_t gndEffectTimeout_ms = 1000
 
const float gndEffectBaroScaler = 4.0f
 
const uint8_t gndGradientSigma = 50
 
const uint8_t fusionTimeStep_ms = 10
 
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 inhibitGpsVertVelUse
 

Friends

class NavEKF2_core
 

Detailed Description

Definition at line 37 of file AP_NavEKF2.h.

Constructor & Destructor Documentation

◆ NavEKF2() [1/2]

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

Definition at line 558 of file AP_NavEKF2.cpp.

Here is the call graph for this function:

◆ NavEKF2() [2/2]

NavEKF2::NavEKF2 ( const NavEKF2 other)
delete

Member Function Documentation

◆ activeCores()

uint8_t NavEKF2::activeCores ( void  ) const
inline

Definition at line 50 of file AP_NavEKF2.h.

Referenced by DataFlash_Class::Log_Write_POS(), and GCS_MAVLINK::send_ahrs2().

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

◆ check_log_write()

void NavEKF2::check_log_write ( void  )

Definition at line 568 of file AP_NavEKF2.cpp.

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

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

◆ getAccelNED()

void NavEKF2::getAccelNED ( Vector3f accelNED) const

Definition at line 823 of file AP_NavEKF2.cpp.

Referenced by activeCores().

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

◆ getAccelZBias()

void NavEKF2::getAccelZBias ( int8_t  instance,
float &  zbias 
) const

Definition at line 911 of file AP_NavEKF2.cpp.

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

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

◆ getActiveMag()

uint8_t NavEKF2::getActiveMag ( int8_t  instance) const

Definition at line 947 of file AP_NavEKF2.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 NavEKF2::getEkfControlLimits ( float &  ekfGndSpdLimit,
float &  ekfNavVelGainScaler 
) const

Definition at line 903 of file AP_NavEKF2.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 NavEKF2::getEulerAngles ( int8_t  instance,
Vector3f eulers 
) const

Definition at line 1024 of file AP_NavEKF2.cpp.

Referenced by AP_AHRS_NavEKF::get_secondary_attitude(), DataFlash_Class::Log_Write_POS(), GCS_MAVLINK::send_ahrs2(), setInhibitGpsVertVelUse(), and AP_AHRS_NavEKF::update_EKF2().

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

◆ getFilterFaults()

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

Definition at line 1169 of file AP_NavEKF2.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 NavEKF2::getFilterGpsStatus ( int8_t  instance,
nav_gps_status faults 
) const

Definition at line 1216 of file AP_NavEKF2.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 NavEKF2::getFilterStatus ( int8_t  instance,
nav_filter_status status 
) const

Definition at line 1203 of file AP_NavEKF2.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_EKF2().

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

◆ getFilterTimeouts()

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

Definition at line 1190 of file AP_NavEKF2.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 NavEKF2::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 1103 of file AP_NavEKF2.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 NavEKF2::getGyroBias ( int8_t  instance,
Vector3f gyroBias 
) const

Definition at line 831 of file AP_NavEKF2.cpp.

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

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

◆ getGyroScaleErrorPercentage()

void NavEKF2::getGyroScaleErrorPercentage ( int8_t  instance,
Vector3f gyroScale 
) const

Definition at line 840 of file AP_NavEKF2.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:

◆ getHAGL()

bool NavEKF2::getHAGL ( float &  HAGL) const

Definition at line 1015 of file AP_NavEKF2.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 NavEKF2::getHeightControlLimit ( float &  height) const

Definition at line 1237 of file AP_NavEKF2.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 NavEKF2::getInnovations ( int8_t  index,
Vector3f velInnov,
Vector3f posInnov,
Vector3f magInnov,
float &  tasInnov,
float &  yawInnov 
) const

Definition at line 1050 of file AP_NavEKF2.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 NavEKF2::getLastPosDownReset ( float &  posDelta)

Definition at line 1343 of file AP_NavEKF2.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 NavEKF2::getLastPosNorthEastReset ( Vector2f posDelta)

Definition at line 1286 of file AP_NavEKF2.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 NavEKF2::getLastVelNorthEastReset ( Vector2f vel) const

Definition at line 1323 of file AP_NavEKF2.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 NavEKF2::getLastYawResetAngle ( float &  yawAngDelta)

Definition at line 1248 of file AP_NavEKF2.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 NavEKF2::getLLH ( struct Location loc) const

Definition at line 980 of file AP_NavEKF2.cpp.

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

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

◆ getMagNED()

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

Definition at line 929 of file AP_NavEKF2.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 NavEKF2::getMagOffsets ( uint8_t  mag_idx,
Vector3f magOffsets 
) const

Definition at line 959 of file AP_NavEKF2.cpp.

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

Here is the caller graph for this function:

◆ getMagXYZ()

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

Definition at line 938 of file AP_NavEKF2.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 NavEKF2::getOriginLLH ( int8_t  instance,
struct Location loc 
) const

Definition at line 992 of file AP_NavEKF2.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 NavEKF2::getOutputTrackingError ( int8_t  instance,
Vector3f error 
) const

Definition at line 1059 of file AP_NavEKF2.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 NavEKF2::getPosD ( int8_t  instance,
float &  posD 
) const

Definition at line 793 of file AP_NavEKF2.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 NavEKF2::getPosDownDerivative ( int8_t  instance) const

Definition at line 812 of file AP_NavEKF2.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 NavEKF2::getPosNE ( int8_t  instance,
Vector2f posNE 
) const

Definition at line 781 of file AP_NavEKF2.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 NavEKF2::getPrimaryCoreIMUIndex ( void  ) const

Definition at line 770 of file AP_NavEKF2.cpp.

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

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

◆ getPrimaryCoreIndex()

int8_t NavEKF2::getPrimaryCoreIndex ( void  ) const

Definition at line 760 of file AP_NavEKF2.cpp.

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

Here is the caller graph for this function:

◆ getQuaternion()

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

Definition at line 1041 of file AP_NavEKF2.cpp.

Referenced by AP_AHRS_NavEKF::get_secondary_quaternion(), 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 NavEKF2::getRangeBeaconDebug ( int8_t  instance,
uint8_t &  ID,
float &  rng,
float &  innov,
float &  innovVar,
float &  testRatio,
Vector3f beaconPosNED,
float &  offsetHigh,
float &  offsetLow 
) const

Definition at line 1113 of file AP_NavEKF2.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 NavEKF2::getRotationBodyToNED ( Matrix3f mat) const

Definition at line 1033 of file AP_NavEKF2.cpp.

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

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

◆ getTiltError()

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

Definition at line 849 of file AP_NavEKF2.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 NavEKF2::getTimingStatistics ( int8_t  instance,
struct ekf_timing timing 
) const

Definition at line 1459 of file AP_NavEKF2.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 NavEKF2::getVariances ( int8_t  instance,
float &  velVar,
float &  posVar,
float &  hgtVar,
Vector3f magVar,
float &  tasVar,
Vector2f offset 
) const

Definition at line 1068 of file AP_NavEKF2.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 NavEKF2::getVelNED ( int8_t  instance,
Vector3f vel 
) const

Definition at line 803 of file AP_NavEKF2.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 NavEKF2::getWind ( int8_t  instance,
Vector3f wind 
) const

Definition at line 920 of file AP_NavEKF2.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 NavEKF2::have_ekf_logging ( void  ) const
inline

Definition at line 321 of file AP_NavEKF2.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 NavEKF2::healthy ( void  ) const

Definition at line 750 of file AP_NavEKF2.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 NavEKF2::InitialiseFilter ( void  )

Definition at line 596 of file AP_NavEKF2.cpp.

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

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

◆ operator=()

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

◆ prearm_failure_reason()

const char * NavEKF2::prearm_failure_reason ( void  ) const

Definition at line 1332 of file AP_NavEKF2.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 NavEKF2::resetGyroBias ( void  )

Definition at line 858 of file AP_NavEKF2.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 NavEKF2::resetHeightDatum ( void  )

Definition at line 872 of file AP_NavEKF2.cpp.

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

Here is the caller graph for this function:

◆ send_status_report()

void NavEKF2::send_status_report ( mavlink_channel_t  chan)

Definition at line 1227 of file AP_NavEKF2.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 NavEKF2::set_baro_alt_noise ( float  noise)
inline

Definition at line 315 of file AP_NavEKF2.h.

◆ set_enable()

void NavEKF2::set_enable ( bool  enable)
inline

Definition at line 318 of file AP_NavEKF2.h.

◆ setInhibitGPS()

uint8_t NavEKF2::setInhibitGPS ( void  )

Definition at line 893 of file AP_NavEKF2.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 NavEKF2::setInhibitGpsVertVelUse ( const bool  varIn)
inline

Definition at line 131 of file AP_NavEKF2.h.

Here is the call graph for this function:

◆ setOriginLLH()

bool NavEKF2::setOriginLLH ( const Location loc)

Definition at line 1005 of file AP_NavEKF2.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 NavEKF2::setTakeoffExpected ( bool  val)

Definition at line 1125 of file AP_NavEKF2.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 NavEKF2::setTerrainHgtStable ( bool  val)

Definition at line 1148 of file AP_NavEKF2.cpp.

Referenced by setInhibitGpsVertVelUse().

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

◆ setTouchdownExpected()

void NavEKF2::setTouchdownExpected ( bool  val)

Definition at line 1136 of file AP_NavEKF2.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 NavEKF2::UpdateFilter ( void  )

Definition at line 682 of file AP_NavEKF2.cpp.

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

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

◆ updateLaneSwitchPosDownResetData()

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

Definition at line 1432 of file AP_NavEKF2.cpp.

Referenced by UpdateFilter().

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

◆ updateLaneSwitchPosResetData()

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

Definition at line 1405 of file AP_NavEKF2.cpp.

Referenced by UpdateFilter().

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

◆ updateLaneSwitchYawResetData()

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

Definition at line 1379 of file AP_NavEKF2.cpp.

Referenced by UpdateFilter().

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

◆ use_compass()

bool NavEKF2::use_compass ( void  ) const

Definition at line 1078 of file AP_NavEKF2.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:

◆ writeExtNavData()

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

Definition at line 1482 of file AP_NavEKF2.cpp.

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

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

◆ writeOptFlowMeas()

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

Definition at line 1093 of file AP_NavEKF2.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:

Friends And Related Function Documentation

◆ NavEKF2_core

friend class NavEKF2_core
friend

Definition at line 38 of file AP_NavEKF2.h.

Referenced by InitialiseFilter().

Member Data Documentation

◆ _accelBiasProcessNoise

AP_Float NavEKF2::_accelBiasProcessNoise
private

Definition at line 364 of file AP_NavEKF2.h.

Referenced by NavEKF2_core::CovariancePrediction().

◆ _accNoise

AP_Float NavEKF2::_accNoise
private

Definition at line 362 of file AP_NavEKF2.h.

Referenced by NavEKF2_core::CovariancePrediction().

◆ _ahrs

const AP_AHRS* NavEKF2::_ahrs
private

Definition at line 343 of file AP_NavEKF2.h.

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

◆ _altSource

AP_Int8 NavEKF2::_altSource
private

◆ _baroAltNoise

AP_Float NavEKF2::_baroAltNoise
private

◆ _easNoise

AP_Float NavEKF2::_easNoise
private

◆ _enable

AP_Int8 NavEKF2::_enable
private

Definition at line 350 of file AP_NavEKF2.h.

Referenced by InitialiseFilter(), and set_enable().

◆ _flowDelay_ms

AP_Int8 NavEKF2::_flowDelay_ms
private

Definition at line 377 of file AP_NavEKF2.h.

Referenced by NavEKF2_core::writeOptFlowMeas().

◆ _flowInnovGate

AP_Int16 NavEKF2::_flowInnovGate
private

Definition at line 376 of file AP_NavEKF2.h.

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

◆ _flowNoise

AP_Float NavEKF2::_flowNoise
private

Definition at line 375 of file AP_NavEKF2.h.

Referenced by NavEKF2_core::SelectFlowFusion().

◆ _framesPerPrediction

uint8_t NavEKF2::_framesPerPrediction
private

Definition at line 347 of file AP_NavEKF2.h.

Referenced by InitialiseFilter(), and UpdateFilter().

◆ _frameTimeUsec

uint32_t NavEKF2::_frameTimeUsec
private

Definition at line 346 of file AP_NavEKF2.h.

Referenced by InitialiseFilter(), and UpdateFilter().

◆ _fusionModeGPS

AP_Int8 NavEKF2::_fusionModeGPS
private

◆ _gpsCheck

AP_Int8 NavEKF2::_gpsCheck
private

Definition at line 383 of file AP_NavEKF2.h.

Referenced by NavEKF2_core::calcGpsGoodToAlign().

◆ _gpsCheckScaler

AP_Int16 NavEKF2::_gpsCheckScaler
private

Definition at line 385 of file AP_NavEKF2.h.

Referenced by NavEKF2_core::calcGpsGoodToAlign().

◆ _gpsDelay_ms

AP_Int16 NavEKF2::_gpsDelay_ms
private

Definition at line 365 of file AP_NavEKF2.h.

Referenced by NavEKF2_core::readGpsData().

◆ _gpsGlitchRadiusMax

AP_Int8 NavEKF2::_gpsGlitchRadiusMax
private

Definition at line 374 of file AP_NavEKF2.h.

Referenced by NavEKF2_core::FuseVelPosNED().

◆ _gpsHorizPosNoise

AP_Float NavEKF2::_gpsHorizPosNoise
private

◆ _gpsHorizVelNoise

AP_Float NavEKF2::_gpsHorizVelNoise
private

◆ _gpsPosInnovGate

AP_Int16 NavEKF2::_gpsPosInnovGate
private

Definition at line 369 of file AP_NavEKF2.h.

Referenced by NavEKF2_core::FuseVelPosNED().

◆ _gpsVelInnovGate

AP_Int16 NavEKF2::_gpsVelInnovGate
private

Definition at line 368 of file AP_NavEKF2.h.

Referenced by NavEKF2_core::FuseVelPosNED().

◆ _gpsVertVelNoise

AP_Float NavEKF2::_gpsVertVelNoise
private

◆ _gyrNoise

AP_Float NavEKF2::_gyrNoise
private

Definition at line 361 of file AP_NavEKF2.h.

Referenced by NavEKF2_core::CovariancePrediction().

◆ _gyroBiasProcessNoise

AP_Float NavEKF2::_gyroBiasProcessNoise
private

Definition at line 363 of file AP_NavEKF2.h.

Referenced by NavEKF2_core::CovariancePrediction().

◆ _gyroScaleProcessNoise

AP_Float NavEKF2::_gyroScaleProcessNoise
private

Definition at line 381 of file AP_NavEKF2.h.

Referenced by NavEKF2_core::CovariancePrediction().

◆ _hgtDelay_ms

AP_Int16 NavEKF2::_hgtDelay_ms
private

Definition at line 366 of file AP_NavEKF2.h.

Referenced by NavEKF2_core::readBaroData().

◆ _hgtInnovGate

AP_Int16 NavEKF2::_hgtInnovGate
private

Definition at line 370 of file AP_NavEKF2.h.

Referenced by NavEKF2_core::FuseVelPosNED().

◆ _imuMask

AP_Int8 NavEKF2::_imuMask
private

Definition at line 384 of file AP_NavEKF2.h.

Referenced by InitialiseFilter().

◆ _logging_mask

AP_Int8 NavEKF2::_logging_mask
private

Definition at line 387 of file AP_NavEKF2.h.

Referenced by check_log_write(), and have_ekf_logging().

◆ _magBodyProcessNoise

AP_Float NavEKF2::_magBodyProcessNoise
private

Definition at line 360 of file AP_NavEKF2.h.

Referenced by NavEKF2_core::CovariancePrediction().

◆ _magCal

AP_Int8 NavEKF2::_magCal
private

Definition at line 373 of file AP_NavEKF2.h.

Referenced by NavEKF2_core::effective_magCal().

◆ _magEarthProcessNoise

AP_Float NavEKF2::_magEarthProcessNoise
private

Definition at line 359 of file AP_NavEKF2.h.

Referenced by NavEKF2_core::CovariancePrediction().

◆ _magInnovGate

AP_Int16 NavEKF2::_magInnovGate
private

Definition at line 371 of file AP_NavEKF2.h.

Referenced by NavEKF2_core::FuseMagnetometer().

◆ _magMask

AP_Int8 NavEKF2::_magMask
private

Definition at line 397 of file AP_NavEKF2.h.

Referenced by NavEKF2_core::effective_magCal().

◆ _magNoise

AP_Float NavEKF2::_magNoise
private

◆ _maxFlowRate

AP_Float NavEKF2::_maxFlowRate
private

◆ _noaidHorizNoise

AP_Float NavEKF2::_noaidHorizNoise
private

Definition at line 386 of file AP_NavEKF2.h.

Referenced by NavEKF2_core::FuseVelPosNED().

◆ _originHgtMode

AP_Int8 NavEKF2::_originHgtMode
private

◆ _rng

const RangeFinder& NavEKF2::_rng
private

◆ _rngBcnDelay_ms

AP_Int8 NavEKF2::_rngBcnDelay_ms
private

Definition at line 395 of file AP_NavEKF2.h.

Referenced by NavEKF2_core::readRngBcnData().

◆ _rngBcnInnovGate

AP_Int16 NavEKF2::_rngBcnInnovGate
private

Definition at line 394 of file AP_NavEKF2.h.

Referenced by NavEKF2_core::FuseRngBcn().

◆ _rngBcnNoise

AP_Float NavEKF2::_rngBcnNoise
private

Definition at line 393 of file AP_NavEKF2.h.

Referenced by NavEKF2_core::readRngBcnData().

◆ _rngInnovGate

AP_Int16 NavEKF2::_rngInnovGate
private

Definition at line 378 of file AP_NavEKF2.h.

Referenced by NavEKF2_core::EstimateTerrainOffset().

◆ _rngNoise

AP_Float NavEKF2::_rngNoise
private

◆ _tasInnovGate

AP_Int16 NavEKF2::_tasInnovGate
private

Definition at line 372 of file AP_NavEKF2.h.

Referenced by NavEKF2_core::FuseAirspeed().

◆ _tauVelPosOutput

AP_Int8 NavEKF2::_tauVelPosOutput
private

Definition at line 390 of file AP_NavEKF2.h.

Referenced by NavEKF2_core::calcOutputStates().

◆ _terrGradMax

AP_Float NavEKF2::_terrGradMax
private

Definition at line 392 of file AP_NavEKF2.h.

Referenced by NavEKF2_core::selectHeightForFusion().

◆ _useRngSwHgt

AP_Int8 NavEKF2::_useRngSwHgt
private

◆ _useRngSwSpd

AP_Float NavEKF2::_useRngSwSpd
private

Definition at line 396 of file AP_NavEKF2.h.

Referenced by NavEKF2_core::selectHeightForFusion().

◆ _windVelProcessNoise

AP_Float NavEKF2::_windVelProcessNoise
private

Definition at line 357 of file AP_NavEKF2.h.

Referenced by NavEKF2_core::CovariancePrediction().

◆ _wndVarHgtRateScale

AP_Float NavEKF2::_wndVarHgtRateScale
private

Definition at line 358 of file AP_NavEKF2.h.

Referenced by NavEKF2_core::CovariancePrediction().

◆ _yawInnovGate

AP_Int16 NavEKF2::_yawInnovGate
private

Definition at line 389 of file AP_NavEKF2.h.

Referenced by NavEKF2_core::fuseEulerYaw().

◆ _yawNoise

AP_Float NavEKF2::_yawNoise
private

Definition at line 388 of file AP_NavEKF2.h.

Referenced by NavEKF2_core::fuseEulerYaw().

◆ betaAvg_ms

const uint8_t NavEKF2::betaAvg_ms = 100
private

Definition at line 416 of file AP_NavEKF2.h.

Referenced by NavEKF2_core::SelectBetaFusion().

◆ core

NavEKF2_core* NavEKF2::core = nullptr
private

◆ core_changed

bool NavEKF2::core_changed

Definition at line 441 of file AP_NavEKF2.h.

◆ core_delta [1/2]

float NavEKF2::core_delta

Definition at line 443 of file AP_NavEKF2.h.

◆ core_delta [2/2]

Vector2f NavEKF2::core_delta

Definition at line 450 of file AP_NavEKF2.h.

◆ covDelAngMax

const float NavEKF2::covDelAngMax = 0.05f
private

Definition at line 418 of file AP_NavEKF2.h.

◆ covTimeStepMax

const float NavEKF2::covTimeStepMax = 0.1f
private

Definition at line 417 of file AP_NavEKF2.h.

◆ DCM33FlowMin

const float NavEKF2::DCM33FlowMin = 0.71f
private

Definition at line 419 of file AP_NavEKF2.h.

Referenced by NavEKF2_core::SelectFlowFusion().

◆ enabled

bool NavEKF2::enabled

Definition at line 429 of file AP_NavEKF2.h.

◆ flowIntervalMax_ms

const uint8_t NavEKF2::flowIntervalMax_ms = 100
private

Definition at line 422 of file AP_NavEKF2.h.

◆ flowTimeDeltaAvg_ms

const uint8_t NavEKF2::flowTimeDeltaAvg_ms = 100
private

Definition at line 421 of file AP_NavEKF2.h.

Referenced by NavEKF2_core::writeOptFlowMeas().

◆ fScaleFactorPnoise

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

Definition at line 420 of file AP_NavEKF2.h.

◆ fusionTimeStep_ms

const uint8_t NavEKF2::fusionTimeStep_ms = 10
private

Definition at line 426 of file AP_NavEKF2.h.

◆ gndEffectBaroScaler

const float NavEKF2::gndEffectBaroScaler = 4.0f
private

Definition at line 424 of file AP_NavEKF2.h.

Referenced by NavEKF2_core::selectHeightForFusion().

◆ gndEffectTimeout_ms

const uint16_t NavEKF2::gndEffectTimeout_ms = 1000
private

◆ gndGradientSigma

const uint8_t NavEKF2::gndGradientSigma = 50
private

Definition at line 425 of file AP_NavEKF2.h.

Referenced by NavEKF2_core::EstimateTerrainOffset().

◆ gpsDVelVarAccScale

const float NavEKF2::gpsDVelVarAccScale = 0.07f
private

Definition at line 402 of file AP_NavEKF2.h.

Referenced by NavEKF2_core::FuseVelPosNED().

◆ gpsNEVelVarAccScale

const float NavEKF2::gpsNEVelVarAccScale = 0.05f
private

Definition at line 401 of file AP_NavEKF2.h.

Referenced by NavEKF2_core::FuseVelPosNED().

◆ gpsPosVarAccScale

const float NavEKF2::gpsPosVarAccScale = 0.05f
private

Definition at line 403 of file AP_NavEKF2.h.

Referenced by NavEKF2_core::FuseVelPosNED().

◆ gyroBiasNoiseScaler

const float NavEKF2::gyroBiasNoiseScaler = 2.0f
private

Definition at line 414 of file AP_NavEKF2.h.

◆ hgtAvg_ms

const uint8_t NavEKF2::hgtAvg_ms = 100
private

Definition at line 415 of file AP_NavEKF2.h.

Referenced by NavEKF2_core::selectHeightForFusion().

◆ hgtRetryTimeMode0_ms

const uint16_t NavEKF2::hgtRetryTimeMode0_ms = 10000
private

Definition at line 409 of file AP_NavEKF2.h.

Referenced by NavEKF2_core::selectHeightForFusion().

◆ hgtRetryTimeMode12_ms

const uint16_t NavEKF2::hgtRetryTimeMode12_ms = 5000
private

Definition at line 410 of file AP_NavEKF2.h.

Referenced by NavEKF2_core::selectHeightForFusion().

◆ imuSampleTime_us

uint64_t NavEKF2::imuSampleTime_us
private

◆ inhibitGpsVertVelUse

bool NavEKF2::inhibitGpsVertVelUse
private

◆ last_function_call

uint32_t NavEKF2::last_function_call

Definition at line 440 of file AP_NavEKF2.h.

◆ last_primary_change

uint32_t NavEKF2::last_primary_change

Definition at line 442 of file AP_NavEKF2.h.

◆ log_baro

bool NavEKF2::log_baro

Definition at line 432 of file AP_NavEKF2.h.

Referenced by NavEKF2_core::readBaroData().

◆ log_compass

bool NavEKF2::log_compass

Definition at line 430 of file AP_NavEKF2.h.

Referenced by NavEKF2_core::readMagData().

◆ log_gps

bool NavEKF2::log_gps

Definition at line 431 of file AP_NavEKF2.h.

Referenced by NavEKF2_core::readGpsData().

◆ log_imu

bool NavEKF2::log_imu

Definition at line 433 of file AP_NavEKF2.h.

Referenced by NavEKF2_core::readDeltaAngle().

◆ logging

struct { ... } NavEKF2::logging

◆ magDelay_ms

const uint8_t NavEKF2::magDelay_ms = 60
private

Definition at line 404 of file AP_NavEKF2.h.

Referenced by NavEKF2_core::readMagData().

◆ magFailTimeLimit_ms

const uint16_t NavEKF2::magFailTimeLimit_ms = 10000
private

Definition at line 412 of file AP_NavEKF2.h.

Referenced by NavEKF2_core::SelectMagFusion().

◆ magVarRateScale

const float NavEKF2::magVarRateScale = 0.005f
private

Definition at line 413 of file AP_NavEKF2.h.

Referenced by NavEKF2_core::FuseMagnetometer().

◆ num_cores

uint8_t NavEKF2::num_cores
private

◆ pos_down_reset_data

struct { ... } NavEKF2::pos_down_reset_data

◆ pos_reset_data

struct { ... } NavEKF2::pos_reset_data

◆ posRetryTimeNoVel_ms

const uint16_t NavEKF2::posRetryTimeNoVel_ms = 7000
private

Definition at line 408 of file AP_NavEKF2.h.

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

◆ posRetryTimeUseVel_ms

const uint16_t NavEKF2::posRetryTimeUseVel_ms = 10000
private

Definition at line 407 of file AP_NavEKF2.h.

Referenced by NavEKF2_core::setAidingMode().

◆ primary

uint8_t NavEKF2::primary
private

◆ runCoreSelection

bool NavEKF2::runCoreSelection
private

Definition at line 460 of file AP_NavEKF2.h.

Referenced by UpdateFilter().

◆ tasDelay_ms

const uint8_t NavEKF2::tasDelay_ms = 240
private

Definition at line 405 of file AP_NavEKF2.h.

Referenced by NavEKF2_core::readAirSpdData().

◆ tasRetryTime_ms

const uint16_t NavEKF2::tasRetryTime_ms = 5000
private

Definition at line 411 of file AP_NavEKF2.h.

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

◆ tiltDriftTimeMax_ms

const uint16_t NavEKF2::tiltDriftTimeMax_ms = 15000
private

Definition at line 406 of file AP_NavEKF2.h.

Referenced by NavEKF2_core::setAidingMode().

◆ var_info

const AP_Param::GroupInfo NavEKF2::var_info
static

Definition at line 47 of file AP_NavEKF2.h.

Referenced by NavEKF2().

◆ yaw_reset_data

struct { ... } NavEKF2::yaw_reset_data

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