23 #pragma GCC optimize("O3") 25 #define EK2_DISABLE_INTERRUPTS 0 35 #define MASK_GPS_NSATS (1<<0) 36 #define MASK_GPS_HDOP (1<<1) 37 #define MASK_GPS_SPD_ERR (1<<2) 38 #define MASK_GPS_POS_ERR (1<<3) 39 #define MASK_GPS_YAW_ERR (1<<4) 40 #define MASK_GPS_POS_DRIFT (1<<5) 41 #define MASK_GPS_VERT_SPD (1<<6) 42 #define MASK_GPS_HORIZ_SPD (1<<7) 45 #define HGT_SOURCE_BARO 0 46 #define HGT_SOURCE_RNG 1 47 #define HGT_SOURCE_GPS 2 48 #define HGT_SOURCE_BCN 3 49 #define HGT_SOURCE_EV 4 52 #define EKF_TARGET_DT 0.01f 55 #define EKF2_MAG_FINAL_RESET_ALT 2.5f 91 bool getPosD(
float &posD)
const;
173 bool getHAGL(
float &HAGL)
const;
204 void getFlowDebug(
float &varFlow,
float &gndOffset,
float &flowInnovX,
float &flowInnovY,
float &auxInnov,
float &HAGL,
float &rngInnov,
float &
range,
float &gndOffsetErr)
const;
332 #if MATH_CHECK_INDEXES 357 typedef ftype Vector2[2];
358 typedef ftype Vector3[3];
359 typedef ftype Vector4[4];
360 typedef ftype Vector5[5];
361 typedef ftype Vector6[6];
362 typedef ftype Vector7[7];
363 typedef ftype Vector8[8];
364 typedef ftype Vector9[9];
365 typedef ftype Vector10[10];
366 typedef ftype Vector11[11];
367 typedef ftype Vector13[13];
368 typedef ftype Vector14[14];
369 typedef ftype Vector15[15];
370 typedef ftype Vector22[22];
371 typedef ftype Vector23[23];
372 typedef ftype Vector24[24];
373 typedef ftype Vector25[25];
374 typedef ftype Vector28[28];
375 typedef ftype Matrix3[3][3];
376 typedef ftype Matrix24[24][24];
377 typedef ftype Matrix34_50[34][50];
378 typedef uint32_t Vector_u32_50[50];
514 void zeroRows(Matrix24 &covMat, uint8_t first, uint8_t last);
517 void zeroCols(Matrix24 &covMat, uint8_t first, uint8_t last);
void calcFiltBaroOffset()
gps_elements gpsDataDelayed
uint32_t lastVelPassTime_ms
uint8_t effective_magCal(void) const
void correctDeltaAngle(Vector3f &delAng, float delAngDT)
void calcIMU_Weighting(float K1, float K2)
struct Location gpsloc_prev
uint32_t lastBaroReceived_ms
obs_ring_buffer_t< gps_elements > storedGPS
uint32_t getLastPosDownReset(float &posD) const
void controlMagYawReset()
uint32_t extNavMeasTime_ms
void zeroCols(Matrix24 &covMat, uint8_t first, uint8_t last)
Quaternion quatAtLastMagReset
void getAccelZBias(float &zbias) const
imu_ring_buffer_t< output_elements > storedOutput
void CalcRangeBeaconPosDownOffset(float obsVar, Vector3f &vehiclePosNED, bool aligning)
uint32_t Vector_u32_50[50]
bool extNavYawResetRequest
void getWind(Vector3f &wind) const
bool getLLH(struct Location &loc) const
char prearm_fail_string[40]
AP_HAL::Util::perf_counter_t _perf_FuseSideslip
Quaternion prevQuatMagReset
void InitialiseVariables()
void UpdateStrapdownEquationsNED()
void getEkfControlLimits(float &ekfGndSpdLimit, float &ekfNavVelGainScaler) const
uint32_t getLastPosNorthEastReset(Vector2f &pos) const
baro_elements baroDataNew
mag_elements magDataDelayed
output_elements outputDataNew
bool getRangeBeaconDebug(uint8_t &ID, float &rng, float &innov, float &innovVar, float &testRatio, Vector3f &beaconPosNED, float &offsetHigh, float &offsetLow)
bool assume_zero_sideslip(void) const
void checkDivergence(void)
ftype Matrix34_50[34][50]
float yawInnovAtLastMagReset
obs_ring_buffer_t< range_elements > storedRange
bool getTakeoffExpected()
uint32_t lastRngMeasTime_ms
ext_nav_elements extNavDataNew
struct NavEKF2_core::@147 mag_state
void getRotationBodyToNED(Matrix3f &mat) const
void getTimingStatistics(struct ekf_timing &timing)
const char * prearm_failure_reason(void) const
void zeroRows(Matrix24 &covMat, uint8_t first, uint8_t last)
void CovariancePrediction()
bool finalInflightMagInit
float beaconVehiclePosErr
uint8_t fusionHorizonOffset
void getFilterFaults(uint16_t &faults) const
bool getHeightControlLimit(float &height) const
uint32_t magYawResetTimer_ms
void updateFilterStatus(void)
float storedRngMeas[2][3]
void getVelNED(Vector3f &vel) const
uint32_t lastDecayTime_ms
bool setup_core(NavEKF2 *_frontend, uint8_t _imu_index, uint8_t _core_index)
bool optFlowFusionDelayed
uint32_t lastHgtPassTime_ms
bool getPosNE(Vector2f &posNE) const
bool rngBcnAlignmentStarted
void EstimateTerrainOffset()
uint32_t lastTimeGpsReceived_ms
Quaternion calcQuatAndFieldStates(float roll, float pitch)
struct NavEKF2_core::state_elements & stateStruct
uint32_t timeAtLastAuxEKF_ms
uint32_t lastGpsVelFail_ms
uint32_t touchdownExpectedSet_ms
uint32_t takeoffExpectedSet_ms
uint32_t imuSampleTime_ms
output_elements outputDataDelayed
bool InitialiseFilterBootstrap(void)
obs_ring_buffer_t< tas_elements > storedTAS
uint32_t lastInnovFailTime_ms
uint32_t lastInnovPassTime_ms
void quat2Tbn(Matrix3f &Tbn, const Quaternion &quat) const
void getFilterGpsStatus(nav_gps_status &status) const
imu_elements imuDataDelayed
uint32_t lastPreAlignGpsCheckTime_ms
uint8_t setInhibitGPS(void)
void getMagNED(Vector3f &magNED) const
uint32_t framesSincePredict
Vector3f earthMagFieldVar
bool readyToUseGPS(void) const
void getAccelNED(Vector3f &accelNED) const
void setTakeoffExpected(bool val)
void send_status_report(mavlink_channel_t chan)
bool readyToUseRangeBeacon(void) const
baro_elements baroDataDelayed
float receiverPosCov[3][3]
bool resetHeightDatum(void)
uint32_t getLastYawResetAngle(float &yawAng) const
uint32_t airborneDetectTime_ms
bool readDeltaAngle(uint8_t ins_index, Vector3f &dAng, float &dAng_dt)
AP_HAL::Util::perf_counter_t _perf_FuseAirspeed
uint32_t secondLastGpsTime_ms
void SelectVelPosFusion()
struct NavEKF2_core::@145 faultStatus
uint8_t rngBcnFuseDataReportIndex
bool optFlowDataPresent(void) const
bool readyToUseExtNav(void) const
uint32_t lastHealthyMagTime_ms
void getMagXYZ(Vector3f &magXYZ) const
const Vector3f * body_offset
uint32_t prevFlowFuseTime_ms
void getGyroBias(Vector3f &gyroBias) const
bool getTouchdownExpected()
struct NavEKF2_core::@146 gpsCheckStatus
const Vector3f * body_offset
uint8_t getIMUIndex(void) const
void correctEkfOriginHeight()
float innovationIncrement
bool useAirspeed(void) const
bool getOriginLLH(struct Location &loc) const
uint8_t getFramesSincePredict(void) const
void setWindMagStateLearningMode()
AidingMode PV_AidingModePrev
float posDownAtLastMagReset
bool useRngFinder(void) const
uint32_t gndHgtValidTime_ms
uint32_t rngBcnLast3DmeasTime_ms
void detectOptFlowTakeoff(void)
float getPosDownDerivative(void) const
static const uint32_t OBS_BUFFER_LENGTH
obs_ring_buffer_t< mag_elements > storedMag
void getFilterTimeouts(uint8_t &timeouts) const
void SelectRngBcnFusion()
Vector3f beaconVehiclePosNED
uint32_t getLastVelNorthEastReset(Vector2f &vel) const
bool getHAGL(float &HAGL) const
uint32_t lastMagUpdate_us
void getOutputTrackingError(Vector3f &error) const
bool use_compass(void) const
AP_HAL::Util::perf_counter_t _perf_test[10]
void UpdateFilter(bool predict)
obs_ring_buffer_t< rng_bcn_elements > storedRangeBeacon
void getEulerAngles(Vector3f &eulers) const
bool magStateInitComplete
AP_HAL::Util::perf_counter_t _perf_FuseMagnetometer
void ConstrainVariances()
bool sideSlipFusionDelayed
void getFlowDebug(float &varFlow, float &gndOffset, float &flowInnovX, float &flowInnovY, float &auxInnov, float &HAGL, float &rngInnov, float &range, float &gndOffsetErr) const
void getQuaternion(Quaternion &quat) const
void getVariances(float &velVar, float &posVar, float &hgtVar, Vector3f &magVar, float &tasVar, Vector2f &offset) const
AP_HAL::Util::perf_counter_t _perf_UpdateFilter
obs_ring_buffer_t< baro_elements > storedBaro
void StoreQuatReset(void)
void calcEarthRateNED(Vector3f &omega, int32_t latitude) const
bool finalInflightYawInit
uint32_t lastGpsAidBadTime_ms
void selectHeightForFusion()
void getInnovations(Vector3f &velInnov, Vector3f &posInnov, Vector3f &magInnov, float &tasInnov, float &yawInnov) const
struct Location EKF_origin
uint32_t lastOriginHgtTime_ms
float errorScore(void) const
nav_filter_status filterStatus
bool setOriginLLH(const Location &loc)
ext_nav_elements extNavDataDelayed
uint32_t lastRngBcnPassTime_ms
rng_bcn_elements rngBcnDataDelayed
void alignMagStateDeclination()
Vector3f delAngCorrection
void writeOptFlowMeas(uint8_t &rawFlowQuality, Vector2f &rawFlowRates, Vector2f &rawGyroRates, uint32_t &msecFlowMeas, const Vector3f &posOffset)
AP_HAL::AnalogSource * chan
imu_ring_buffer_t< imu_elements > storedIMU
AP_HAL::Util::perf_counter_t _perf_TerrainOffset
of_elements ofDataDelayed
bool calcGpsGoodToAlign(void)
#define error(fmt, args ...)
uint32_t lastTimeRngBcn_ms[10]
Vector3f outputTrackError
obs_ring_buffer_t< ext_nav_elements > storedExtNav
uint8_t getActiveMag() const
bool expectGndEffectTouchdown
void FuseDeclination(float declErr)
void controlFilterModes()
AP_HAL::Util::perf_counter_t _perf_FuseVelPosNED
bool rngBcnAlignmentCompleted
uint8_t localFilterTimeStep_ms
AP_HAL::Util::perf_counter_t _perf_FuseOptFlow
void calcGpsGoodForFlight(void)
range_elements rangeDataNew
uint8_t lastRngBcnChecked
bool magStateResetRequest
bool expectGndEffectTakeoff
uint32_t timeTasReceived_ms
void getGyroScaleErrorPercentage(Vector3f &gyroScale) const
range_elements rangeDataDelayed
uint32_t lastPosPassTime_ms
uint32_t lastTasPassTime_ms
tas_elements tasDataDelayed
uint32_t extNavLastPosResetTime_ms
uint32_t rngValidMeaTime_ms
void updateTimingStatistics(void)
void setTouchdownExpected(bool val)
void StoreOutputReset(void)
AP_HAL::Util::perf_counter_t _perf_CovariancePrediction
void writeExtNavData(const Vector3f &sensOffset, const Vector3f &pos, const Quaternion &quat, float posErr, float angErr, uint32_t timeStamp_ms, uint32_t resetTime_ms)
void correctDeltaVelocity(Vector3f &delVel, float delVelDT)
uint32_t terrainHgtStableSet_ms
float InitialGyroBiasUncertainty(void) const
Quaternion imuQuatDownSampleNew
uint32_t storedRngMeasTime_ms[2][3]
void checkAttitudeAlignmentStatus()
uint32_t flowValidMeaTime_ms
bool readDeltaVelocity(uint8_t ins_index, Vector3f &dVel, float &dVel_dt)
void getFilterStatus(nav_filter_status &status) const
void setTerrainHgtStable(bool val)
rng_bcn_elements rngBcnDataNew
struct NavEKF2_core::@144 rngBcnFusionReport[10]
uint8_t imu_buffer_length
Vector2f lastKnownPositionNE
obs_ring_buffer_t< of_elements > storedOF
void getTiltError(float &ang) const
bool getMagOffsets(uint8_t mag_idx, Vector3f &magOffsets) const
bool getPosD(float &posD) const
bool checkGyroCalStatus(void)
uint32_t lastPosResetD_ms
imu_elements imuDataDownSampledNew
uint32_t lastGpsCheckTime_ms
void StoreQuatRotate(Quaternion deltaQuat)