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

#include <AP_NavEKF3_core.h>

Collaboration diagram for NavEKF3_core:
[legend]

Classes

struct  baro_elements
 
struct  gps_elements
 
struct  imu_elements
 
struct  mag_elements
 
struct  of_elements
 
struct  output_elements
 
struct  range_elements
 
struct  rng_bcn_elements
 
struct  state_elements
 
struct  tas_elements
 
struct  vel_odm_elements
 
struct  wheel_odm_elements
 

Public Member Functions

 NavEKF3_core (void)
 
bool setup_core (NavEKF3 *_frontend, uint8_t _imu_index, uint8_t _core_index)
 
bool InitialiseFilterBootstrap (void)
 
void UpdateFilter (bool predict)
 
bool healthy (void) const
 
float errorScore (void) const
 
bool getPosNE (Vector2f &posNE) const
 
bool getPosD (float &posD) const
 
void getVelNED (Vector3f &vel) const
 
float getPosDownDerivative (void) const
 
void getAccelNED (Vector3f &accelNED) const
 
void getGyroBias (Vector3f &gyroBias) const
 
void getAccelBias (Vector3f &accelBias) const
 
void getTiltError (float &ang) const
 
void resetGyroBias (void)
 
bool resetHeightDatum (void)
 
uint8_t setInhibitGPS (void)
 
void getEkfControlLimits (float &ekfGndSpdLimit, float &ekfNavVelGainScaler) const
 
void getWind (Vector3f &wind) const
 
void getMagNED (Vector3f &magNED) const
 
void getMagXYZ (Vector3f &magXYZ) const
 
uint8_t getActiveMag () const
 
bool getMagOffsets (uint8_t mag_idx, Vector3f &magOffsets) const
 
bool getLLH (struct Location &loc) const
 
bool getOriginLLH (struct Location &loc) const
 
bool setOriginLLH (const Location &loc)
 
bool getHAGL (float &HAGL) const
 
void getEulerAngles (Vector3f &eulers) const
 
void getRotationBodyToNED (Matrix3f &mat) const
 
void getQuaternion (Quaternion &quat) const
 
void getInnovations (Vector3f &velInnov, Vector3f &posInnov, Vector3f &magInnov, float &tasInnov, float &yawInnov) const
 
void getVariances (float &velVar, float &posVar, float &hgtVar, Vector3f &magVar, float &tasVar, Vector2f &offset) const
 
void getStateVariances (float stateVar[24])
 
bool use_compass (void) const
 
void writeOptFlowMeas (uint8_t &rawFlowQuality, Vector2f &rawFlowRates, Vector2f &rawGyroRates, uint32_t &msecFlowMeas, const Vector3f &posOffset)
 
void getFlowDebug (float &varFlow, float &gndOffset, float &flowInnovX, float &flowInnovY, float &auxInnov, float &HAGL, float &rngInnov, float &range, float &gndOffsetErr) const
 
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 (Vector3f &velInnov, Vector3f &velInnovVar)
 
bool getRangeBeaconDebug (uint8_t &ID, float &rng, float &innov, float &innovVar, float &testRatio, Vector3f &beaconPosNED, float &offsetHigh, float &offsetLow, Vector3f &posNED)
 
void setTakeoffExpected (bool val)
 
void setTouchdownExpected (bool val)
 
void setTerrainHgtStable (bool val)
 
void getFilterFaults (uint16_t &faults) const
 
void getFilterTimeouts (uint8_t &timeouts) const
 
void getFilterGpsStatus (nav_gps_status &status) const
 
void getFilterStatus (nav_filter_status &status) const
 
void send_status_report (mavlink_channel_t chan)
 
bool getHeightControlLimit (float &height) const
 
uint32_t getLastYawResetAngle (float &yawAng) const
 
uint32_t getLastPosNorthEastReset (Vector2f &pos) const
 
uint32_t getLastPosDownReset (float &posD) const
 
uint32_t getLastVelNorthEastReset (Vector2f &vel) const
 
const char * prearm_failure_reason (void) const
 
uint8_t getFramesSincePredict (void) const
 
void getOutputTrackingError (Vector3f &error) const
 
uint8_t getIMUIndex (void) const
 
void getTimingStatistics (struct ekf_timing &timing)
 

Private Types

enum  resetDataSource {
  DEFAULT =0, GPS =1, RNGBCN =2, FLOW =3,
  BARO =4, MAG =5, RNGFND =6
}
 
enum  AidingMode { AID_ABSOLUTE =0, AID_NONE =1, AID_RELATIVE =2 }
 
typedef float ftype
 
typedef ftype Vector2[2]
 
typedef ftype Vector3[3]
 
typedef ftype Vector4[4]
 
typedef ftype Vector5[5]
 
typedef ftype Vector6[6]
 
typedef ftype Vector7[7]
 
typedef ftype Vector8[8]
 
typedef ftype Vector9[9]
 
typedef ftype Vector10[10]
 
typedef ftype Vector11[11]
 
typedef ftype Vector13[13]
 
typedef ftype Vector14[14]
 
typedef ftype Vector15[15]
 
typedef ftype Vector21[21]
 
typedef ftype Vector22[22]
 
typedef ftype Vector23[23]
 
typedef ftype Vector24[24]
 
typedef ftype Vector25[25]
 
typedef ftype Vector28[28]
 
typedef ftype Matrix3[3][3]
 
typedef ftype Matrix24[24][24]
 
typedef ftype Matrix34_50[34][50]
 
typedef uint32_t Vector_u32_50[50]
 

Private Member Functions

void updateFilterStatus (void)
 
void UpdateStrapdownEquationsNED ()
 
void CovariancePrediction ()
 
void ForceSymmetry ()
 
void ConstrainVariances ()
 
void ConstrainStates ()
 
void FuseVelPosNED ()
 
void FuseBodyVel ()
 
void FuseRngBcn ()
 
void FuseRngBcnStatic ()
 
void CalcRangeBeaconPosDownOffset (float obsVar, Vector3f &vehiclePosNED, bool aligning)
 
void FuseMagnetometer ()
 
void FuseAirspeed ()
 
void FuseSideslip ()
 
void zeroRows (Matrix24 &covMat, uint8_t first, uint8_t last)
 
void zeroCols (Matrix24 &covMat, uint8_t first, uint8_t last)
 
void StoreOutputReset (void)
 
void StoreQuatReset (void)
 
void StoreQuatRotate (Quaternion deltaQuat)
 
void StoreBaro ()
 
bool RecallBaro ()
 
void StoreRange ()
 
bool RecallRange ()
 
void StoreMag ()
 
bool RecallMag ()
 
void StoreTAS ()
 
bool RecallTAS ()
 
void StoreOF ()
 
bool RecallOF ()
 
void quat2Tbn (Matrix3f &Tbn, const Quaternion &quat) const
 
void calcEarthRateNED (Vector3f &omega, int32_t latitude) const
 
void CovarianceInit ()
 
bool readDeltaVelocity (uint8_t ins_index, Vector3f &dVel, float &dVel_dt)
 
bool readDeltaAngle (uint8_t ins_index, Vector3f &dAng)
 
void correctDeltaAngle (Vector3f &delAng, float delAngDT)
 
void correctDeltaVelocity (Vector3f &delVel, float delVelDT)
 
void readIMUData ()
 
void readGpsData ()
 
void readBaroData ()
 
void readMagData ()
 
void readAirSpdData ()
 
void readRngBcnData ()
 
void SelectVelPosFusion ()
 
void SelectRngBcnFusion ()
 
void SelectMagFusion ()
 
void SelectTasFusion ()
 
void SelectBetaFusion ()
 
void realignYawGPS ()
 
Quaternion calcQuatAndFieldStates (float roll, float pitch)
 
void InitialiseVariables ()
 
void ResetPosition (void)
 
void ResetVelocity (void)
 
void ResetHeight (void)
 
bool useAirspeed (void) const
 
bool readyToUseGPS (void) const
 
bool readyToUseRangeBeacon (void) const
 
void checkDivergence (void)
 
void calcIMU_Weighting (float K1, float K2)
 
bool readyToUseOptFlow (void) const
 
bool readyToUseBodyOdm (void) const
 
bool useRngFinder (void) const
 
void SelectFlowFusion ()
 
void SelectBodyOdomFusion ()
 
void EstimateTerrainOffset ()
 
void FuseOptFlow ()
 
void controlFilterModes ()
 
void detectFlight ()
 
void setAidingMode ()
 
void setWindMagStateLearningMode ()
 
void checkAttitudeAlignmentStatus ()
 
void controlMagYawReset ()
 
void setOrigin ()
 
bool getTakeoffExpected ()
 
bool getTouchdownExpected ()
 
bool calcGpsGoodToAlign (void)
 
void checkGyroCalStatus (void)
 
void calcGpsGoodForFlight (void)
 
void readRangeFinder ()
 
void detectOptFlowTakeoff (void)
 
void alignMagStateDeclination ()
 
void fuseEulerYaw ()
 
void FuseDeclination (float declErr)
 
void calcOutputStates ()
 
void calcFiltBaroOffset ()
 
void correctEkfOriginHeight ()
 
void selectHeightForFusion ()
 
void zeroAttCovOnly ()
 
void recordYawReset ()
 
void recordMagReset ()
 
uint8_t effective_magCal (void) const
 
Vector3f calcRotVecVariances (void)
 
void initialiseQuatCovariances (Vector3f &rotVarVec)
 
void updateTimingStatistics (void)
 
void updateStateIndexLim (void)
 
bool assume_zero_sideslip (void) const
 
float InitialGyroBiasUncertainty (void) const
 

Private Attributes

NavEKF3frontend
 
uint8_t imu_index
 
uint8_t core_index
 
uint8_t imu_buffer_length
 
uint8_t obs_buffer_length
 
const AP_AHRS_ahrs
 
Vector24 statesArray
 
struct NavEKF3_core::state_elementsstateStruct
 
bool statesInitialised
 
bool velHealth
 
bool posHealth
 
bool hgtHealth
 
bool magHealth
 
bool tasHealth
 
bool velTimeout
 
bool posTimeout
 
bool hgtTimeout
 
bool magTimeout
 
bool tasTimeout
 
bool badMagYaw
 
bool badIMUdata
 
float gpsNoiseScaler
 
Vector28 Kfusion
 
Matrix24 KH
 
Matrix24 KHP
 
Matrix24 P
 
imu_ring_buffer_t< imu_elementsstoredIMU
 
obs_ring_buffer_t< gps_elementsstoredGPS
 
obs_ring_buffer_t< mag_elementsstoredMag
 
obs_ring_buffer_t< baro_elementsstoredBaro
 
obs_ring_buffer_t< tas_elementsstoredTAS
 
obs_ring_buffer_t< range_elementsstoredRange
 
imu_ring_buffer_t< output_elementsstoredOutput
 
Matrix3f prevTnb
 
ftype accNavMag
 
ftype accNavMagHoriz
 
Vector3f earthRateNED
 
ftype dtIMUavg
 
ftype dtEkfAvg
 
ftype dt
 
ftype hgtRate
 
bool onGround
 
bool prevOnGround
 
bool inFlight
 
bool prevInFlight
 
bool manoeuvring
 
uint32_t airborneDetectTime_ms
 
Vector6 innovVelPos
 
Vector6 varInnovVelPos
 
bool fuseVelData
 
bool fusePosData
 
bool fuseHgtData
 
Vector3f innovMag
 
Vector3f varInnovMag
 
ftype innovVtas
 
ftype varInnovVtas
 
bool magFusePerformed
 
bool magFuseRequired
 
uint32_t prevTasStep_ms
 
uint32_t prevBetaStep_ms
 
uint32_t lastMagUpdate_us
 
Vector3f velDotNED
 
Vector3f velDotNEDfilt
 
uint32_t imuSampleTime_ms
 
bool tasDataToFuse
 
uint32_t lastBaroReceived_ms
 
uint16_t hgtRetryTime_ms
 
uint32_t lastVelPassTime_ms
 
uint32_t lastPosPassTime_ms
 
uint32_t lastHgtPassTime_ms
 
uint32_t lastTasPassTime_ms
 
uint32_t lastTimeGpsReceived_ms
 
uint32_t timeAtLastAuxEKF_ms
 
uint32_t secondLastGpsTime_ms
 
uint32_t lastHealthyMagTime_ms
 
bool allMagSensorsFailed
 
uint32_t lastSynthYawTime_ms
 
uint32_t ekfStartTime_ms
 
Matrix24 nextP
 
Vector2f lastKnownPositionNE
 
uint32_t lastDecayTime_ms
 
float velTestRatio
 
float posTestRatio
 
float hgtTestRatio
 
Vector3f magTestRatio
 
float tasTestRatio
 
bool inhibitWindStates
 
bool inhibitMagStates
 
bool inhibitDelVelBiasStates
 
bool inhibitDelAngBiasStates
 
bool gpsNotAvailable
 
struct Location EKF_origin
 
bool validOrigin
 
float gpsSpdAccuracy
 
float gpsPosAccuracy
 
float gpsHgtAccuracy
 
uint32_t lastGpsVelFail_ms
 
uint32_t lastGpsAidBadTime_ms
 
float posDownAtTakeoff
 
bool useGpsVertVel
 
float yawResetAngle
 
uint32_t lastYawReset_ms
 
bool tiltAlignComplete
 
bool yawAlignComplete
 
bool magStateInitComplete
 
uint8_t stateIndexLim
 
imu_elements imuDataDelayed
 
imu_elements imuDataNew
 
imu_elements imuDataDownSampledNew
 
Quaternion imuQuatDownSampleNew
 
uint8_t fifoIndexNow
 
uint8_t fifoIndexDelayed
 
baro_elements baroDataNew
 
baro_elements baroDataDelayed
 
uint8_t baroStoreIndex
 
range_elements rangeDataNew
 
range_elements rangeDataDelayed
 
uint8_t rangeStoreIndex
 
tas_elements tasDataNew
 
tas_elements tasDataDelayed
 
uint8_t tasStoreIndex
 
mag_elements magDataNew
 
mag_elements magDataDelayed
 
uint8_t magStoreIndex
 
gps_elements gpsDataNew
 
gps_elements gpsDataDelayed
 
uint8_t last_gps_idx
 
output_elements outputDataNew
 
output_elements outputDataDelayed
 
Vector3f delAngCorrection
 
Vector3f velErrintegral
 
Vector3f posErrintegral
 
float innovYaw
 
uint32_t timeTasReceived_ms
 
bool gpsGoodToAlign
 
uint32_t magYawResetTimer_ms
 
bool consistentMagData
 
bool motorsArmed
 
bool prevMotorsArmed
 
bool posVelFusionDelayed
 
bool optFlowFusionDelayed
 
bool airSpdFusionDelayed
 
bool sideSlipFusionDelayed
 
Vector3f lastMagOffsets
 
bool lastMagOffsetsValid
 
Vector2f posResetNE
 
uint32_t lastPosReset_ms
 
Vector2f velResetNE
 
uint32_t lastVelReset_ms
 
float posResetD
 
uint32_t lastPosResetD_ms
 
float yawTestRatio
 
Quaternion prevQuatMagReset
 
uint8_t fusionHorizonOffset
 
float hgtInnovFiltState
 
uint8_t magSelectIndex
 
bool runUpdates
 
uint32_t framesSincePredict
 
bool startPredictEnabled
 
uint8_t localFilterTimeStep_ms
 
float posDownObsNoise
 
Vector3f delAngCorrected
 
Vector3f delVelCorrected
 
bool magFieldLearned
 
Vector3f earthMagFieldVar
 
Vector3f bodyMagFieldVar
 
bool delAngBiasLearned
 
nav_filter_status filterStatus
 
float ekfOriginHgtVar
 
double ekfGpsRefHgt
 
uint32_t lastOriginHgtTime_ms
 
Vector3f outputTrackError
 
Vector3f velOffsetNED
 
Vector3f posOffsetNED
 
uint32_t firstInitTime_ms
 
uint32_t lastInitFailReport_ms
 
resetDataSource posResetSource
 
resetDataSource velResetSource
 
float posDownDerivative
 
float posDown
 
struct Location gpsloc_prev
 
