22 #pragma GCC optimize("O3") 24 #define EK3_DISABLE_INTERRUPTS 0 33 #define MASK_GPS_NSATS (1<<0) 34 #define MASK_GPS_HDOP (1<<1) 35 #define MASK_GPS_SPD_ERR (1<<2) 36 #define MASK_GPS_POS_ERR (1<<3) 37 #define MASK_GPS_YAW_ERR (1<<4) 38 #define MASK_GPS_POS_DRIFT (1<<5) 39 #define MASK_GPS_VERT_SPD (1<<6) 40 #define MASK_GPS_HORIZ_SPD (1<<7) 43 #define HGT_SOURCE_BARO 0 44 #define HGT_SOURCE_RNG 1 45 #define HGT_SOURCE_GPS 2 46 #define HGT_SOURCE_BCN 3 48 #define earthRate 0.000072921f // earth rotation rate (rad/sec) 52 #define STARTUP_WIND_SPEED 3.0f 55 #define GYRO_BIAS_LIMIT 0.5f 58 #define ACCEL_BIAS_LIM_SCALER 0.2f 61 #define EKF_TARGET_DT_MS 12 62 #define EKF_TARGET_DT 0.012f 65 #define EKF3_MAG_FINAL_RESET_ALT 2.5f 101 bool getPosD(
float &posD)
const;
178 bool getHAGL(
float &HAGL)
const;
212 void getFlowDebug(
float &varFlow,
float &gndOffset,
float &flowInnovX,
float &flowInnovY,
float &auxInnov,
float &HAGL,
float &rngInnov,
float &
range,
float &gndOffsetErr)
const;
235 void writeWheelOdom(
float delAng,
float delTime, uint32_t timeStamp_ms,
const Vector3f &posOffset,
float radius);
262 float &offsetHigh,
float &offsetLow,
Vector3f &posNED);
366 #if MATH_CHECK_INDEXES 392 typedef ftype Vector2[2];
393 typedef ftype Vector3[3];
394 typedef ftype Vector4[4];
395 typedef ftype Vector5[5];
396 typedef ftype Vector6[6];
397 typedef ftype Vector7[7];
398 typedef ftype Vector8[8];
399 typedef ftype Vector9[9];
400 typedef ftype Vector10[10];
401 typedef ftype Vector11[11];
402 typedef ftype Vector13[13];
403 typedef ftype Vector14[14];
404 typedef ftype Vector15[15];
405 typedef ftype Vector21[21];
406 typedef ftype Vector22[22];
407 typedef ftype Vector23[23];
408 typedef ftype Vector24[24];
409 typedef ftype Vector25[25];
410 typedef ftype Vector28[28];
411 typedef ftype Matrix3[3][3];
412 typedef ftype Matrix24[24][24];
413 typedef ftype Matrix34_50[34][50];
414 typedef uint32_t Vector_u32_50[50];
552 void zeroRows(Matrix24 &covMat, uint8_t first, uint8_t last);
555 void zeroCols(Matrix24 &covMat, uint8_t first, uint8_t last);
Quaternion calcQuatAndFieldStates(float roll, float pitch)
void getRotationBodyToNED(Matrix3f &mat) const
char prearm_fail_string[40]
Quaternion prevQuatMagReset
gps_elements gpsDataDelayed
void setWindMagStateLearningMode()
void zeroCols(Matrix24 &covMat, uint8_t first, uint8_t last)
AP_HAL::Util::perf_counter_t _perf_test[10]
void StoreOutputReset(void)
float getPosDownDerivative(void) const
uint32_t lastPosPassTime_ms
void CalcRangeBeaconPosDownOffset(float obsVar, Vector3f &vehiclePosNED, bool aligning)
baro_elements baroDataDelayed
void getFilterFaults(uint16_t &faults) const
bool getPosD(float &posD) const
bool calcGpsGoodToAlign(void)
uint32_t terrainHgtStableSet_ms
uint32_t gndHgtValidTime_ms
uint32_t prevFlowFuseTime_ms
bool getPosNE(Vector2f &posNE) const
uint32_t storedRngMeasTime_ms[2][3]
bool optFlowFusionDelayed
bool magStateInitComplete
uint32_t lastInnovPassTime_ms
Quaternion quatAtLastMagReset
obs_ring_buffer_t< vel_odm_elements > storedBodyOdm
bool setup_core(NavEKF3 *_frontend, uint8_t _imu_index, uint8_t _core_index)
void updateStateIndexLim(void)
uint8_t getIMUIndex(void) const
void quat2Tbn(Matrix3f &Tbn, const Quaternion &quat) const
wheel_odm_elements wheelOdmDataNew
void selectHeightForFusion()
uint32_t secondLastGpsTime_ms
bool expectGndEffectTouchdown
uint32_t getBodyFrameOdomDebug(Vector3f &velInnov, Vector3f &velInnovVar)
float maxOffsetStateChangeFilt
imu_elements imuDataDelayed
uint8_t getActiveMag() const
bool setOriginLLH(const Location &loc)
float beaconVehiclePosErr
float storedRngMeas[2][3]
void getVelNED(Vector3f &vel) const
obs_ring_buffer_t< mag_elements > storedMag
void SelectBodyOdomFusion()
void getTimingStatistics(struct ekf_timing &timing)
uint32_t getLastVelNorthEastReset(Vector2f &vel) const
obs_ring_buffer_t< tas_elements > storedTAS
uint8_t lastRngBcnChecked
bool assume_zero_sideslip(void) const
AP_HAL::Util::perf_counter_t _perf_FuseAirspeed
void calcFiltBaroOffset()
void getAccelBias(Vector3f &accelBias) const
vel_odm_elements bodyOdmDataDelayed
uint32_t wheelOdmMeasTime_ms
void correctDeltaAngle(Vector3f &delAng, float delAngDT)
imu_ring_buffer_t< output_elements > storedOutput
range_elements rangeDataNew
void getMagNED(Vector3f &magNED) const
float InitialGyroBiasUncertainty(void) const
void StoreQuatReset(void)
void SelectVelPosFusion()
bool readyToUseBodyOdm(void) const
uint32_t timeTasReceived_ms
uint32_t lastVelPassTime_ms
void calcGpsGoodForFlight(void)
bool rngBcnAlignmentStarted
void getQuaternion(Quaternion &quat) const
uint32_t lastTasPassTime_ms
void getTiltError(float &ang) const
Quaternion imuQuatDownSampleNew
void checkGyroCalStatus(void)
uint32_t lastPosResetD_ms
ftype Matrix34_50[34][50]
uint32_t lastbodyVelPassTime_ms
void getGyroBias(Vector3f &gyroBias) const
of_elements ofDataDelayed
bool readDeltaAngle(uint8_t ins_index, Vector3f &dAng)
bool sideSlipFusionDelayed
tas_elements tasDataDelayed
uint8_t effective_magCal(void) const
void UpdateStrapdownEquationsNED()
void getFilterStatus(nav_filter_status &status) const
struct NavEKF3_core::@153 faultStatus
uint32_t lastRngBcnPassTime_ms
float posDownAtLastMagReset
uint32_t flowValidMeaTime_ms
obs_ring_buffer_t< rng_bcn_elements > storedRangeBeacon
uint32_t framesSincePredict
AP_HAL::Util::perf_counter_t _perf_FuseSideslip
wheel_odm_elements wheelOdmDataDelayed
baro_elements baroDataNew
uint32_t timeAtLastAuxEKF_ms
bool readyToUseOptFlow(void) const
uint8_t setInhibitGPS(void)
AP_HAL::Util::perf_counter_t _perf_UpdateFilter
range_elements rangeDataDelayed
struct NavEKF3_core::state_elements & stateStruct
bool inhibitDelAngBiasStates
void zeroRows(Matrix24 &covMat, uint8_t first, uint8_t last)
bool use_compass(void) const
uint8_t localFilterTimeStep_ms
AP_HAL::Util::perf_counter_t _perf_FuseVelPosNED
void controlFilterModes()
float errorScore(void) const
uint32_t getLastYawResetAngle(float &yawAng) const
uint32_t lastDecayTime_ms
bool InitialiseFilterBootstrap(void)
void calcIMU_Weighting(float K1, float K2)
void getWind(Vector3f &wind) const
bool getRangeBeaconDebug(uint8_t &ID, float &rng, float &innov, float &innovVar, float &testRatio, Vector3f &beaconPosNED, float &offsetHigh, float &offsetLow, Vector3f &posNED)
Vector3f beaconVehiclePosNED
output_elements outputDataNew
void updateTimingStatistics(void)
bool getHAGL(float &HAGL) const
uint32_t lastInitFailReport_ms
Vector3f calcRotVecVariances(void)
bool readyToUseGPS(void) const
void StoreQuatRotate(Quaternion deltaQuat)
float bcnPosDownOffsetMax
uint32_t getLastPosNorthEastReset(Vector2f &pos) const
AP_HAL::Util::perf_counter_t _perf_FuseOptFlow
bool readyToUseRangeBeacon(void) const
float minOffsetStateChangeFilt
Vector2f lastKnownPositionNE
void FuseDeclination(float declErr)
AidingMode PV_AidingModePrev
uint32_t lastHgtPassTime_ms
bool expectGndEffectTakeoff
Vector3f delAngCorrection
uint32_t Vector_u32_50[50]
uint8_t obs_buffer_length
float receiverPosCov[3][3]
void InitialiseVariables()
void getEulerAngles(Vector3f &eulers) const
float yawInnovAtLastMagReset
Vector3f outputTrackError
uint32_t lastTimeGpsReceived_ms
uint32_t lastPreAlignGpsCheckTime_ms
void UpdateFilter(bool predict)
obs_ring_buffer_t< gps_elements > storedGPS
resetDataSource velResetSource
void getVariances(float &velVar, float &posVar, float &hgtVar, Vector3f &magVar, float &tasVar, Vector2f &offset) const
Vector3f earthMagFieldVar
void setTakeoffExpected(bool val)
uint32_t lastRngMeasTime_ms
obs_ring_buffer_t< range_elements > storedRange
uint8_t rngBcnFuseDataReportIndex
void updateFilterStatus(void)
AP_HAL::Util::perf_counter_t _perf_CovariancePrediction
bool magStateResetRequest
void getEkfControlLimits(float &ekfGndSpdLimit, float &ekfNavVelGainScaler) const
uint32_t getLastPosDownReset(float &posD) const
void detectOptFlowTakeoff(void)
resetDataSource posResetSource
struct Location gpsloc_prev
uint32_t magYawResetTimer_ms
void controlMagYawReset()
void getInnovations(Vector3f &velInnov, Vector3f &posInnov, Vector3f &magInnov, float &tasInnov, float &yawInnov) const
vel_odm_elements bodyOdmDataNew
struct NavEKF3_core::@152 rngBcnFusionReport[10]
AP_HAL::Util::perf_counter_t _perf_FuseBodyOdom
imu_ring_buffer_t< imu_elements > storedIMU
void getFilterGpsStatus(nav_gps_status &status) const
void correctEkfOriginHeight()
bool inhibitDelVelBiasStates
output_elements outputDataDelayed
uint32_t lastGpsCheckTime_ms
rng_bcn_elements rngBcnDataNew
mag_elements magDataDelayed
void getFlowDebug(float &varFlow, float &gndOffset, float &flowInnovX, float &flowInnovY, float &auxInnov, float &HAGL, float &rngInnov, float &range, float &gndOffsetErr) const
obs_ring_buffer_t< of_elements > storedOF
struct NavEKF3_core::@154 gpsCheckStatus
void writeWheelOdom(float delAng, float delTime, uint32_t timeStamp_ms, const Vector3f &posOffset, float radius)
uint32_t lastMagUpdate_us
uint32_t lastOriginHgtTime_ms
uint32_t touchdownExpectedSet_ms
AP_HAL::Util::perf_counter_t _perf_TerrainOffset
void calcEarthRateNED(Vector3f &omega, int32_t latitude) const
void CovariancePrediction()
struct NavEKF3_core::@155 mag_state
bool getTouchdownExpected()
void getStateVariances(float stateVar[24])
AP_HAL::AnalogSource * chan
obs_ring_buffer_t< wheel_odm_elements > storedWheelOdm
void getOutputTrackingError(Vector3f &error) const
void checkAttitudeAlignmentStatus()
bool rngBcnAlignmentCompleted
uint32_t rngValidMeaTime_ms
uint32_t takeoffExpectedSet_ms
bool getMagOffsets(uint8_t mag_idx, Vector3f &magOffsets) const
uint8_t getFramesSincePredict(void) const
uint32_t rngBcnLast3DmeasTime_ms
uint32_t lastSynthYawTime_ms
void writeOptFlowMeas(uint8_t &rawFlowQuality, Vector2f &rawFlowRates, Vector2f &rawGyroRates, uint32_t &msecFlowMeas, const Vector3f &posOffset)
#define error(fmt, args ...)
const char * prearm_failure_reason(void) const
void alignMagStateDeclination()
void getMagXYZ(Vector3f &magXYZ) const
bool getTakeoffExpected()
float innovationIncrement
void getAccelNED(Vector3f &accelNED) const
void checkDivergence(void)
void setTouchdownExpected(bool val)
void ConstrainVariances()
bool getHeightControlLimit(float &height) const
imu_elements imuDataDownSampledNew
uint32_t firstInitTime_ms
uint32_t lastGpsAidBadTime_ms
uint32_t lastBaroReceived_ms
bool getLLH(struct Location &loc) const
uint8_t fusionHorizonOffset
bool finalInflightMagInit
const Vector3f * body_offset
bool readDeltaVelocity(uint8_t ins_index, Vector3f &dVel, float &dVel_dt)
struct Location EKF_origin
bool bodyVelFusionDelayed
uint32_t bodyOdmMeasTime_ms
nav_filter_status filterStatus
const Vector3f * hub_offset
void correctDeltaVelocity(Vector3f &delVel, float delVelDT)
obs_ring_buffer_t< baro_elements > storedBaro
rng_bcn_elements rngBcnDataDelayed
bool useRngFinder(void) const
void EstimateTerrainOffset()
uint32_t imuSampleTime_ms
void SelectRngBcnFusion()
void send_status_report(mavlink_channel_t chan)
uint32_t prevBodyVelFuseTime_ms
bool finalInflightYawInit
uint32_t lastTimeRngBcn_ms[10]
bool getOriginLLH(struct Location &loc) const
uint32_t lastGpsVelFail_ms
uint32_t lastHealthyMagTime_ms
void setTerrainHgtStable(bool val)
void initialiseQuatCovariances(Vector3f &rotVarVec)
bool useAirspeed(void) const
uint8_t imu_buffer_length
uint32_t airborneDetectTime_ms
AP_HAL::Util::perf_counter_t _perf_FuseMagnetometer
void getFilterTimeouts(uint8_t &timeouts) const
bool resetHeightDatum(void)
uint32_t lastInnovFailTime_ms
const Vector3f * body_offset
float bcnPosDownOffsetMin
void writeBodyFrameOdom(float quality, const Vector3f &delPos, const Vector3f &delAng, float delTime, uint32_t timeStamp_ms, const Vector3f &posOffset)