uint32_t lastPreAlignGpsCheckTime_ms
 
float gpsDriftNE
 
float gpsVertVelFilt
 
float gpsHorizVelFilt
 
bool gpsSpdAccPass
 
bool ekfInnovationsPass
 
float sAccFilterState1
 
float sAccFilterState2
 
uint32_t lastGpsCheckTime_ms
 
uint32_t lastInnovPassTime_ms
 
uint32_t lastInnovFailTime_ms
 
bool gpsAccuracyGood
 
float innovationIncrement
 
float lastInnovation
 
obs_ring_buffer_t< of_elementsstoredOF
 
of_elements ofDataNew
 
of_elements ofDataDelayed
 
uint8_t ofStoreIndex
 
bool flowDataToFuse
 
bool flowDataValid
 
bool fuseOptFlowData
 
float auxFlowObsInnov
 
float auxFlowObsInnovVar
 
uint32_t flowValidMeaTime_ms
 
uint32_t rngValidMeaTime_ms
 
uint32_t flowMeaTime_ms
 
uint32_t gndHgtValidTime_ms
 
Matrix3f Tbn_flow
 
Vector2 varInnovOptFlow
 
Vector2 innovOptFlow
 
float Popt
 
float terrainState
 
float prevPosN
 
float prevPosE
 
float varInnovRng
 
float innovRng
 
float hgtMea
 
bool inhibitGndState
 
uint32_t prevFlowFuseTime_ms
 
Vector2 flowTestRatio
 
float auxFlowTestRatio
 
float R_LOS
 
float auxRngTestRatio
 
Vector2f flowGyroBias
 
bool rangeDataToFuse
 
bool baroDataToFuse
 
bool gpsDataToFuse
 
bool magDataToFuse
 
Vector2f heldVelNE
 
AidingMode PV_AidingMode
 
AidingMode PV_AidingModePrev
 
bool gpsInhibit
 
bool gndOffsetValid
 
Vector3f delAngBodyOF
 
float delTimeOF
 
bool flowFusionActive
 
Vector3f accelPosOffset
 
float baroHgtOffset
 
float rngOnGnd
 
float storedRngMeas [2][3]
 
uint32_t storedRngMeasTime_ms [2][3]
 
uint32_t lastRngMeasTime_ms
 
uint8_t rngMeasIndex [2]
 
bool terrainHgtStable
 
uint32_t terrainHgtStableSet_ms
 
obs_ring_buffer_t< vel_odm_elementsstoredBodyOdm
 
vel_odm_elements bodyOdmDataNew
 
vel_odm_elements bodyOdmDataDelayed
 
uint32_t lastbodyVelPassTime_ms
 
Vector3 bodyVelTestRatio
 
Vector3 varInnovBodyVel
 
Vector3 innovBodyVel
 
uint32_t prevBodyVelFuseTime_ms
 
uint32_t bodyOdmMeasTime_ms
 
bool bodyVelFusionDelayed
 
bool bodyVelFusionActive
 
uint32_t wheelOdmMeasTime_ms
 
bool usingWheelSensors
 
obs_ring_buffer_t< wheel_odm_elementsstoredWheelOdm
 
wheel_odm_elements wheelOdmDataNew
 
wheel_odm_elements wheelOdmDataDelayed
 
obs_ring_buffer_t< rng_bcn_elementsstoredRangeBeacon
 
rng_bcn_elements rngBcnDataNew
 
rng_bcn_elements rngBcnDataDelayed
 
uint8_t rngBcnStoreIndex
 
uint32_t lastRngBcnPassTime_ms
 
float rngBcnTestRatio
 
bool rngBcnHealth
 
bool rngBcnTimeout
 
float varInnovRngBcn
 
float innovRngBcn
 
uint32_t lastTimeRngBcn_ms [10]
 
bool rngBcnDataToFuse
 
Vector3f beaconVehiclePosNED
 
float beaconVehiclePosErr
 
uint32_t rngBcnLast3DmeasTime_ms
 
bool rngBcnGoodToAlign
 
uint8_t lastRngBcnChecked
 
Vector3f receiverPos
 
float receiverPosCov [3][3]
 
bool rngBcnAlignmentStarted
 
bool rngBcnAlignmentCompleted
 
uint8_t lastBeaconIndex
 
Vector3f rngBcnPosSum
 
uint8_t numBcnMeas
 
float rngSum
 
uint8_t N_beacons
 
float maxBcnPosD
 
float minBcnPosD
 
bool usingMinHypothesis
 
float bcnPosDownOffsetMax
 
float bcnPosOffsetMaxVar
 
float maxOffsetStateChangeFilt
 
float bcnPosDownOffsetMin
 
float bcnPosOffsetMinVar
 
float minOffsetStateChangeFilt
 
Vector3f bcnPosOffsetNED
 
bool bcnOriginEstInit
 
uint8_t rngBcnFuseDataReportIndex
 
struct {
   float   rng
 
   float   innov
 
   float   innovVar
 
   float   testRatio
 
   Vector3f   beaconPosNED
 
rngBcnFusionReport [10]
 
uint8_t activeHgtSource
 
bool takeOffDetected
 
float rngAtStartOfFlight
 
uint32_t timeAtArming_ms
 
bool expectGndEffectTakeoff
 
uint32_t takeoffExpectedSet_ms
 
bool expectGndEffectTouchdown
 
uint32_t touchdownExpectedSet_ms
 
float meaHgtAtTakeOff
 
bool finalInflightYawInit
 
bool finalInflightMagInit
 
bool magStateResetRequest
 
bool magYawResetRequest
 
bool gpsYawResetRequest
 
float posDownAtLastMagReset
 
float yawInnovAtLastMagReset
 
Quaternion quatAtLastMagReset
 
struct {
   bool   bad_xmag:1
 
   bool   bad_ymag:1
 
   bool   bad_zmag:1
 
   bool   bad_airspeed:1
 
   bool   bad_sideslip:1
 
   bool   bad_nvel:1
 
   bool   bad_evel:1
 
   bool   bad_dvel:1
 
   bool   bad_npos:1
 
   bool   bad_epos:1
 
   bool   bad_dpos:1
 
   bool   bad_yaw:1
 
   bool   bad_decl:1
 
   bool   bad_xflow:1
 
   bool   bad_yflow:1
 
   bool   bad_rngbcn:1
 
   bool   bad_xvel:1
 
   bool   bad_yvel:1
 
   bool   bad_zvel:1
 
faultStatus
 
struct {
   bool   bad_sAcc:1
 
   bool   bad_hAcc:1
 
   bool   bad_vAcc:1
 
   bool   bad_yaw:1
 
   bool   bad_sats:1
 
   bool   bad_VZ:1
 
   bool   bad_horiz_drift:1
 
   bool   bad_hdop:1
 
   bool   bad_vert_vel:1
 
   bool   bad_fix:1
 
   bool   bad_horiz_vel:1
 
gpsCheckStatus
 
struct {
   ftype   q0
 
   ftype   q1
 
   ftype   q2
 
   ftype   q3
 
   ftype   magN
 
   ftype   magE
 
   ftype   magD
 
   ftype   magXbias
 
   ftype   magYbias
 
   ftype   magZbias
 
   uint8_t   obsIndex
 
   Matrix3f   DCM
 
   Vector3f   MagPred
 
   ftype   R_MAG
 
   Vector9   SH_MAG
 
mag_state
 
char prearm_fail_string [40]
 
AP_HAL::Util::perf_counter_t _perf_UpdateFilter
 
AP_HAL::Util::perf_counter_t _perf_CovariancePrediction
 
AP_HAL::Util::perf_counter_t _perf_FuseVelPosNED
 
AP_HAL::Util::perf_counter_t _perf_FuseMagnetometer
 
AP_HAL::Util::perf_counter_t _perf_FuseAirspeed
 
AP_HAL::Util::perf_counter_t _perf_FuseSideslip
 
AP_HAL::Util::perf_counter_t _perf_TerrainOffset
 
AP_HAL::Util::perf_counter_t _perf_FuseOptFlow
 
AP_HAL::Util::perf_counter_t _perf_FuseBodyOdom
 
AP_HAL::Util::perf_counter_t _perf_test [10]
 
struct ekf_timing timing
 

Detailed Description

Definition at line 69 of file AP_NavEKF3_core.h.

Member Typedef Documentation

◆ ftype

typedef float NavEKF3_core::ftype
private

Definition at line 365 of file AP_NavEKF3_core.h.

◆ Matrix24

typedef ftype NavEKF3_core::Matrix24[24][24]
private

Definition at line 412 of file AP_NavEKF3_core.h.

◆ Matrix3

typedef ftype NavEKF3_core::Matrix3[3][3]
private

Definition at line 411 of file AP_NavEKF3_core.h.

◆ Matrix34_50

typedef ftype NavEKF3_core::Matrix34_50[34][50]
private

Definition at line 413 of file AP_NavEKF3_core.h.

◆ Vector10

typedef ftype NavEKF3_core::Vector10[10]
private

Definition at line 400 of file AP_NavEKF3_core.h.

◆ Vector11

typedef ftype NavEKF3_core::Vector11[11]
private

Definition at line 401 of file AP_NavEKF3_core.h.

◆ Vector13

typedef ftype NavEKF3_core::Vector13[13]
private

Definition at line 402 of file AP_NavEKF3_core.h.

◆ Vector14

typedef ftype NavEKF3_core::Vector14[14]
private

Definition at line 403 of file AP_NavEKF3_core.h.

◆ Vector15

typedef ftype NavEKF3_core::Vector15[15]
private

Definition at line 404 of file AP_NavEKF3_core.h.

◆ Vector2

typedef ftype NavEKF3_core::Vector2[2]
private

Definition at line 392 of file AP_NavEKF3_core.h.

◆ Vector21

typedef ftype NavEKF3_core::Vector21[21]
private

Definition at line 405 of file AP_NavEKF3_core.h.

◆ Vector22

typedef ftype NavEKF3_core::Vector22[22]
private

Definition at line 406 of file AP_NavEKF3_core.h.

◆ Vector23

typedef ftype NavEKF3_core::Vector23[23]
private

Definition at line 407 of file AP_NavEKF3_core.h.

◆ Vector24

typedef ftype NavEKF3_core::Vector24[24]
private

Definition at line 408 of file AP_NavEKF3_core.h.

◆ Vector25

typedef ftype NavEKF3_core::Vector25[25]
private

Definition at line 409 of file AP_NavEKF3_core.h.

◆ Vector28

typedef ftype NavEKF3_core::Vector28[28]
private

Definition at line 410 of file AP_NavEKF3_core.h.

◆ Vector3

typedef ftype NavEKF3_core::Vector3[3]
private

Definition at line 393 of file AP_NavEKF3_core.h.

◆ Vector4

typedef ftype NavEKF3_core::Vector4[4]
private

Definition at line 394 of file AP_NavEKF3_core.h.

◆ Vector5

typedef ftype NavEKF3_core::Vector5[5]
private

Definition at line 395 of file AP_NavEKF3_core.h.

◆ Vector6

typedef ftype NavEKF3_core::Vector6[6]
private

Definition at line 396 of file AP_NavEKF3_core.h.

◆ Vector7

typedef ftype NavEKF3_core::Vector7[7]
private

Definition at line 397 of file AP_NavEKF3_core.h.

◆ Vector8

typedef ftype NavEKF3_core::Vector8[8]
private

Definition at line 398 of file AP_NavEKF3_core.h.

◆ Vector9

typedef ftype NavEKF3_core::Vector9[9]
private

Definition at line 399 of file AP_NavEKF3_core.h.

◆ Vector_u32_50

typedef uint32_t NavEKF3_core::Vector_u32_50[50]
private

Definition at line 414 of file AP_NavEKF3_core.h.

Member Enumeration Documentation

◆ AidingMode

Enumerator
AID_ABSOLUTE 
AID_NONE 
AID_RELATIVE 

Definition at line 1044 of file AP_NavEKF3_core.h.

◆ resetDataSource

Enumerator
DEFAULT 
GPS 
RNGBCN 
FLOW 
BARO 
MAG 
RNGFND 

Definition at line 971 of file AP_NavEKF3_core.h.

Constructor & Destructor Documentation

◆ NavEKF3_core()

NavEKF3_core::NavEKF3_core ( void  )

Definition at line 14 of file AP_NavEKF3_core.cpp.

Here is the call graph for this function:

Member Function Documentation

◆ alignMagStateDeclination()

void NavEKF3_core::alignMagStateDeclination ( )
private

Definition at line 1152 of file AP_NavEKF3_MagFusion.cpp.

Referenced by calcQuatAndFieldStates(), readGpsData(), readRngBcnData(), and setWindMagStateLearningMode().

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

◆ assume_zero_sideslip()

bool NavEKF3_core::assume_zero_sideslip ( void  ) const
private

Definition at line 462 of file AP_NavEKF3_Control.cpp.

Referenced by calcGpsGoodToAlign(), controlMagYawReset(), detectFlight(), InitialiseFilterBootstrap(), readMagData(), SelectBetaFusion(), SelectMagFusion(), setWindMagStateLearningMode(), and updateFilterStatus().

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

◆ calcEarthRateNED()

void NavEKF3_core::calcEarthRateNED ( Vector3f omega,
int32_t  latitude 
) const
private

Definition at line 1515 of file AP_NavEKF3_core.cpp.

Referenced by InitialiseFilterBootstrap(), setOrigin(), and setOriginLLH().

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

◆ calcFiltBaroOffset()

void NavEKF3_core::calcFiltBaroOffset ( )
private

Definition at line 638 of file AP_NavEKF3_Measurements.cpp.

Referenced by selectHeightForFusion().

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

◆ calcGpsGoodForFlight()

void NavEKF3_core::calcGpsGoodForFlight ( void  )
private

Definition at line 239 of file AP_NavEKF3_VehicleStatus.cpp.

Referenced by readGpsData().

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

◆ calcGpsGoodToAlign()

bool NavEKF3_core::calcGpsGoodToAlign ( void  )
private

Definition at line 21 of file AP_NavEKF3_VehicleStatus.cpp.

Referenced by readGpsData().

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

◆ calcIMU_Weighting()

void NavEKF3_core::calcIMU_Weighting ( float  K1,
float  K2 
)
private

◆ calcOutputStates()

void NavEKF3_core::calcOutputStates ( )
private

Definition at line 691 of file AP_NavEKF3_core.cpp.

Referenced by UpdateFilter().

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

◆ calcQuatAndFieldStates()

Quaternion NavEKF3_core::calcQuatAndFieldStates ( float  roll,
float  pitch 
)
private

Definition at line 1525 of file AP_NavEKF3_core.cpp.

Referenced by controlMagYawReset().

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

◆ CalcRangeBeaconPosDownOffset()

void NavEKF3_core::CalcRangeBeaconPosDownOffset ( float  obsVar,
Vector3f vehiclePosNED,
bool  aligning 
)
private

Definition at line 520 of file AP_NavEKF3_RngBcnFusion.cpp.

Referenced by FuseRngBcn(), and FuseRngBcnStatic().

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

◆ calcRotVecVariances()

Vector3f NavEKF3_core::calcRotVecVariances ( void  )
private

Definition at line 1619 of file AP_NavEKF3_core.cpp.

Referenced by checkAttitudeAlignmentStatus(), controlMagYawReset(), and realignYawGPS().

Here is the caller graph for this function:

◆ checkAttitudeAlignmentStatus()

void NavEKF3_core::checkAttitudeAlignmentStatus ( )
private

Definition at line 385 of file AP_NavEKF3_Control.cpp.

Referenced by controlFilterModes().

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

◆ checkDivergence()

void NavEKF3_core::checkDivergence ( void  )
private

◆ checkGyroCalStatus()

void NavEKF3_core::checkGyroCalStatus ( void  )
private

Definition at line 510 of file AP_NavEKF3_Control.cpp.

Referenced by setAidingMode().

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

◆ ConstrainStates()

void NavEKF3_core::ConstrainStates ( )
private

Definition at line 1488 of file AP_NavEKF3_core.cpp.

Referenced by UpdateStrapdownEquationsNED().

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

◆ ConstrainVariances()

void NavEKF3_core::ConstrainVariances ( )
private

Definition at line 1423 of file AP_NavEKF3_core.cpp.

Referenced by FuseAirspeed(), FuseBodyVel(), FuseDeclination(), fuseEulerYaw(), FuseMagnetometer(), FuseOptFlow(), FuseRngBcn(), FuseSideslip(), and FuseVelPosNED().

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

◆ controlFilterModes()

void NavEKF3_core::controlFilterModes ( )
private

Definition at line 15 of file AP_NavEKF3_Control.cpp.

Referenced by UpdateFilter().

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

◆ controlMagYawReset()

void NavEKF3_core::controlMagYawReset ( )
private

Definition at line 18 of file AP_NavEKF3_MagFusion.cpp.

Referenced by SelectMagFusion().

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

◆ correctDeltaAngle()

void NavEKF3_core::correctDeltaAngle ( Vector3f delAng,
float  delAngDT 
)
private

Definition at line 601 of file AP_NavEKF3_core.cpp.

Referenced by calcOutputStates(), and readIMUData().

Here is the caller graph for this function:

◆ correctDeltaVelocity()

void NavEKF3_core::correctDeltaVelocity ( Vector3f delVel,
float  delVelDT 
)
private

Definition at line 606 of file AP_NavEKF3_core.cpp.

Referenced by calcOutputStates(), and readIMUData().

Here is the caller graph for this function:

◆ correctEkfOriginHeight()

void NavEKF3_core::correctEkfOriginHeight ( )
private

Definition at line 645 of file AP_NavEKF3_Measurements.cpp.

Referenced by selectHeightForFusion().

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

◆ CovarianceInit()

void NavEKF3_core::CovarianceInit ( )
private

Definition at line 484 of file AP_NavEKF3_core.cpp.

Referenced by FuseAirspeed(), fuseEulerYaw(), FuseMagnetometer(), FuseRngBcn(), FuseSideslip(), and InitialiseFilterBootstrap().

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

◆ CovariancePrediction()

void NavEKF3_core::CovariancePrediction ( )
private

Definition at line 835 of file AP_NavEKF3_core.cpp.

Referenced by UpdateFilter().

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

◆ detectFlight()

void NavEKF3_core::detectFlight ( )
private

Definition at line 294 of file AP_NavEKF3_VehicleStatus.cpp.

Referenced by controlFilterModes().

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

◆ detectOptFlowTakeoff()

void NavEKF3_core::detectOptFlowTakeoff ( void  )
private

Definition at line 450 of file AP_NavEKF3_VehicleStatus.cpp.

Referenced by writeOptFlowMeas().

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

◆ effective_magCal()

uint8_t NavEKF3_core::effective_magCal ( void  ) const
private

Definition at line 44 of file AP_NavEKF3_Control.cpp.

Referenced by setWindMagStateLearningMode().

Here is the caller graph for this function:

◆ errorScore()

float NavEKF3_core::errorScore ( void  ) const

Definition at line 42 of file AP_NavEKF3_Outputs.cpp.

Referenced by NavEKF3::UpdateFilter().

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

◆ EstimateTerrainOffset()

void NavEKF3_core::EstimateTerrainOffset ( )
private

Definition at line 84 of file AP_NavEKF3_OptFlowFusion.cpp.

Referenced by SelectFlowFusion().

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

◆ ForceSymmetry()

void NavEKF3_core::ForceSymmetry ( )
private

Definition at line 1408 of file AP_NavEKF3_core.cpp.

Referenced by FuseAirspeed(), FuseBodyVel(), FuseDeclination(), fuseEulerYaw(), FuseMagnetometer(), FuseOptFlow(), FuseRngBcn(), FuseSideslip(), and FuseVelPosNED().

Here is the caller graph for this function:

◆ FuseAirspeed()

void NavEKF3_core::FuseAirspeed ( )
private

Definition at line 25 of file AP_NavEKF3_AirDataFusion.cpp.

Referenced by SelectTasFusion().

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

◆ FuseBodyVel()

void NavEKF3_core::FuseBodyVel ( )
private

Definition at line 921 of file AP_NavEKF3_PosVelFusion.cpp.

Referenced by SelectBodyOdomFusion().

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

◆ FuseDeclination()

void NavEKF3_core::FuseDeclination ( float  declErr)
private

Definition at line 977 of file AP_NavEKF3_MagFusion.cpp.

Referenced by alignMagStateDeclination(), and SelectMagFusion().

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

◆ fuseEulerYaw()

void NavEKF3_core::fuseEulerYaw ( )
private

Definition at line 752 of file AP_NavEKF3_MagFusion.cpp.

Referenced by SelectMagFusion().

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

◆ FuseMagnetometer()

void NavEKF3_core::FuseMagnetometer ( )
private

Definition at line 315 of file AP_NavEKF3_MagFusion.cpp.

Referenced by SelectMagFusion().

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

◆ FuseOptFlow()

void NavEKF3_core::FuseOptFlow ( )
private

Definition at line 266 of file AP_NavEKF3_OptFlowFusion.cpp.

Referenced by SelectFlowFusion().

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

◆ FuseRngBcn()

void NavEKF3_core::FuseRngBcn ( )
private

Definition at line 51 of file AP_NavEKF3_RngBcnFusion.cpp.

Referenced by SelectRngBcnFusion().

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

◆ FuseRngBcnStatic()

void NavEKF3_core::FuseRngBcnStatic ( )
private

Definition at line 285 of file AP_NavEKF3_RngBcnFusion.cpp.

Referenced by SelectRngBcnFusion().

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

◆ FuseSideslip()

void NavEKF3_core::FuseSideslip ( )
private

Definition at line 261 of file AP_NavEKF3_AirDataFusion.cpp.

Referenced by SelectBetaFusion().

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

◆ FuseVelPosNED()

void NavEKF3_core::FuseVelPosNED ( )
private

Definition at line 358 of file AP_NavEKF3_PosVelFusion.cpp.

Referenced by SelectVelPosFusion().

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

◆ getAccelBias()

void NavEKF3_core::getAccelBias ( Vector3f accelBias) const

Definition at line 146 of file AP_NavEKF3_Outputs.cpp.

Referenced by NavEKF3::getAccelBias().

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

◆ getAccelNED()

void NavEKF3_core::getAccelNED ( Vector3f accelNED) const

Definition at line 232 of file AP_NavEKF3_Outputs.cpp.

Referenced by NavEKF3::getAccelNED().

Here is the caller graph for this function:

◆ getActiveMag()

uint8_t NavEKF3_core::getActiveMag ( ) const

Definition at line 430 of file AP_NavEKF3_Outputs.cpp.

Referenced by NavEKF3::getActiveMag().

Here is the caller graph for this function:

◆ getBodyFrameOdomDebug()

uint32_t NavEKF3_core::getBodyFrameOdomDebug ( Vector3f velInnov,
Vector3f velInnovVar 
)

Definition at line 69 of file AP_NavEKF3_Outputs.cpp.

Referenced by NavEKF3::getBodyFrameOdomDebug().

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

◆ getEkfControlLimits()

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

Definition at line 360 of file AP_NavEKF3_Outputs.cpp.

Referenced by NavEKF3::getEkfControlLimits().

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

◆ getEulerAngles()

void NavEKF3_core::getEulerAngles ( Vector3f eulers) const

Definition at line 129 of file AP_NavEKF3_Outputs.cpp.

Referenced by NavEKF3::getEulerAngles(), and NavEKF3::updateLaneSwitchYawResetData().

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

◆ getFilterFaults()

void NavEKF3_core::getFilterFaults ( uint16_t &  faults) const

Definition at line 486 of file AP_NavEKF3_Outputs.cpp.

Referenced by NavEKF3::getFilterFaults(), and healthy().

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

◆ getFilterGpsStatus()

void NavEKF3_core::getFilterGpsStatus ( nav_gps_status status) const

Definition at line 527 of file AP_NavEKF3_Outputs.cpp.

Referenced by NavEKF3::getFilterGpsStatus().

Here is the caller graph for this function:

◆ getFilterStatus()

void NavEKF3_core::getFilterStatus ( nav_filter_status status) const

Definition at line 519 of file AP_NavEKF3_Outputs.cpp.

Referenced by NavEKF3::getFilterStatus().

Here is the caller graph for this function:

◆ getFilterTimeouts()

void NavEKF3_core::getFilterTimeouts ( uint8_t &  timeouts) const

Definition at line 509 of file AP_NavEKF3_Outputs.cpp.

Referenced by NavEKF3::getFilterTimeouts().

Here is the caller graph for this function:

◆ getFlowDebug()

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

Definition at line 55 of file AP_NavEKF3_Outputs.cpp.

Referenced by NavEKF3::getFlowDebug().

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

◆ getFramesSincePredict()

uint8_t NavEKF3_core::getFramesSincePredict ( void  ) const

Definition at line 618 of file AP_NavEKF3_Outputs.cpp.

◆ getGyroBias()

void NavEKF3_core::getGyroBias ( Vector3f gyroBias) const

Definition at line 136 of file AP_NavEKF3_Outputs.cpp.

Referenced by detectOptFlowTakeoff(), and NavEKF3::getGyroBias().

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

◆ getHAGL()

bool NavEKF3_core::getHAGL ( float &  HAGL) const

Definition at line 302 of file AP_NavEKF3_Outputs.cpp.

Referenced by NavEKF3::getHAGL().

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

◆ getHeightControlLimit()

bool NavEKF3_core::getHeightControlLimit ( float &  height) const

Definition at line 111 of file AP_NavEKF3_Outputs.cpp.

Referenced by NavEKF3::getHeightControlLimit().

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

◆ getIMUIndex()

uint8_t NavEKF3_core::getIMUIndex ( void  ) const
inline

Definition at line 352 of file AP_NavEKF3_core.h.

Referenced by NavEKF3::getPrimaryCoreIMUIndex().

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

◆ getInnovations()

void NavEKF3_core::getInnovations ( Vector3f velInnov,
Vector3f posInnov,
Vector3f magInnov,
float &  tasInnov,
float &  yawInnov 
) const

Definition at line 436 of file AP_NavEKF3_Outputs.cpp.

Referenced by NavEKF3::getInnovations().

Here is the caller graph for this function:

◆ getLastPosDownReset()

uint32_t NavEKF3_core::getLastPosDownReset ( float &  posD) const

Definition at line 192 of file AP_NavEKF3_Outputs.cpp.

Referenced by NavEKF3::getLastPosDownReset().

Here is the caller graph for this function:

◆ getLastPosNorthEastReset()

uint32_t NavEKF3_core::getLastPosNorthEastReset ( Vector2f pos) const

Definition at line 184 of file AP_NavEKF3_Outputs.cpp.

Referenced by NavEKF3::getLastPosNorthEastReset().

Here is the caller graph for this function:

◆ getLastVelNorthEastReset()

uint32_t NavEKF3_core::getLastVelNorthEastReset ( Vector2f vel) const

Definition at line 200 of file AP_NavEKF3_Outputs.cpp.

Referenced by NavEKF3::getLastVelNorthEastReset().

Here is the caller graph for this function:

◆ getLastYawResetAngle()

uint32_t NavEKF3_core::getLastYawResetAngle ( float &  yawAng) const

Definition at line 176 of file AP_NavEKF3_Outputs.cpp.

Referenced by NavEKF3::getLastYawResetAngle().

Here is the caller graph for this function:

◆ getLLH()

bool NavEKF3_core::getLLH ( struct Location loc) const

Definition at line 313 of file AP_NavEKF3_Outputs.cpp.

Referenced by NavEKF3::getLLH().

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

◆ getMagNED()

void NavEKF3_core::getMagNED ( Vector3f magNED) const

Definition at line 394 of file AP_NavEKF3_Outputs.cpp.

Referenced by NavEKF3::getMagNED().

Here is the caller graph for this function:

◆ getMagOffsets()

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

Definition at line 407 of file AP_NavEKF3_Outputs.cpp.

Here is the call graph for this function:

◆ getMagXYZ()

void NavEKF3_core::getMagXYZ ( Vector3f magXYZ) const

Definition at line 400 of file AP_NavEKF3_Outputs.cpp.

Referenced by NavEKF3::getMagXYZ().

Here is the caller graph for this function:

◆ getOriginLLH()

bool NavEKF3_core::getOriginLLH ( struct Location loc) const

Definition at line 381 of file AP_NavEKF3_Outputs.cpp.

Referenced by NavEKF3::getOriginLLH().

Here is the caller graph for this function:

◆ getOutputTrackingError()

void NavEKF3_core::getOutputTrackingError ( Vector3f error) const

Definition at line 624 of file AP_NavEKF3_Outputs.cpp.

Referenced by NavEKF3::getOutputTrackingError().

Here is the caller graph for this function:

◆ getPosD()

bool NavEKF3_core::getPosD ( float &  posD) const

Definition at line 282 of file AP_NavEKF3_Outputs.cpp.

Referenced by NavEKF3::getPosD(), and NavEKF3::updateLaneSwitchPosDownResetData().

Here is the caller graph for this function:

◆ getPosDownDerivative()

float NavEKF3_core::getPosDownDerivative ( void  ) const

Definition at line 224 of file AP_NavEKF3_Outputs.cpp.

Referenced by NavEKF3::getPosDownDerivative().

Here is the caller graph for this function:

◆ getPosNE()

bool NavEKF3_core::getPosNE ( Vector2f posNE) const

Definition at line 239 of file AP_NavEKF3_Outputs.cpp.

Referenced by NavEKF3::getPosNE(), and NavEKF3::updateLaneSwitchPosResetData().

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

◆ getQuaternion()

void NavEKF3_core::getQuaternion ( Quaternion quat) const

Definition at line 169 of file AP_NavEKF3_Outputs.cpp.

Referenced by NavEKF3::getQuaternion().

Here is the caller graph for this function:

◆ getRangeBeaconDebug()

bool NavEKF3_core::getRangeBeaconDebug ( uint8_t &  ID,
float &  rng,
float &  innov,
float &  innovVar,
float &  testRatio,
Vector3f beaconPosNED,
float &  offsetHigh,
float &  offsetLow,
Vector3f posNED 
)

Definition at line 81 of file AP_NavEKF3_Outputs.cpp.

Referenced by NavEKF3::getRangeBeaconDebug().

Here is the caller graph for this function:

◆ getRotationBodyToNED()

void NavEKF3_core::getRotationBodyToNED ( Matrix3f mat) const

Definition at line 162 of file AP_NavEKF3_Outputs.cpp.

Referenced by NavEKF3::getRotationBodyToNED().

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

◆ getStateVariances()

void NavEKF3_core::getStateVariances ( float  stateVar[24])

Definition at line 468 of file AP_NavEKF3_Outputs.cpp.

Referenced by NavEKF3::getStateVariances().

Here is the caller graph for this function:

◆ getTakeoffExpected()

bool NavEKF3_core::getTakeoffExpected ( )
private

Definition at line 404 of file AP_NavEKF3_VehicleStatus.cpp.

Referenced by readBaroData(), and selectHeightForFusion().

Here is the caller graph for this function:

◆ getTiltError()

void NavEKF3_core::getTiltError ( float &  ang) const

Definition at line 156 of file AP_NavEKF3_Outputs.cpp.

Referenced by NavEKF3::getTiltError().

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

◆ getTimingStatistics()

void NavEKF3_core::getTimingStatistics ( struct ekf_timing timing)

Definition at line 853 of file AP_NavEKF3_Measurements.cpp.

Referenced by getIMUIndex(), and NavEKF3::getTimingStatistics().

Here is the caller graph for this function:

◆ getTouchdownExpected()

bool NavEKF3_core::getTouchdownExpected ( )
private

Definition at line 423 of file AP_NavEKF3_VehicleStatus.cpp.

Referenced by FuseVelPosNED(), and selectHeightForFusion().

Here is the caller graph for this function:

◆ getVariances()

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

Definition at line 454 of file AP_NavEKF3_Outputs.cpp.

Referenced by NavEKF3::getVariances(), and send_status_report().

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

◆ getVelNED()

void NavEKF3_core::getVelNED ( Vector3f vel) const

Definition at line 217 of file AP_NavEKF3_Outputs.cpp.

Referenced by NavEKF3::getVelNED().

Here is the caller graph for this function:

◆ getWind()

void NavEKF3_core::getWind ( Vector3f wind) const

Definition at line 207 of file AP_NavEKF3_Outputs.cpp.

Referenced by NavEKF3::getWind().

Here is the caller graph for this function:

◆ healthy()

bool NavEKF3_core::healthy ( void  ) const

Definition at line 14 of file AP_NavEKF3_Outputs.cpp.

Referenced by getHAGL(), NavEKF3::healthy(), NavEKF3::UpdateFilter(), and updateFilterStatus().

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

◆ InitialGyroBiasUncertainty()

float NavEKF3_core::InitialGyroBiasUncertainty ( void  ) const
private

Definition at line 29 of file AP_NavEKF3_GyroBias.cpp.

Referenced by CovarianceInit(), and setWindMagStateLearningMode().

Here is the caller graph for this function:

◆ InitialiseFilterBootstrap()

bool NavEKF3_core::InitialiseFilterBootstrap ( void  )

Definition at line 397 of file AP_NavEKF3_core.cpp.

Referenced by NavEKF3::InitialiseFilter().

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

◆ initialiseQuatCovariances()

void NavEKF3_core::initialiseQuatCovariances ( Vector3f rotVarVec)
private

Definition at line 1662 of file AP_NavEKF3_core.cpp.

Referenced by controlMagYawReset(), CovarianceInit(), and realignYawGPS().

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

◆ InitialiseVariables()

void NavEKF3_core::InitialiseVariables ( )
private

Definition at line 155 of file AP_NavEKF3_core.cpp.

Referenced by InitialiseFilterBootstrap().

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

◆ prearm_failure_reason()

const char * NavEKF3_core::prearm_failure_reason ( void  ) const

Definition at line 606 of file AP_NavEKF3_Outputs.cpp.

Referenced by NavEKF3::prearm_failure_reason().

Here is the caller graph for this function:

◆ quat2Tbn()

void NavEKF3_core::quat2Tbn ( Matrix3f Tbn,
const Quaternion quat 
) const
private

Definition at line 1401 of file AP_NavEKF3_core.cpp.

Here is the call graph for this function:

◆ readAirSpdData()

void NavEKF3_core::readAirSpdData ( )
private

Definition at line 690 of file AP_NavEKF3_Measurements.cpp.

Referenced by SelectTasFusion().

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

◆ readBaroData()

void NavEKF3_core::readBaroData ( )
private

Definition at line 602 of file AP_NavEKF3_Measurements.cpp.

Referenced by InitialiseFilterBootstrap(), and selectHeightForFusion().

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

◆ readDeltaAngle()

bool NavEKF3_core::readDeltaAngle ( uint8_t  ins_index,
Vector3f dAng 
)
private

Definition at line 585 of file AP_NavEKF3_Measurements.cpp.

Referenced by readIMUData().

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

◆ readDeltaVelocity()

bool NavEKF3_core::readDeltaVelocity ( uint8_t  ins_index,
Vector3f dVel,
float &  dVel_dt 
)
private

Definition at line 439 of file AP_NavEKF3_Measurements.cpp.

Referenced by readIMUData().

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

◆ readGpsData()

void NavEKF3_core::readGpsData ( )
private

Definition at line 455 of file AP_NavEKF3_Measurements.cpp.

Referenced by InitialiseFilterBootstrap(), and SelectVelPosFusion().

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

◆ readIMUData()

void NavEKF3_core::readIMUData ( )
private

Definition at line 330 of file AP_NavEKF3_Measurements.cpp.

Referenced by InitialiseFilterBootstrap(), and UpdateFilter().

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

◆ readMagData()

void NavEKF3_core::readMagData ( )
private

Definition at line 236 of file AP_NavEKF3_Measurements.cpp.

Referenced by calcQuatAndFieldStates(), InitialiseFilterBootstrap(), and SelectMagFusion().

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

◆ readRangeFinder()

void NavEKF3_core::readRangeFinder ( void  )
private

Definition at line 20 of file AP_NavEKF3_Measurements.cpp.

Referenced by selectHeightForFusion().

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

◆ readRngBcnData()

void NavEKF3_core::readRngBcnData ( )
private

Definition at line 718 of file AP_NavEKF3_Measurements.cpp.

Referenced by SelectRngBcnFusion().

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

◆ readyToUseBodyOdm()

bool NavEKF3_core::readyToUseBodyOdm ( void  ) const
private

Definition at line 425 of file AP_NavEKF3_Control.cpp.

Referenced by setAidingMode().

Here is the caller graph for this function:

◆ readyToUseGPS()

bool NavEKF3_core::readyToUseGPS ( void  ) const
private

Definition at line 442 of file AP_NavEKF3_Control.cpp.

Referenced by setAidingMode().

Here is the caller graph for this function:

◆ readyToUseOptFlow()

bool NavEKF3_core::readyToUseOptFlow ( void  ) const
private

Definition at line 418 of file AP_NavEKF3_Control.cpp.

Referenced by setAidingMode().

Here is the caller graph for this function:

◆ readyToUseRangeBeacon()

bool NavEKF3_core::readyToUseRangeBeacon ( void  ) const
private

Definition at line 448 of file AP_NavEKF3_Control.cpp.

Referenced by setAidingMode().

Here is the caller graph for this function:

◆ realignYawGPS()

void NavEKF3_core::realignYawGPS ( )
private

Definition at line 150 of file AP_NavEKF3_MagFusion.cpp.

Referenced by SelectVelPosFusion().

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

◆ RecallBaro()

bool NavEKF3_core::RecallBaro ( )
private

◆ RecallMag()

bool NavEKF3_core::RecallMag ( )
private

◆ RecallOF()

bool NavEKF3_core::RecallOF ( )
private

◆ RecallRange()

bool NavEKF3_core::RecallRange ( )
private

◆ RecallTAS()

bool NavEKF3_core::RecallTAS ( )
private

◆ recordMagReset()

void NavEKF3_core::recordMagReset ( )
private

Definition at line 1185 of file AP_NavEKF3_MagFusion.cpp.

Referenced by calcQuatAndFieldStates().

Here is the caller graph for this function:

◆ recordYawReset()

void NavEKF3_core::recordYawReset ( )
private

Definition at line 501 of file AP_NavEKF3_Control.cpp.

Referenced by controlMagYawReset(), and realignYawGPS().

Here is the caller graph for this function:

◆ resetGyroBias()

void NavEKF3_core::resetGyroBias ( void  )

Definition at line 15 of file AP_NavEKF3_GyroBias.cpp.

Referenced by NavEKF3::resetGyroBias().

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

◆ ResetHeight()

void NavEKF3_core::ResetHeight ( void  )
private

Definition at line 139 of file AP_NavEKF3_PosVelFusion.cpp.

Referenced by FuseVelPosNED(), and InitialiseFilterBootstrap().

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

◆ resetHeightDatum()

bool NavEKF3_core::resetHeightDatum ( void  )

Definition at line 202 of file AP_NavEKF3_PosVelFusion.cpp.

Here is the call graph for this function:

◆ ResetPosition()

void NavEKF3_core::ResetPosition ( void  )
private

Definition at line 76 of file AP_NavEKF3_PosVelFusion.cpp.

Referenced by FuseVelPosNED(), InitialiseFilterBootstrap(), realignYawGPS(), and setAidingMode().

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

◆ ResetVelocity()

void NavEKF3_core::ResetVelocity ( void  )
private

Definition at line 20 of file AP_NavEKF3_PosVelFusion.cpp.

Referenced by FuseVelPosNED(), InitialiseFilterBootstrap(), realignYawGPS(), and setAidingMode().

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

◆ SelectBetaFusion()

void NavEKF3_core::SelectBetaFusion ( )
private

Definition at line 231 of file AP_NavEKF3_AirDataFusion.cpp.

Referenced by UpdateFilter().

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

◆ SelectBodyOdomFusion()

void NavEKF3_core::SelectBodyOdomFusion ( )
private

Definition at line 1553 of file AP_NavEKF3_PosVelFusion.cpp.

Referenced by UpdateFilter().

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

◆ SelectFlowFusion()

void NavEKF3_core::SelectFlowFusion ( )
private

Definition at line 22 of file AP_NavEKF3_OptFlowFusion.cpp.

Referenced by UpdateFilter().

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

◆ selectHeightForFusion()

void NavEKF3_core::selectHeightForFusion ( )
private

Definition at line 746 of file AP_NavEKF3_PosVelFusion.cpp.

Referenced by SelectVelPosFusion().

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

◆ SelectMagFusion()

void NavEKF3_core::SelectMagFusion ( )
private

Definition at line 219 of file AP_NavEKF3_MagFusion.cpp.

Referenced by UpdateFilter().

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

◆ SelectRngBcnFusion()

void NavEKF3_core::SelectRngBcnFusion ( )
private

Definition at line 18 of file AP_NavEKF3_RngBcnFusion.cpp.

Referenced by UpdateFilter().

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

◆ SelectTasFusion()

void NavEKF3_core::SelectTasFusion ( )
private

Definition at line 200 of file AP_NavEKF3_AirDataFusion.cpp.

Referenced by UpdateFilter().

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

◆ SelectVelPosFusion()

void NavEKF3_core::SelectVelPosFusion ( )
private

Definition at line 227 of file AP_NavEKF3_PosVelFusion.cpp.

Referenced by UpdateFilter().

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

◆ send_status_report()

void NavEKF3_core::send_status_report ( mavlink_channel_t  chan)

Definition at line 546 of file AP_NavEKF3_Outputs.cpp.

Referenced by NavEKF3::send_status_report().

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

◆ setAidingMode()

void NavEKF3_core::setAidingMode ( )
private

Definition at line 197 of file AP_NavEKF3_Control.cpp.

Referenced by controlFilterModes().

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

◆ setInhibitGPS()

uint8_t NavEKF3_core::setInhibitGPS ( void  )

Definition at line 523 of file AP_NavEKF3_Control.cpp.

Referenced by NavEKF3::setInhibitGPS().

Here is the caller graph for this function:

◆ setOrigin()

void NavEKF3_core::setOrigin ( )
private

Definition at line 485 of file AP_NavEKF3_Control.cpp.

Referenced by readGpsData().

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

◆ setOriginLLH()

bool NavEKF3_core::setOriginLLH ( const Location loc)

Definition at line 471 of file AP_NavEKF3_Control.cpp.

Referenced by readRngBcnData(), and NavEKF3::setOriginLLH().

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

◆ setTakeoffExpected()

void NavEKF3_core::setTakeoffExpected ( bool  val)

Definition at line 415 of file AP_NavEKF3_VehicleStatus.cpp.

Referenced by NavEKF3::setTakeoffExpected().

Here is the caller graph for this function:

◆ setTerrainHgtStable()

void NavEKF3_core::setTerrainHgtStable ( bool  val)

Definition at line 443 of file AP_NavEKF3_VehicleStatus.cpp.

Referenced by NavEKF3::setTerrainHgtStable().

Here is the caller graph for this function:

◆ setTouchdownExpected()

void NavEKF3_core::setTouchdownExpected ( bool  val)

Definition at line 434 of file AP_NavEKF3_VehicleStatus.cpp.

Referenced by NavEKF3::setTouchdownExpected().

Here is the caller graph for this function:

◆ setup_core()

bool NavEKF3_core::setup_core ( NavEKF3 _frontend,
uint8_t  _imu_index,
uint8_t  _core_index 
)

Definition at line 42 of file AP_NavEKF3_core.cpp.

Referenced by NavEKF3::InitialiseFilter().

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

◆ setWindMagStateLearningMode()

void NavEKF3_core::setWindMagStateLearningMode ( )
private

Definition at line 56 of file AP_NavEKF3_Control.cpp.

Referenced by controlFilterModes().

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

◆ StoreBaro()

void NavEKF3_core::StoreBaro ( )
private

◆ StoreMag()

void NavEKF3_core::StoreMag ( )
private

◆ StoreOF()

void NavEKF3_core::StoreOF ( )
private

◆ StoreOutputReset()

void NavEKF3_core::StoreOutputReset ( void  )
private

Definition at line 1363 of file AP_NavEKF3_core.cpp.

Referenced by InitialiseFilterBootstrap().

Here is the caller graph for this function:

◆ StoreQuatReset()

void NavEKF3_core::StoreQuatReset ( void  )
private

Definition at line 1379 of file AP_NavEKF3_core.cpp.

◆ StoreQuatRotate()

void NavEKF3_core::StoreQuatRotate ( Quaternion  deltaQuat)
private

Definition at line 1390 of file AP_NavEKF3_core.cpp.

Referenced by controlMagYawReset().

Here is the caller graph for this function:

◆ StoreRange()

void NavEKF3_core::StoreRange ( )
private

◆ StoreTAS()

void NavEKF3_core::StoreTAS ( )
private

◆ UpdateFilter()

void NavEKF3_core::UpdateFilter ( bool  predict)

Definition at line 534 of file AP_NavEKF3_core.cpp.

Referenced by NavEKF3::UpdateFilter().

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

◆ updateFilterStatus()

void NavEKF3_core::updateFilterStatus ( void  )
private

Definition at line 534 of file AP_NavEKF3_Control.cpp.

Referenced by UpdateFilter().

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

◆ updateStateIndexLim()

void NavEKF3_core::updateStateIndexLim ( void  )
private

Definition at line 175 of file AP_NavEKF3_Control.cpp.

Referenced by setWindMagStateLearningMode().

Here is the caller graph for this function:

◆ UpdateStrapdownEquationsNED()

void NavEKF3_core::UpdateStrapdownEquationsNED ( )
private

Definition at line 618 of file AP_NavEKF3_core.cpp.

Referenced by UpdateFilter().

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

◆ updateTimingStatistics()

void NavEKF3_core::updateTimingStatistics ( void  )
private

Definition at line 828 of file AP_NavEKF3_Measurements.cpp.

Referenced by readIMUData().

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

◆ use_compass()

bool NavEKF3_core::use_compass ( void  ) const

Definition at line 454 of file AP_NavEKF3_Control.cpp.

Referenced by alignMagStateDeclination(), calcGpsGoodToAlign(), calcQuatAndFieldStates(), checkAttitudeAlignmentStatus(), FuseDeclination(), fuseEulerYaw(), readMagData(), realignYawGPS(), SelectBetaFusion(), SelectMagFusion(), setWindMagStateLearningMode(), updateFilterStatus(), and NavEKF3::use_compass().

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

◆ useAirspeed()

bool NavEKF3_core::useAirspeed ( void  ) const
private

Definition at line 405 of file AP_NavEKF3_Control.cpp.

Referenced by SelectBetaFusion(), and setWindMagStateLearningMode().

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

◆ useRngFinder()

bool NavEKF3_core::useRngFinder ( void  ) const
private

Definition at line 411 of file AP_NavEKF3_Control.cpp.

◆ writeBodyFrameOdom()

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

Definition at line 114 of file AP_NavEKF3_Measurements.cpp.

Referenced by NavEKF3::writeBodyFrameOdom().

Here is the caller graph for this function:

◆ writeOptFlowMeas()

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

Definition at line 164 of file AP_NavEKF3_Measurements.cpp.

Referenced by NavEKF3::writeOptFlowMeas().

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

◆ writeWheelOdom()

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

Definition at line 136 of file AP_NavEKF3_Measurements.cpp.

Referenced by NavEKF3::writeWheelOdom().

Here is the caller graph for this function:

◆ zeroAttCovOnly()

void NavEKF3_core::zeroAttCovOnly ( )
private

Definition at line 1605 of file AP_NavEKF3_core.cpp.

Referenced by calcQuatAndFieldStates().

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

◆ zeroCols()

void NavEKF3_core::zeroCols ( Matrix24 covMat,
uint8_t  first,
uint8_t  last 
)
private

Definition at line 1353 of file AP_NavEKF3_core.cpp.

Referenced by alignMagStateDeclination(), calcQuatAndFieldStates(), ConstrainVariances(), FuseVelPosNED(), initialiseQuatCovariances(), realignYawGPS(), resetGyroBias(), ResetHeight(), ResetPosition(), ResetVelocity(), and zeroAttCovOnly().

Here is the caller graph for this function:

◆ zeroRows()

void NavEKF3_core::zeroRows ( Matrix24 covMat,
uint8_t  first,
uint8_t  last 
)
private

Definition at line 1343 of file AP_NavEKF3_core.cpp.

Referenced by alignMagStateDeclination(), calcQuatAndFieldStates(), ConstrainVariances(), FuseVelPosNED(), initialiseQuatCovariances(), realignYawGPS(), resetGyroBias(), ResetHeight(), ResetPosition(), ResetVelocity(), and zeroAttCovOnly().

Here is the caller graph for this function:

Member Data Documentation

◆ _ahrs

const AP_AHRS* NavEKF3_core::_ahrs
private

◆ _perf_CovariancePrediction

AP_HAL::Util::perf_counter_t NavEKF3_core::_perf_CovariancePrediction
private

Definition at line 1230 of file AP_NavEKF3_core.h.

Referenced by CovariancePrediction().

◆ _perf_FuseAirspeed

AP_HAL::Util::perf_counter_t NavEKF3_core::_perf_FuseAirspeed
private

Definition at line 1233 of file AP_NavEKF3_core.h.

Referenced by FuseAirspeed().

◆ _perf_FuseBodyOdom

AP_HAL::Util::perf_counter_t NavEKF3_core::_perf_FuseBodyOdom
private

Definition at line 1237 of file AP_NavEKF3_core.h.

Referenced by SelectBodyOdomFusion().

◆ _perf_FuseMagnetometer

AP_HAL::Util::perf_counter_t NavEKF3_core::_perf_FuseMagnetometer
private

Definition at line 1232 of file AP_NavEKF3_core.h.

Referenced by SelectMagFusion().

◆ _perf_FuseOptFlow

AP_HAL::Util::perf_counter_t NavEKF3_core::_perf_FuseOptFlow
private

Definition at line 1236 of file AP_NavEKF3_core.h.

Referenced by SelectFlowFusion().

◆ _perf_FuseSideslip

AP_HAL::Util::perf_counter_t NavEKF3_core::_perf_FuseSideslip
private

Definition at line 1234 of file AP_NavEKF3_core.h.

Referenced by FuseSideslip().

◆ _perf_FuseVelPosNED

AP_HAL::Util::perf_counter_t NavEKF3_core::_perf_FuseVelPosNED
private

Definition at line 1231 of file AP_NavEKF3_core.h.

Referenced by FuseVelPosNED().

◆ _perf_TerrainOffset

AP_HAL::Util::perf_counter_t NavEKF3_core::_perf_TerrainOffset
private

Definition at line 1235 of file AP_NavEKF3_core.h.

Referenced by EstimateTerrainOffset().

◆ _perf_test

AP_HAL::Util::perf_counter_t NavEKF3_core::_perf_test[10]
private

Definition at line 1238 of file AP_NavEKF3_core.h.

Referenced by NavEKF3_core(), and SelectMagFusion().

◆ _perf_UpdateFilter

AP_HAL::Util::perf_counter_t NavEKF3_core::_perf_UpdateFilter
private

Definition at line 1229 of file AP_NavEKF3_core.h.

Referenced by UpdateFilter().

◆ accelPosOffset

Vector3f NavEKF3_core::accelPosOffset
private

◆ accNavMag

ftype NavEKF3_core::accNavMag
private

Definition at line 826 of file AP_NavEKF3_core.h.

Referenced by FuseVelPosNED(), and UpdateStrapdownEquationsNED().

◆ accNavMagHoriz

ftype NavEKF3_core::accNavMagHoriz
private

Definition at line 827 of file AP_NavEKF3_core.h.

Referenced by setWindMagStateLearningMode(), and UpdateStrapdownEquationsNED().

◆ activeHgtSource

uint8_t NavEKF3_core::activeHgtSource
private

◆ airborneDetectTime_ms

uint32_t NavEKF3_core::airborneDetectTime_ms
private

Definition at line 838 of file AP_NavEKF3_core.h.

Referenced by detectFlight().

◆ airSpdFusionDelayed

bool NavEKF3_core::airSpdFusionDelayed
private

Definition at line 933 of file AP_NavEKF3_core.h.

Referenced by InitialiseVariables(), and SelectTasFusion().

◆ allMagSensorsFailed

bool NavEKF3_core::allMagSensorsFailed
private

Definition at line 867 of file AP_NavEKF3_core.h.

Referenced by InitialiseVariables(), readMagData(), realignYawGPS(), and use_compass().

◆ auxFlowObsInnov

float NavEKF3_core::auxFlowObsInnov
private

Definition at line 1016 of file AP_NavEKF3_core.h.

Referenced by EstimateTerrainOffset(), and getFlowDebug().

◆ auxFlowObsInnovVar

float NavEKF3_core::auxFlowObsInnovVar
private

Definition at line 1017 of file AP_NavEKF3_core.h.

Referenced by EstimateTerrainOffset().

◆ auxFlowTestRatio

float NavEKF3_core::auxFlowTestRatio
private

Definition at line 1035 of file AP_NavEKF3_core.h.

Referenced by EstimateTerrainOffset().

◆ auxRngTestRatio

float NavEKF3_core::auxRngTestRatio
private

Definition at line 1037 of file AP_NavEKF3_core.h.

Referenced by EstimateTerrainOffset(), and send_status_report().

◆ bad_airspeed

bool NavEKF3_core::bad_airspeed

Definition at line 1171 of file AP_NavEKF3_core.h.

◆ bad_decl

bool NavEKF3_core::bad_decl

Definition at line 1180 of file AP_NavEKF3_core.h.

◆ bad_dpos

bool NavEKF3_core::bad_dpos

Definition at line 1178 of file AP_NavEKF3_core.h.

◆ bad_dvel

bool NavEKF3_core::bad_dvel

Definition at line 1175 of file AP_NavEKF3_core.h.

◆ bad_epos

bool NavEKF3_core::bad_epos

Definition at line 1177 of file AP_NavEKF3_core.h.

◆ bad_evel

bool NavEKF3_core::bad_evel

Definition at line 1174 of file AP_NavEKF3_core.h.

◆ bad_fix

bool NavEKF3_core::bad_fix

Definition at line 1200 of file AP_NavEKF3_core.h.

◆ bad_hAcc

bool NavEKF3_core::bad_hAcc

Definition at line 1192 of file AP_NavEKF3_core.h.

◆ bad_hdop

bool NavEKF3_core::bad_hdop

Definition at line 1198 of file AP_NavEKF3_core.h.

◆ bad_horiz_drift

bool NavEKF3_core::bad_horiz_drift

Definition at line 1197 of file AP_NavEKF3_core.h.

◆ bad_horiz_vel

bool NavEKF3_core::bad_horiz_vel

Definition at line 1201 of file AP_NavEKF3_core.h.

◆ bad_npos

bool NavEKF3_core::bad_npos

Definition at line 1176 of file AP_NavEKF3_core.h.

◆ bad_nvel

bool NavEKF3_core::bad_nvel

Definition at line 1173 of file AP_NavEKF3_core.h.

◆ bad_rngbcn

bool NavEKF3_core::bad_rngbcn

Definition at line 1183 of file AP_NavEKF3_core.h.

◆ bad_sAcc

bool NavEKF3_core::bad_sAcc

Definition at line 1191 of file AP_NavEKF3_core.h.

◆ bad_sats

bool NavEKF3_core::bad_sats

Definition at line 1195 of file AP_NavEKF3_core.h.

◆ bad_sideslip

bool NavEKF3_core::bad_sideslip

Definition at line 1172 of file AP_NavEKF3_core.h.

◆ bad_vAcc

bool NavEKF3_core::bad_vAcc

Definition at line 1193 of file AP_NavEKF3_core.h.

◆ bad_vert_vel

bool NavEKF3_core::bad_vert_vel

Definition at line 1199 of file AP_NavEKF3_core.h.

◆ bad_VZ

bool NavEKF3_core::bad_VZ

Definition at line 1196 of file AP_NavEKF3_core.h.

◆ bad_xflow

bool NavEKF3_core::bad_xflow

Definition at line 1181 of file AP_NavEKF3_core.h.

◆ bad_xmag

bool NavEKF3_core::bad_xmag

Definition at line 1168 of file AP_NavEKF3_core.h.

◆ bad_xvel

bool NavEKF3_core::bad_xvel

Definition at line 1184 of file AP_NavEKF3_core.h.

◆ bad_yaw

bool NavEKF3_core::bad_yaw

Definition at line 1179 of file AP_NavEKF3_core.h.

◆ bad_yflow

bool NavEKF3_core::bad_yflow

Definition at line 1182 of file AP_NavEKF3_core.h.

◆ bad_ymag

bool NavEKF3_core::bad_ymag

Definition at line 1169 of file AP_NavEKF3_core.h.

◆ bad_yvel

bool NavEKF3_core::bad_yvel

Definition at line 1185 of file AP_NavEKF3_core.h.

◆ bad_zmag

bool NavEKF3_core::bad_zmag

Definition at line 1170 of file AP_NavEKF3_core.h.

◆ bad_zvel

bool NavEKF3_core::bad_zvel

Definition at line 1186 of file AP_NavEKF3_core.h.

◆ badIMUdata

bool NavEKF3_core::badIMUdata
private

◆ badMagYaw

bool NavEKF3_core::badMagYaw
private

Definition at line 810 of file AP_NavEKF3_core.h.

Referenced by InitialiseVariables(), and realignYawGPS().

◆ baroDataDelayed

baro_elements NavEKF3_core::baroDataDelayed
private

Definition at line 905 of file AP_NavEKF3_core.h.

Referenced by calcFiltBaroOffset(), selectHeightForFusion(), and setAidingMode().

◆ baroDataNew

baro_elements NavEKF3_core::baroDataNew
private

Definition at line 904 of file AP_NavEKF3_core.h.

Referenced by readBaroData().

◆ baroDataToFuse

bool NavEKF3_core::baroDataToFuse
private

Definition at line 1040 of file AP_NavEKF3_core.h.

Referenced by selectHeightForFusion().

◆ baroHgtOffset

float NavEKF3_core::baroHgtOffset
private

◆ baroStoreIndex

uint8_t NavEKF3_core::baroStoreIndex
private

Definition at line 906 of file AP_NavEKF3_core.h.

Referenced by InitialiseVariables().

◆ bcnOriginEstInit

bool NavEKF3_core::bcnOriginEstInit
private

Definition at line 1129 of file AP_NavEKF3_core.h.

Referenced by InitialiseVariables(), and SelectRngBcnFusion().

◆ bcnPosDownOffsetMax

float NavEKF3_core::bcnPosDownOffsetMax
private

◆ bcnPosDownOffsetMin

float NavEKF3_core::bcnPosDownOffsetMin
private

◆ bcnPosOffsetMaxVar

float NavEKF3_core::bcnPosOffsetMaxVar
private

Definition at line 1121 of file AP_NavEKF3_core.h.

Referenced by CalcRangeBeaconPosDownOffset(), and InitialiseVariables().

◆ bcnPosOffsetMinVar

float NavEKF3_core::bcnPosOffsetMinVar
private

Definition at line 1125 of file AP_NavEKF3_core.h.

Referenced by CalcRangeBeaconPosDownOffset(), and InitialiseVariables().

◆ bcnPosOffsetNED

Vector3f NavEKF3_core::bcnPosOffsetNED
private

◆ beaconPosNED

Vector3f NavEKF3_core::beaconPosNED

Definition at line 1138 of file AP_NavEKF3_core.h.

◆ beaconVehiclePosErr

float NavEKF3_core::beaconVehiclePosErr
private

Definition at line 1103 of file AP_NavEKF3_core.h.

Referenced by InitialiseVariables(), and readRngBcnData().

◆ beaconVehiclePosNED

Vector3f NavEKF3_core::beaconVehiclePosNED
private

Definition at line 1102 of file AP_NavEKF3_core.h.

Referenced by InitialiseVariables(), and readRngBcnData().

◆ bodyMagFieldVar

Vector3f NavEKF3_core::bodyMagFieldVar
private

Definition at line 957 of file AP_NavEKF3_core.h.

Referenced by SelectMagFusion(), and setWindMagStateLearningMode().

◆ bodyOdmDataDelayed

vel_odm_elements NavEKF3_core::bodyOdmDataDelayed
private

◆ bodyOdmDataNew

vel_odm_elements NavEKF3_core::bodyOdmDataNew
private

Definition at line 1070 of file AP_NavEKF3_core.h.

Referenced by InitialiseVariables(), readyToUseBodyOdm(), and writeBodyFrameOdom().

◆ bodyOdmMeasTime_ms

uint32_t NavEKF3_core::bodyOdmMeasTime_ms
private

Definition at line 1077 of file AP_NavEKF3_core.h.

Referenced by InitialiseVariables(), readyToUseBodyOdm(), and writeBodyFrameOdom().

◆ bodyVelFusionActive

bool NavEKF3_core::bodyVelFusionActive
private

Definition at line 1079 of file AP_NavEKF3_core.h.

Referenced by FuseBodyVel(), InitialiseVariables(), and setAidingMode().

◆ bodyVelFusionDelayed

bool NavEKF3_core::bodyVelFusionDelayed
private

Definition at line 1078 of file AP_NavEKF3_core.h.

Referenced by InitialiseVariables(), and SelectBodyOdomFusion().

◆ bodyVelTestRatio

Vector3 NavEKF3_core::bodyVelTestRatio
private

Definition at line 1073 of file AP_NavEKF3_core.h.

Referenced by FuseBodyVel(), and InitialiseVariables().

◆ consistentMagData

bool NavEKF3_core::consistentMagData
private

Definition at line 928 of file AP_NavEKF3_core.h.

Referenced by calcGpsGoodToAlign(), and readMagData().

◆ core_index

uint8_t NavEKF3_core::core_index
private

Definition at line 361 of file AP_NavEKF3_core.h.

Referenced by effective_magCal(), and setup_core().

◆ DCM

Matrix3f NavEKF3_core::DCM

Definition at line 1219 of file AP_NavEKF3_core.h.

Referenced by FuseMagnetometer().

◆ delAngBiasLearned

bool NavEKF3_core::delAngBiasLearned
private

◆ delAngBodyOF

Vector3f NavEKF3_core::delAngBodyOF
private

Definition at line 1052 of file AP_NavEKF3_core.h.

Referenced by UpdateStrapdownEquationsNED(), and writeOptFlowMeas().

◆ delAngCorrected

Vector3f NavEKF3_core::delAngCorrected
private

Definition at line 953 of file AP_NavEKF3_core.h.

Referenced by readIMUData(), and UpdateStrapdownEquationsNED().

◆ delAngCorrection

Vector3f NavEKF3_core::delAngCorrection
private

Definition at line 921 of file AP_NavEKF3_core.h.

Referenced by calcOutputStates(), and InitialiseVariables().

◆ delTimeOF

float NavEKF3_core::delTimeOF
private

Definition at line 1053 of file AP_NavEKF3_core.h.

Referenced by UpdateStrapdownEquationsNED(), and writeOptFlowMeas().

◆ delVelCorrected

Vector3f NavEKF3_core::delVelCorrected
private

Definition at line 954 of file AP_NavEKF3_core.h.

Referenced by readIMUData(), and UpdateStrapdownEquationsNED().

◆ dt

ftype NavEKF3_core::dt
private

Definition at line 831 of file AP_NavEKF3_core.h.

Referenced by CovariancePrediction(), and InitialiseVariables().

◆ dtEkfAvg

ftype NavEKF3_core::dtEkfAvg
private

◆ dtIMUavg

ftype NavEKF3_core::dtIMUavg
private

◆ earthMagFieldVar

Vector3f NavEKF3_core::earthMagFieldVar
private

Definition at line 956 of file AP_NavEKF3_core.h.

Referenced by SelectMagFusion(), and setWindMagStateLearningMode().

◆ earthRateNED

Vector3f NavEKF3_core::earthRateNED
private

◆ EKF_origin

struct Location NavEKF3_core::EKF_origin
private

◆ ekfGpsRefHgt

double NavEKF3_core::ekfGpsRefHgt
private

◆ ekfInnovationsPass

bool NavEKF3_core::ekfInnovationsPass
private

Definition at line 996 of file AP_NavEKF3_core.h.

Referenced by calcGpsGoodForFlight(), and InitialiseVariables().

◆ ekfOriginHgtVar

float NavEKF3_core::ekfOriginHgtVar
private

◆ ekfStartTime_ms

uint32_t NavEKF3_core::ekfStartTime_ms
private

Definition at line 869 of file AP_NavEKF3_core.h.

Referenced by healthy(), InitialiseVariables(), and readMagData().

◆ expectGndEffectTakeoff

bool NavEKF3_core::expectGndEffectTakeoff
private

◆ expectGndEffectTouchdown

bool NavEKF3_core::expectGndEffectTouchdown
private

◆ faultStatus

struct { ... } NavEKF3_core::faultStatus

◆ fifoIndexDelayed

uint8_t NavEKF3_core::fifoIndexDelayed
private

Definition at line 903 of file AP_NavEKF3_core.h.

◆ fifoIndexNow

uint8_t NavEKF3_core::fifoIndexNow
private

Definition at line 902 of file AP_NavEKF3_core.h.

◆ filterStatus

nav_filter_status NavEKF3_core::filterStatus
private

◆ finalInflightMagInit

bool NavEKF3_core::finalInflightMagInit
private

◆ finalInflightYawInit

bool NavEKF3_core::finalInflightYawInit
private

◆ firstInitTime_ms

uint32_t NavEKF3_core::firstInitTime_ms
private

Definition at line 966 of file AP_NavEKF3_core.h.

Referenced by InitialiseFilterBootstrap(), and NavEKF3_core().

◆ flowDataToFuse

bool NavEKF3_core::flowDataToFuse
private

Definition at line 1013 of file AP_NavEKF3_core.h.

Referenced by SelectFlowFusion().

◆ flowDataValid

bool NavEKF3_core::flowDataValid
private

◆ flowFusionActive

bool NavEKF3_core::flowFusionActive
private

Definition at line 1054 of file AP_NavEKF3_core.h.

Referenced by FuseOptFlow(), InitialiseVariables(), and setAidingMode().

◆ flowGyroBias

Vector2f NavEKF3_core::flowGyroBias
private

Definition at line 1038 of file AP_NavEKF3_core.h.

Referenced by InitialiseVariables(), and writeOptFlowMeas().

◆ flowMeaTime_ms

uint32_t NavEKF3_core::flowMeaTime_ms
private

Definition at line 1020 of file AP_NavEKF3_core.h.

Referenced by InitialiseVariables(), readyToUseOptFlow(), and writeOptFlowMeas().

◆ flowTestRatio

Vector2 NavEKF3_core::flowTestRatio
private

Definition at line 1034 of file AP_NavEKF3_core.h.

Referenced by FuseOptFlow(), and getFlowDebug().

◆ flowValidMeaTime_ms

uint32_t NavEKF3_core::flowValidMeaTime_ms
private

◆ framesSincePredict

uint32_t NavEKF3_core::framesSincePredict
private

Definition at line 949 of file AP_NavEKF3_core.h.

Referenced by getFramesSincePredict(), InitialiseVariables(), and readIMUData().

◆ frontend

NavEKF3* NavEKF3_core::frontend
private

◆ fuseHgtData

bool NavEKF3_core::fuseHgtData
private

Definition at line 843 of file AP_NavEKF3_core.h.

Referenced by FuseVelPosNED(), selectHeightForFusion(), and SelectVelPosFusion().

◆ fuseOptFlowData

bool NavEKF3_core::fuseOptFlowData
private

◆ fusePosData

bool NavEKF3_core::fusePosData
private

Definition at line 842 of file AP_NavEKF3_core.h.

Referenced by FuseVelPosNED(), and SelectVelPosFusion().

◆ fuseVelData

bool NavEKF3_core::fuseVelData
private

Definition at line 841 of file AP_NavEKF3_core.h.

Referenced by FuseVelPosNED(), and SelectVelPosFusion().

◆ fusionHorizonOffset

uint8_t NavEKF3_core::fusionHorizonOffset
private

Definition at line 945 of file AP_NavEKF3_core.h.

◆ gndHgtValidTime_ms

uint32_t NavEKF3_core::gndHgtValidTime_ms
private

◆ gndOffsetValid

bool NavEKF3_core::gndOffsetValid
private

◆ gpsAccuracyGood

bool NavEKF3_core::gpsAccuracyGood
private

◆ gpsCheckStatus

struct { ... } NavEKF3_core::gpsCheckStatus

◆ gpsDataDelayed

gps_elements NavEKF3_core::gpsDataDelayed
private

◆ gpsDataNew

gps_elements NavEKF3_core::gpsDataNew
private

◆ gpsDataToFuse

bool NavEKF3_core::gpsDataToFuse
private

Definition at line 1041 of file AP_NavEKF3_core.h.

Referenced by readyToUseGPS(), selectHeightForFusion(), and SelectVelPosFusion().

◆ gpsDriftNE

float NavEKF3_core::gpsDriftNE
private

Definition at line 990 of file AP_NavEKF3_core.h.

Referenced by calcGpsGoodToAlign(), and InitialiseVariables().

◆ gpsGoodToAlign

bool NavEKF3_core::gpsGoodToAlign
private

Definition at line 926 of file AP_NavEKF3_core.h.

Referenced by InitialiseVariables(), readGpsData(), and readyToUseGPS().

◆ gpsHgtAccuracy

float NavEKF3_core::gpsHgtAccuracy
private

◆ gpsHorizVelFilt

float NavEKF3_core::gpsHorizVelFilt
private

Definition at line 992 of file AP_NavEKF3_core.h.

Referenced by calcGpsGoodToAlign(), and InitialiseVariables().

◆ gpsInhibit

bool NavEKF3_core::gpsInhibit
private

Definition at line 1050 of file AP_NavEKF3_core.h.

Referenced by InitialiseVariables(), readyToUseGPS(), and setInhibitGPS().

◆ gpsloc_prev

struct Location NavEKF3_core::gpsloc_prev
private

Definition at line 988 of file AP_NavEKF3_core.h.

Referenced by calcGpsGoodToAlign(), and InitialiseVariables().

◆ gpsNoiseScaler

float NavEKF3_core::gpsNoiseScaler
private

Definition at line 813 of file AP_NavEKF3_core.h.

Referenced by FuseVelPosNED(), InitialiseVariables(), and readGpsData().

◆ gpsNotAvailable

bool NavEKF3_core::gpsNotAvailable
private

◆ gpsPosAccuracy

float NavEKF3_core::gpsPosAccuracy
private

Definition at line 886 of file AP_NavEKF3_core.h.

Referenced by FuseVelPosNED(), InitialiseVariables(), readGpsData(), and ResetPosition().

◆ gpsSpdAccPass

bool NavEKF3_core::gpsSpdAccPass
private

Definition at line 995 of file AP_NavEKF3_core.h.

Referenced by calcGpsGoodForFlight(), and InitialiseVariables().

◆ gpsSpdAccuracy

float NavEKF3_core::gpsSpdAccuracy
private

◆ gpsVertVelFilt

float NavEKF3_core::gpsVertVelFilt
private

Definition at line 991 of file AP_NavEKF3_core.h.

Referenced by calcGpsGoodToAlign(), and InitialiseVariables().

◆ gpsYawResetRequest

bool NavEKF3_core::gpsYawResetRequest
private

◆ heldVelNE

Vector2f NavEKF3_core::heldVelNE
private

Definition at line 1043 of file AP_NavEKF3_core.h.

Referenced by InitialiseVariables().

◆ hgtHealth

bool NavEKF3_core::hgtHealth
private

Definition at line 802 of file AP_NavEKF3_core.h.

Referenced by FuseVelPosNED().

◆ hgtInnovFiltState

float NavEKF3_core::hgtInnovFiltState
private

Definition at line 946 of file AP_NavEKF3_core.h.

Referenced by FuseVelPosNED(), healthy(), and InitialiseVariables().

◆ hgtMea

float NavEKF3_core::hgtMea
private

◆ hgtRate

ftype NavEKF3_core::hgtRate
private

Definition at line 832 of file AP_NavEKF3_core.h.

Referenced by CovariancePrediction(), and InitialiseVariables().

◆ hgtRetryTime_ms

uint16_t NavEKF3_core::hgtRetryTime_ms
private

Definition at line 858 of file AP_NavEKF3_core.h.

Referenced by selectHeightForFusion().

◆ hgtTestRatio

float NavEKF3_core::hgtTestRatio
private

Definition at line 875 of file AP_NavEKF3_core.h.

Referenced by errorScore(), FuseVelPosNED(), getVariances(), and healthy().

◆ hgtTimeout

bool NavEKF3_core::hgtTimeout
private

◆ imu_buffer_length

uint8_t NavEKF3_core::imu_buffer_length
private

◆ imu_index

uint8_t NavEKF3_core::imu_index
private

◆ imuDataDelayed

imu_elements NavEKF3_core::imuDataDelayed
private

◆ imuDataDownSampledNew

imu_elements NavEKF3_core::imuDataDownSampledNew
private

Definition at line 900 of file AP_NavEKF3_core.h.

Referenced by InitialiseVariables(), readGpsData(), and readIMUData().

◆ imuDataNew

imu_elements NavEKF3_core::imuDataNew
private

Definition at line 899 of file AP_NavEKF3_core.h.

Referenced by calcOutputStates(), readIMUData(), and writeOptFlowMeas().

◆ imuQuatDownSampleNew

Quaternion NavEKF3_core::imuQuatDownSampleNew
private

Definition at line 901 of file AP_NavEKF3_core.h.

Referenced by readIMUData().

◆ imuSampleTime_ms

uint32_t NavEKF3_core::imuSampleTime_ms
private

◆ inFlight

bool NavEKF3_core::inFlight
private

◆ inhibitDelAngBiasStates

bool NavEKF3_core::inhibitDelAngBiasStates
private

◆ inhibitDelVelBiasStates

bool NavEKF3_core::inhibitDelVelBiasStates
private

◆ inhibitGndState

bool NavEKF3_core::inhibitGndState
private

Definition at line 1032 of file AP_NavEKF3_core.h.

Referenced by ConstrainStates(), EstimateTerrainOffset(), and InitialiseVariables().

◆ inhibitMagStates

bool NavEKF3_core::inhibitMagStates
private

◆ inhibitWindStates

bool NavEKF3_core::inhibitWindStates
private

◆ innov

float NavEKF3_core::innov

Definition at line 1135 of file AP_NavEKF3_core.h.

Referenced by CalcRangeBeaconPosDownOffset().

◆ innovationIncrement

float NavEKF3_core::innovationIncrement
private

Definition at line 1005 of file AP_NavEKF3_core.h.

Referenced by InitialiseVariables().

◆ innovBodyVel

Vector3 NavEKF3_core::innovBodyVel
private

Definition at line 1075 of file AP_NavEKF3_core.h.

Referenced by FuseBodyVel(), getBodyFrameOdomDebug(), and InitialiseVariables().

◆ innovMag

Vector3f NavEKF3_core::innovMag
private

Definition at line 844 of file AP_NavEKF3_core.h.

Referenced by FuseMagnetometer(), and getInnovations().

◆ innovOptFlow

Vector2 NavEKF3_core::innovOptFlow
private

Definition at line 1024 of file AP_NavEKF3_core.h.

Referenced by FuseOptFlow(), and getFlowDebug().

◆ innovRng

float NavEKF3_core::innovRng
private

Definition at line 1030 of file AP_NavEKF3_core.h.

Referenced by EstimateTerrainOffset(), and getFlowDebug().

◆ innovRngBcn

float NavEKF3_core::innovRngBcn
private

Definition at line 1099 of file AP_NavEKF3_core.h.

Referenced by FuseRngBcn(), FuseRngBcnStatic(), and InitialiseVariables().

◆ innovVar

float NavEKF3_core::innovVar

Definition at line 1136 of file AP_NavEKF3_core.h.

Referenced by CalcRangeBeaconPosDownOffset().

◆ innovVelPos

Vector6 NavEKF3_core::innovVelPos
private

Definition at line 839 of file AP_NavEKF3_core.h.

Referenced by FuseVelPosNED(), getInnovations(), and healthy().

◆ innovVtas

ftype NavEKF3_core::innovVtas
private

Definition at line 846 of file AP_NavEKF3_core.h.

Referenced by FuseAirspeed(), and getInnovations().

◆ innovYaw

float NavEKF3_core::innovYaw
private

◆ Kfusion

Vector28 NavEKF3_core::Kfusion
private

◆ KH

Matrix24 NavEKF3_core::KH
private

◆ KHP

Matrix24 NavEKF3_core::KHP
private

◆ last_gps_idx

uint8_t NavEKF3_core::last_gps_idx
private

Definition at line 918 of file AP_NavEKF3_core.h.

Referenced by InitialiseVariables(), ResetPosition(), and SelectVelPosFusion().

◆ lastBaroReceived_ms

uint32_t NavEKF3_core::lastBaroReceived_ms
private

Definition at line 857 of file AP_NavEKF3_core.h.

Referenced by InitialiseVariables(), and readBaroData().

◆ lastBeaconIndex

uint8_t NavEKF3_core::lastBeaconIndex
private

Definition at line 1111 of file AP_NavEKF3_core.h.

Referenced by FuseRngBcnStatic(), and InitialiseVariables().

◆ lastbodyVelPassTime_ms

uint32_t NavEKF3_core::lastbodyVelPassTime_ms
private

Definition at line 1072 of file AP_NavEKF3_core.h.

Referenced by InitialiseVariables(), and setAidingMode().

◆ lastDecayTime_ms

uint32_t NavEKF3_core::lastDecayTime_ms
private

Definition at line 872 of file AP_NavEKF3_core.h.

Referenced by InitialiseVariables().

◆ lastGpsAidBadTime_ms

uint32_t NavEKF3_core::lastGpsAidBadTime_ms
private

Definition at line 889 of file AP_NavEKF3_core.h.

Referenced by InitialiseVariables().

◆ lastGpsCheckTime_ms

uint32_t NavEKF3_core::lastGpsCheckTime_ms
private

Definition at line 999 of file AP_NavEKF3_core.h.

Referenced by calcGpsGoodForFlight(), and InitialiseVariables().

◆ lastGpsVelFail_ms

uint32_t NavEKF3_core::lastGpsVelFail_ms
private

◆ lastHealthyMagTime_ms

uint32_t NavEKF3_core::lastHealthyMagTime_ms
private

Definition at line 866 of file AP_NavEKF3_core.h.

Referenced by InitialiseVariables(), readMagData(), and SelectMagFusion().

◆ lastHgtPassTime_ms

uint32_t NavEKF3_core::lastHgtPassTime_ms
private

◆ lastInitFailReport_ms

uint32_t NavEKF3_core::lastInitFailReport_ms
private

Definition at line 967 of file AP_NavEKF3_core.h.

Referenced by NavEKF3_core(), and setup_core().

◆ lastInnovation

float NavEKF3_core::lastInnovation
private

Definition at line 1006 of file AP_NavEKF3_core.h.

Referenced by InitialiseVariables().

◆ lastInnovFailTime_ms

uint32_t NavEKF3_core::lastInnovFailTime_ms
private

Definition at line 1001 of file AP_NavEKF3_core.h.

Referenced by calcGpsGoodForFlight(), and InitialiseVariables().

◆ lastInnovPassTime_ms

uint32_t NavEKF3_core::lastInnovPassTime_ms
private

Definition at line 1000 of file AP_NavEKF3_core.h.

Referenced by calcGpsGoodForFlight(), and InitialiseVariables().

◆ lastKnownPositionNE

Vector2f NavEKF3_core::lastKnownPositionNE
private

◆ lastMagOffsets

Vector3f NavEKF3_core::lastMagOffsets
private

Definition at line 935 of file AP_NavEKF3_core.h.

Referenced by readMagData().

◆ lastMagOffsetsValid

bool NavEKF3_core::lastMagOffsetsValid
private

Definition at line 936 of file AP_NavEKF3_core.h.

Referenced by InitialiseVariables(), and readMagData().

◆ lastMagUpdate_us

uint32_t NavEKF3_core::lastMagUpdate_us
private

Definition at line 852 of file AP_NavEKF3_core.h.

Referenced by InitialiseVariables(), and readMagData().

◆ lastOriginHgtTime_ms

uint32_t NavEKF3_core::lastOriginHgtTime_ms
private

Definition at line 962 of file AP_NavEKF3_core.h.

Referenced by correctEkfOriginHeight().

◆ lastPosPassTime_ms

uint32_t NavEKF3_core::lastPosPassTime_ms
private

◆ lastPosReset_ms

uint32_t NavEKF3_core::lastPosReset_ms
private

◆ lastPosResetD_ms

uint32_t NavEKF3_core::lastPosResetD_ms
private

◆ lastPreAlignGpsCheckTime_ms

uint32_t NavEKF3_core::lastPreAlignGpsCheckTime_ms
private

Definition at line 989 of file AP_NavEKF3_core.h.

Referenced by calcGpsGoodToAlign(), and InitialiseVariables().

◆ lastRngBcnChecked

uint8_t NavEKF3_core::lastRngBcnChecked
private

Definition at line 1106 of file AP_NavEKF3_core.h.

Referenced by InitialiseVariables(), and readRngBcnData().

◆ lastRngBcnPassTime_ms

uint32_t NavEKF3_core::lastRngBcnPassTime_ms
private

Definition at line 1094 of file AP_NavEKF3_core.h.

Referenced by FuseRngBcn(), InitialiseVariables(), ResetPosition(), and setAidingMode().

◆ lastRngMeasTime_ms

uint32_t NavEKF3_core::lastRngMeasTime_ms
private

Definition at line 1063 of file AP_NavEKF3_core.h.

Referenced by InitialiseVariables(), and readRangeFinder().

◆ lastSynthYawTime_ms

uint32_t NavEKF3_core::lastSynthYawTime_ms
private

Definition at line 868 of file AP_NavEKF3_core.h.

Referenced by InitialiseVariables(), and SelectMagFusion().

◆ lastTasPassTime_ms

uint32_t NavEKF3_core::lastTasPassTime_ms
private

Definition at line 862 of file AP_NavEKF3_core.h.

Referenced by FuseAirspeed(), InitialiseVariables(), and setAidingMode().

◆ lastTimeGpsReceived_ms

uint32_t NavEKF3_core::lastTimeGpsReceived_ms
private

◆ lastTimeRngBcn_ms

uint32_t NavEKF3_core::lastTimeRngBcn_ms[10]
private

Definition at line 1100 of file AP_NavEKF3_core.h.

Referenced by InitialiseVariables(), and readRngBcnData().

◆ lastVelPassTime_ms

uint32_t NavEKF3_core::lastVelPassTime_ms
private

◆ lastVelReset_ms

uint32_t NavEKF3_core::lastVelReset_ms
private

Definition at line 940 of file AP_NavEKF3_core.h.

Referenced by getLastVelNorthEastReset(), InitialiseVariables(), and ResetVelocity().

◆ lastYawReset_ms

uint32_t NavEKF3_core::lastYawReset_ms
private

◆ localFilterTimeStep_ms

uint8_t NavEKF3_core::localFilterTimeStep_ms
private

◆ mag_state

struct { ... } NavEKF3_core::mag_state

◆ magD

ftype NavEKF3_core::magD

Definition at line 1214 of file AP_NavEKF3_core.h.

Referenced by FuseMagnetometer().

◆ magDataDelayed

mag_elements NavEKF3_core::magDataDelayed
private

◆ magDataNew

mag_elements NavEKF3_core::magDataNew
private

Definition at line 913 of file AP_NavEKF3_core.h.

Referenced by readMagData().

◆ magDataToFuse

bool NavEKF3_core::magDataToFuse
private

Definition at line 1042 of file AP_NavEKF3_core.h.

Referenced by readMagData(), and SelectMagFusion().

◆ magE

ftype NavEKF3_core::magE

Definition at line 1213 of file AP_NavEKF3_core.h.

Referenced by FuseDeclination(), and FuseMagnetometer().

◆ magFieldLearned

bool NavEKF3_core::magFieldLearned
private

◆ magFusePerformed

bool NavEKF3_core::magFusePerformed
private

◆ magFuseRequired

bool NavEKF3_core::magFuseRequired
private

Definition at line 849 of file AP_NavEKF3_core.h.

Referenced by FuseMagnetometer().

◆ magHealth

bool NavEKF3_core::magHealth
private

Definition at line 803 of file AP_NavEKF3_core.h.

Referenced by fuseEulerYaw(), FuseMagnetometer(), and SelectMagFusion().

◆ magN

ftype NavEKF3_core::magN

Definition at line 1212 of file AP_NavEKF3_core.h.

Referenced by FuseDeclination(), and FuseMagnetometer().

◆ MagPred

Vector3f NavEKF3_core::MagPred

Definition at line 1220 of file AP_NavEKF3_core.h.

Referenced by FuseMagnetometer().

◆ magSelectIndex

uint8_t NavEKF3_core::magSelectIndex
private

◆ magStateInitComplete

bool NavEKF3_core::magStateInitComplete
private

◆ magStateResetRequest

bool NavEKF3_core::magStateResetRequest
private

◆ magStoreIndex

uint8_t NavEKF3_core::magStoreIndex
private

Definition at line 915 of file AP_NavEKF3_core.h.

Referenced by InitialiseVariables().

◆ magTestRatio

Vector3f NavEKF3_core::magTestRatio
private

◆ magTimeout

bool NavEKF3_core::magTimeout
private

◆ magXbias

ftype NavEKF3_core::magXbias

Definition at line 1215 of file AP_NavEKF3_core.h.

Referenced by FuseMagnetometer().

◆ magYawResetRequest

bool NavEKF3_core::magYawResetRequest
private

◆ magYawResetTimer_ms

uint32_t NavEKF3_core::magYawResetTimer_ms
private

Definition at line 927 of file AP_NavEKF3_core.h.

Referenced by calcGpsGoodToAlign(), and InitialiseVariables().

◆ magYbias

ftype NavEKF3_core::magYbias

Definition at line 1216 of file AP_NavEKF3_core.h.

Referenced by FuseMagnetometer().

◆ magZbias

ftype NavEKF3_core::magZbias

Definition at line 1217 of file AP_NavEKF3_core.h.

Referenced by FuseMagnetometer().

◆ manoeuvring

bool NavEKF3_core::manoeuvring
private

Definition at line 837 of file AP_NavEKF3_core.h.

Referenced by InitialiseVariables(), and setWindMagStateLearningMode().

◆ maxBcnPosD

float NavEKF3_core::maxBcnPosD
private

◆ maxOffsetStateChangeFilt

float NavEKF3_core::maxOffsetStateChangeFilt
private

Definition at line 1122 of file AP_NavEKF3_core.h.

Referenced by CalcRangeBeaconPosDownOffset(), and InitialiseVariables().

◆ meaHgtAtTakeOff

float NavEKF3_core::meaHgtAtTakeOff
private

Definition at line 1154 of file AP_NavEKF3_core.h.

Referenced by readBaroData(), selectHeightForFusion(), and setAidingMode().

◆ minBcnPosD

float NavEKF3_core::minBcnPosD
private

◆ minOffsetStateChangeFilt

float NavEKF3_core::minOffsetStateChangeFilt
private

Definition at line 1126 of file AP_NavEKF3_core.h.

Referenced by CalcRangeBeaconPosDownOffset(), and InitialiseVariables().

◆ motorsArmed

bool NavEKF3_core::motorsArmed
private

◆ N_beacons

uint8_t NavEKF3_core::N_beacons
private

Definition at line 1115 of file AP_NavEKF3_core.h.

Referenced by getRangeBeaconDebug(), InitialiseVariables(), and readRngBcnData().

◆ nextP

Matrix24 NavEKF3_core::nextP
private

Definition at line 870 of file AP_NavEKF3_core.h.

Referenced by InitialiseVariables().

◆ numBcnMeas

uint8_t NavEKF3_core::numBcnMeas
private

Definition at line 1113 of file AP_NavEKF3_core.h.

Referenced by FuseRngBcnStatic(), and InitialiseVariables().

◆ obs_buffer_length

uint8_t NavEKF3_core::obs_buffer_length
private

Definition at line 363 of file AP_NavEKF3_core.h.

Referenced by setup_core().

◆ obsIndex

uint8_t NavEKF3_core::obsIndex

Definition at line 1218 of file AP_NavEKF3_core.h.

Referenced by FuseBodyVel(), FuseMagnetometer(), FuseOptFlow(), and FuseVelPosNED().

◆ ofDataDelayed

of_elements NavEKF3_core::ofDataDelayed
private

Definition at line 1011 of file AP_NavEKF3_core.h.

Referenced by EstimateTerrainOffset(), FuseOptFlow(), and SelectFlowFusion().

◆ ofDataNew

of_elements NavEKF3_core::ofDataNew
private

Definition at line 1010 of file AP_NavEKF3_core.h.

Referenced by writeOptFlowMeas().

◆ ofStoreIndex

uint8_t NavEKF3_core::ofStoreIndex
private

Definition at line 1012 of file AP_NavEKF3_core.h.

Referenced by InitialiseVariables().

◆ onGround

bool NavEKF3_core::onGround
private

◆ optFlowFusionDelayed

bool NavEKF3_core::optFlowFusionDelayed
private

Definition at line 932 of file AP_NavEKF3_core.h.

Referenced by InitialiseVariables(), and SelectFlowFusion().

◆ outputDataDelayed

output_elements NavEKF3_core::outputDataDelayed
private

◆ outputDataNew

output_elements NavEKF3_core::outputDataNew
private

◆ outputTrackError

Vector3f NavEKF3_core::outputTrackError
private

Definition at line 963 of file AP_NavEKF3_core.h.

Referenced by calcOutputStates(), and getOutputTrackingError().

◆ P

Matrix24 NavEKF3_core::P
private

◆ Popt

float NavEKF3_core::Popt
private

◆ posDown

float NavEKF3_core::posDown
private

Definition at line 985 of file AP_NavEKF3_core.h.

Referenced by InitialiseVariables(), and StoreOutputReset().

◆ posDownAtLastMagReset

float NavEKF3_core::posDownAtLastMagReset
private

◆ posDownAtTakeoff

float NavEKF3_core::posDownAtTakeoff
private

Definition at line 890 of file AP_NavEKF3_core.h.

Referenced by controlMagYawReset(), and detectFlight().

◆ posDownDerivative

float NavEKF3_core::posDownDerivative
private

Definition at line 984 of file AP_NavEKF3_core.h.

Referenced by getPosDownDerivative(), InitialiseVariables(), and StoreOutputReset().

◆ posDownObsNoise

float NavEKF3_core::posDownObsNoise
private

Definition at line 952 of file AP_NavEKF3_core.h.

Referenced by FuseVelPosNED(), ResetHeight(), and selectHeightForFusion().

◆ posErrintegral

Vector3f NavEKF3_core::posErrintegral
private

Definition at line 923 of file AP_NavEKF3_core.h.

Referenced by calcOutputStates(), and InitialiseVariables().

◆ posHealth

bool NavEKF3_core::posHealth
private

Definition at line 801 of file AP_NavEKF3_core.h.

Referenced by FuseVelPosNED().

◆ posOffsetNED

Vector3f NavEKF3_core::posOffsetNED
private

Definition at line 965 of file AP_NavEKF3_core.h.

Referenced by calcOutputStates(), getHAGL(), getPosD(), getPosNE(), and InitialiseVariables().

◆ posResetD

float NavEKF3_core::posResetD
private

◆ posResetNE

Vector2f NavEKF3_core::posResetNE
private

◆ posResetSource

resetDataSource NavEKF3_core::posResetSource
private

◆ posTestRatio

float NavEKF3_core::posTestRatio
private

◆ posTimeout

bool NavEKF3_core::posTimeout
private

◆ posVelFusionDelayed

bool NavEKF3_core::posVelFusionDelayed
private

Definition at line 931 of file AP_NavEKF3_core.h.

Referenced by InitialiseVariables(), and SelectVelPosFusion().

◆ prearm_fail_string

char NavEKF3_core::prearm_fail_string[40]
private

Definition at line 1226 of file AP_NavEKF3_core.h.

Referenced by calcGpsGoodToAlign(), and prearm_failure_reason().

◆ prevBetaStep_ms

uint32_t NavEKF3_core::prevBetaStep_ms
private

Definition at line 851 of file AP_NavEKF3_core.h.

Referenced by InitialiseVariables(), and SelectBetaFusion().

◆ prevBodyVelFuseTime_ms

uint32_t NavEKF3_core::prevBodyVelFuseTime_ms
private

◆ prevFlowFuseTime_ms

uint32_t NavEKF3_core::prevFlowFuseTime_ms
private

Definition at line 1033 of file AP_NavEKF3_core.h.

Referenced by FuseOptFlow(), InitialiseVariables(), and setAidingMode().

◆ prevInFlight

bool NavEKF3_core::prevInFlight
private

Definition at line 836 of file AP_NavEKF3_core.h.

Referenced by detectFlight(), and InitialiseVariables().

◆ prevMotorsArmed

bool NavEKF3_core::prevMotorsArmed
private

Definition at line 930 of file AP_NavEKF3_core.h.

Referenced by controlFilterModes(), and InitialiseVariables().

◆ prevOnGround

bool NavEKF3_core::prevOnGround
private

Definition at line 834 of file AP_NavEKF3_core.h.

Referenced by detectFlight(), and InitialiseVariables().

◆ prevPosE

float NavEKF3_core::prevPosE
private

Definition at line 1028 of file AP_NavEKF3_core.h.

Referenced by EstimateTerrainOffset(), and InitialiseVariables().

◆ prevPosN

float NavEKF3_core::prevPosN
private

Definition at line 1027 of file AP_NavEKF3_core.h.

Referenced by EstimateTerrainOffset(), and InitialiseVariables().

◆ prevQuatMagReset

Quaternion NavEKF3_core::prevQuatMagReset
private

Definition at line 944 of file AP_NavEKF3_core.h.

Referenced by controlMagYawReset().

◆ prevTasStep_ms

uint32_t NavEKF3_core::prevTasStep_ms
private

Definition at line 850 of file AP_NavEKF3_core.h.

Referenced by InitialiseVariables(), and SelectTasFusion().

◆ prevTnb

Matrix3f NavEKF3_core::prevTnb
private

◆ PV_AidingMode

AidingMode NavEKF3_core::PV_AidingMode
private

◆ PV_AidingModePrev

AidingMode NavEKF3_core::PV_AidingModePrev
private

Definition at line 1049 of file AP_NavEKF3_core.h.

Referenced by InitialiseVariables(), and setAidingMode().

◆ q0

ftype NavEKF3_core::q0

◆ q1

ftype NavEKF3_core::q1

◆ q2

ftype NavEKF3_core::q2

◆ q3

ftype NavEKF3_core::q3

◆ quatAtLastMagReset

Quaternion NavEKF3_core::quatAtLastMagReset
private

◆ R_LOS

float NavEKF3_core::R_LOS
private

Definition at line 1036 of file AP_NavEKF3_core.h.

Referenced by EstimateTerrainOffset(), FuseOptFlow(), and SelectFlowFusion().

◆ R_MAG

ftype NavEKF3_core::R_MAG

Definition at line 1221 of file AP_NavEKF3_core.h.

Referenced by FuseMagnetometer().

◆ rangeDataDelayed

range_elements NavEKF3_core::rangeDataDelayed
private

Definition at line 908 of file AP_NavEKF3_core.h.

Referenced by EstimateTerrainOffset(), getFlowDebug(), and selectHeightForFusion().

◆ rangeDataNew

range_elements NavEKF3_core::rangeDataNew
private

Definition at line 907 of file AP_NavEKF3_core.h.

Referenced by detectFlight(), detectOptFlowTakeoff(), and readRangeFinder().

◆ rangeDataToFuse

bool NavEKF3_core::rangeDataToFuse
private

◆ rangeStoreIndex

uint8_t NavEKF3_core::rangeStoreIndex
private

Definition at line 909 of file AP_NavEKF3_core.h.

Referenced by InitialiseVariables().

◆ receiverPos

Vector3f NavEKF3_core::receiverPos
private

◆ receiverPosCov

float NavEKF3_core::receiverPosCov[3][3]
private

◆ rng

float NavEKF3_core::rng

Definition at line 1134 of file AP_NavEKF3_core.h.

◆ rngAtStartOfFlight

float NavEKF3_core::rngAtStartOfFlight
private

Definition at line 1146 of file AP_NavEKF3_core.h.

Referenced by detectFlight(), and detectOptFlowTakeoff().

◆ rngBcnAlignmentCompleted

bool NavEKF3_core::rngBcnAlignmentCompleted
private

◆ rngBcnAlignmentStarted

bool NavEKF3_core::rngBcnAlignmentStarted
private

Definition at line 1109 of file AP_NavEKF3_core.h.

Referenced by FuseRngBcnStatic(), getPosNE(), and InitialiseVariables().

◆ rngBcnDataDelayed

rng_bcn_elements NavEKF3_core::rngBcnDataDelayed
private

◆ rngBcnDataNew

rng_bcn_elements NavEKF3_core::rngBcnDataNew
private

Definition at line 1091 of file AP_NavEKF3_core.h.

Referenced by InitialiseVariables(), and readRngBcnData().

◆ rngBcnDataToFuse

bool NavEKF3_core::rngBcnDataToFuse
private

◆ rngBcnFuseDataReportIndex

uint8_t NavEKF3_core::rngBcnFuseDataReportIndex
private

Definition at line 1132 of file AP_NavEKF3_core.h.

Referenced by getRangeBeaconDebug(), and InitialiseVariables().

◆ rngBcnFusionReport

struct { ... } NavEKF3_core::rngBcnFusionReport[10]

◆ rngBcnGoodToAlign

bool NavEKF3_core::rngBcnGoodToAlign
private

Definition at line 1105 of file AP_NavEKF3_core.h.

Referenced by InitialiseVariables(), readRngBcnData(), and selectHeightForFusion().

◆ rngBcnHealth

bool NavEKF3_core::rngBcnHealth
private

Definition at line 1096 of file AP_NavEKF3_core.h.

Referenced by FuseRngBcn(), FuseRngBcnStatic(), and InitialiseVariables().

◆ rngBcnLast3DmeasTime_ms

uint32_t NavEKF3_core::rngBcnLast3DmeasTime_ms
private

Definition at line 1104 of file AP_NavEKF3_core.h.

Referenced by InitialiseVariables(), readRngBcnData(), and ResetPosition().

◆ rngBcnPosSum

Vector3f NavEKF3_core::rngBcnPosSum
private

Definition at line 1112 of file AP_NavEKF3_core.h.

Referenced by FuseRngBcnStatic(), and InitialiseVariables().

◆ rngBcnStoreIndex

uint8_t NavEKF3_core::rngBcnStoreIndex
private

Definition at line 1093 of file AP_NavEKF3_core.h.

Referenced by InitialiseVariables().

◆ rngBcnTestRatio

float NavEKF3_core::rngBcnTestRatio
private

Definition at line 1095 of file AP_NavEKF3_core.h.

Referenced by FuseRngBcn(), FuseRngBcnStatic(), and InitialiseVariables().

◆ rngBcnTimeout

bool NavEKF3_core::rngBcnTimeout
private

Definition at line 1097 of file AP_NavEKF3_core.h.

Referenced by InitialiseVariables(), ResetPosition(), and setAidingMode().

◆ rngMeasIndex

uint8_t NavEKF3_core::rngMeasIndex[2]
private

Definition at line 1064 of file AP_NavEKF3_core.h.

Referenced by InitialiseVariables(), and readRangeFinder().

◆ rngOnGnd

float NavEKF3_core::rngOnGnd
private

◆ rngSum

float NavEKF3_core::rngSum
private

Definition at line 1114 of file AP_NavEKF3_core.h.

Referenced by FuseRngBcnStatic(), and InitialiseVariables().

◆ rngValidMeaTime_ms

uint32_t NavEKF3_core::rngValidMeaTime_ms
private

Definition at line 1019 of file AP_NavEKF3_core.h.

Referenced by InitialiseVariables(), readRangeFinder(), and selectHeightForFusion().

◆ runUpdates

bool NavEKF3_core::runUpdates
private

◆ sAccFilterState1

float NavEKF3_core::sAccFilterState1
private

Definition at line 997 of file AP_NavEKF3_core.h.

Referenced by calcGpsGoodForFlight(), and InitialiseVariables().

◆ sAccFilterState2

float NavEKF3_core::sAccFilterState2
private

Definition at line 998 of file AP_NavEKF3_core.h.

Referenced by calcGpsGoodForFlight(), and InitialiseVariables().

◆ secondLastGpsTime_ms

uint32_t NavEKF3_core::secondLastGpsTime_ms
private

Definition at line 865 of file AP_NavEKF3_core.h.

Referenced by InitialiseVariables(), and readGpsData().

◆ SH_MAG

Vector9 NavEKF3_core::SH_MAG

Definition at line 1222 of file AP_NavEKF3_core.h.

Referenced by FuseMagnetometer().

◆ sideSlipFusionDelayed

bool NavEKF3_core::sideSlipFusionDelayed
private

Definition at line 934 of file AP_NavEKF3_core.h.

Referenced by InitialiseVariables(), and SelectBetaFusion().

◆ startPredictEnabled

bool NavEKF3_core::startPredictEnabled
private

Definition at line 950 of file AP_NavEKF3_core.h.

Referenced by readIMUData(), and UpdateFilter().

◆ stateIndexLim

uint8_t NavEKF3_core::stateIndexLim
private

◆ statesArray

Vector24 NavEKF3_core::statesArray
private

◆ statesInitialised

bool NavEKF3_core::statesInitialised
private

◆ stateStruct

struct NavEKF3_core::state_elements & NavEKF3_core::stateStruct
private

◆ storedBaro

obs_ring_buffer_t<baro_elements> NavEKF3_core::storedBaro
private

◆ storedBodyOdm

obs_ring_buffer_t<vel_odm_elements> NavEKF3_core::storedBodyOdm
private

◆ storedGPS

obs_ring_buffer_t<gps_elements> NavEKF3_core::storedGPS
private

◆ storedIMU

imu_ring_buffer_t<imu_elements> NavEKF3_core::storedIMU
private

◆ storedMag

obs_ring_buffer_t<mag_elements> NavEKF3_core::storedMag
private

Definition at line 820 of file AP_NavEKF3_core.h.

Referenced by InitialiseVariables(), readMagData(), SelectMagFusion(), and setup_core().

◆ storedOF

obs_ring_buffer_t<of_elements> NavEKF3_core::storedOF
private

Definition at line 1009 of file AP_NavEKF3_core.h.

Referenced by SelectFlowFusion(), setup_core(), and writeOptFlowMeas().

◆ storedOutput

imu_ring_buffer_t<output_elements> NavEKF3_core::storedOutput
private

◆ storedRange

obs_ring_buffer_t<range_elements> NavEKF3_core::storedRange
private

◆ storedRangeBeacon

obs_ring_buffer_t<rng_bcn_elements> NavEKF3_core::storedRangeBeacon
private

Definition at line 1090 of file AP_NavEKF3_core.h.

Referenced by InitialiseVariables(), readRngBcnData(), and setup_core().

◆ storedRngMeas

float NavEKF3_core::storedRngMeas[2][3]
private

Definition at line 1061 of file AP_NavEKF3_core.h.

Referenced by InitialiseVariables(), and readRangeFinder().

◆ storedRngMeasTime_ms

uint32_t NavEKF3_core::storedRngMeasTime_ms[2][3]
private

Definition at line 1062 of file AP_NavEKF3_core.h.

Referenced by InitialiseVariables(), and readRangeFinder().

◆ storedTAS

obs_ring_buffer_t<tas_elements> NavEKF3_core::storedTAS
private

Definition at line 822 of file AP_NavEKF3_core.h.

Referenced by InitialiseVariables(), readAirSpdData(), and setup_core().

◆ storedWheelOdm

obs_ring_buffer_t<wheel_odm_elements> NavEKF3_core::storedWheelOdm
private

◆ takeOffDetected

bool NavEKF3_core::takeOffDetected
private

◆ takeoffExpectedSet_ms

uint32_t NavEKF3_core::takeoffExpectedSet_ms
private

Definition at line 1151 of file AP_NavEKF3_core.h.

Referenced by getTakeoffExpected(), InitialiseVariables(), and setTakeoffExpected().

◆ tasDataDelayed

tas_elements NavEKF3_core::tasDataDelayed
private

Definition at line 911 of file AP_NavEKF3_core.h.

Referenced by FuseAirspeed(), readAirSpdData(), and setWindMagStateLearningMode().

◆ tasDataNew

tas_elements NavEKF3_core::tasDataNew
private

Definition at line 910 of file AP_NavEKF3_core.h.

Referenced by readAirSpdData(), and SelectTasFusion().

◆ tasDataToFuse

bool NavEKF3_core::tasDataToFuse
private

Definition at line 856 of file AP_NavEKF3_core.h.

Referenced by readAirSpdData(), and SelectTasFusion().

◆ tasHealth

bool NavEKF3_core::tasHealth
private

Definition at line 804 of file AP_NavEKF3_core.h.

Referenced by FuseAirspeed().

◆ tasStoreIndex

uint8_t NavEKF3_core::tasStoreIndex
private

Definition at line 912 of file AP_NavEKF3_core.h.

Referenced by InitialiseVariables().

◆ tasTestRatio

float NavEKF3_core::tasTestRatio
private

Definition at line 877 of file AP_NavEKF3_core.h.

Referenced by FuseAirspeed(), and getVariances().

◆ tasTimeout

bool NavEKF3_core::tasTimeout
private

◆ Tbn_flow

Matrix3f NavEKF3_core::Tbn_flow
private

Definition at line 1022 of file AP_NavEKF3_core.h.

Referenced by writeOptFlowMeas().

◆ terrainHgtStable

bool NavEKF3_core::terrainHgtStable
private

◆ terrainHgtStableSet_ms

uint32_t NavEKF3_core::terrainHgtStableSet_ms
private

Definition at line 1066 of file AP_NavEKF3_core.h.

Referenced by InitialiseVariables(), and setTerrainHgtStable().

◆ terrainState

float NavEKF3_core::terrainState
private

◆ testRatio

float NavEKF3_core::testRatio

Definition at line 1137 of file AP_NavEKF3_core.h.

◆ tiltAlignComplete

bool NavEKF3_core::tiltAlignComplete
private

◆ timeAtArming_ms

uint32_t NavEKF3_core::timeAtArming_ms
private

Definition at line 1147 of file AP_NavEKF3_core.h.

Referenced by controlFilterModes(), and detectOptFlowTakeoff().

◆ timeAtLastAuxEKF_ms

uint32_t NavEKF3_core::timeAtLastAuxEKF_ms
private

Definition at line 864 of file AP_NavEKF3_core.h.

Referenced by EstimateTerrainOffset(), and InitialiseVariables().

◆ timeTasReceived_ms

uint32_t NavEKF3_core::timeTasReceived_ms
private

Definition at line 925 of file AP_NavEKF3_core.h.

Referenced by InitialiseVariables(), and readAirSpdData().

◆ timing

struct ekf_timing NavEKF3_core::timing
private

Definition at line 1241 of file AP_NavEKF3_core.h.

Referenced by getIMUIndex(), getTimingStatistics(), and updateTimingStatistics().

◆ touchdownExpectedSet_ms

uint32_t NavEKF3_core::touchdownExpectedSet_ms
private

◆ useGpsVertVel

bool NavEKF3_core::useGpsVertVel
private

◆ usingMinHypothesis

bool NavEKF3_core::usingMinHypothesis
private

Definition at line 1118 of file AP_NavEKF3_core.h.

Referenced by CalcRangeBeaconPosDownOffset().

◆ usingWheelSensors

bool NavEKF3_core::usingWheelSensors
private

Definition at line 1083 of file AP_NavEKF3_core.h.

Referenced by InitialiseVariables(), and SelectBodyOdomFusion().

◆ validOrigin

bool NavEKF3_core::validOrigin
private

◆ varInnovBodyVel

Vector3 NavEKF3_core::varInnovBodyVel
private

Definition at line 1074 of file AP_NavEKF3_core.h.

Referenced by FuseBodyVel(), getBodyFrameOdomDebug(), and InitialiseVariables().

◆ varInnovMag

Vector3f NavEKF3_core::varInnovMag
private

Definition at line 845 of file AP_NavEKF3_core.h.

Referenced by FuseMagnetometer().

◆ varInnovOptFlow

Vector2 NavEKF3_core::varInnovOptFlow
private

Definition at line 1023 of file AP_NavEKF3_core.h.

Referenced by FuseOptFlow().

◆ varInnovRng

float NavEKF3_core::varInnovRng
private

Definition at line 1029 of file AP_NavEKF3_core.h.

Referenced by EstimateTerrainOffset().

◆ varInnovRngBcn

float NavEKF3_core::varInnovRngBcn
private

Definition at line 1098 of file AP_NavEKF3_core.h.

Referenced by FuseRngBcn(), FuseRngBcnStatic(), and InitialiseVariables().

◆ varInnovVelPos

Vector6 NavEKF3_core::varInnovVelPos
private

Definition at line 840 of file AP_NavEKF3_core.h.

Referenced by FuseVelPosNED().

◆ varInnovVtas

ftype NavEKF3_core::varInnovVtas
private

Definition at line 847 of file AP_NavEKF3_core.h.

Referenced by FuseAirspeed().

◆ velDotNED

Vector3f NavEKF3_core::velDotNED
private

Definition at line 853 of file AP_NavEKF3_core.h.

Referenced by getAccelNED(), and UpdateStrapdownEquationsNED().

◆ velDotNEDfilt

Vector3f NavEKF3_core::velDotNEDfilt
private

Definition at line 854 of file AP_NavEKF3_core.h.

Referenced by InitialiseVariables(), and UpdateStrapdownEquationsNED().

◆ velErrintegral

Vector3f NavEKF3_core::velErrintegral
private

Definition at line 922 of file AP_NavEKF3_core.h.

Referenced by calcOutputStates(), and InitialiseVariables().

◆ velHealth

bool NavEKF3_core::velHealth
private

Definition at line 800 of file AP_NavEKF3_core.h.

Referenced by FuseVelPosNED().

◆ velOffsetNED

Vector3f NavEKF3_core::velOffsetNED
private

◆ velResetNE

Vector2f NavEKF3_core::velResetNE
private

Definition at line 939 of file AP_NavEKF3_core.h.

Referenced by getLastVelNorthEastReset(), InitialiseVariables(), and ResetVelocity().

◆ velResetSource

resetDataSource NavEKF3_core::velResetSource
private

◆ velTestRatio

float NavEKF3_core::velTestRatio
private

◆ velTimeout

bool NavEKF3_core::velTimeout
private

◆ wheelOdmDataDelayed

wheel_odm_elements NavEKF3_core::wheelOdmDataDelayed
private

Definition at line 1086 of file AP_NavEKF3_core.h.

Referenced by getBodyFrameOdomDebug(), and SelectBodyOdomFusion().

◆ wheelOdmDataNew

wheel_odm_elements NavEKF3_core::wheelOdmDataNew
private

Definition at line 1085 of file AP_NavEKF3_core.h.

Referenced by writeWheelOdom().

◆ wheelOdmMeasTime_ms

uint32_t NavEKF3_core::wheelOdmMeasTime_ms
private

Definition at line 1082 of file AP_NavEKF3_core.h.

Referenced by InitialiseVariables(), readyToUseBodyOdm(), and writeWheelOdom().

◆ yawAlignComplete

bool NavEKF3_core::yawAlignComplete
private

◆ yawInnovAtLastMagReset

float NavEKF3_core::yawInnovAtLastMagReset
private

◆ yawResetAngle

float NavEKF3_core::yawResetAngle
private

◆ yawTestRatio

float NavEKF3_core::yawTestRatio
private

Definition at line 943 of file AP_NavEKF3_core.h.

Referenced by calcGpsGoodToAlign(), fuseEulerYaw(), getVariances(), and SelectMagFusion().


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