123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384858687888990919293949596979899100101102103104105106107108109110111112113114115116117118119120121122123124125126127128129130131132133134135136137138139140141142143144145146147148149150151152153154155156157158159160161162163164165166167168169170171172173174175176177178179180181182183184185186187188189190191192193194195196197198199200201202203204205206207208209210211212213214215216217218219220221222223224225226227228229230231232233234235236237238239240241242243244245246247248249250251252253254255256257258259260261262263264265266267268269270271272273274275276277278279280281282283284285286287288289290291292293294295296297298299300301302303304305306307308309310311312313314315316317318319320321322323324325326327328329330331332333334335336337338339340341342343344345346347348349350351352353354355356357358359360361362363364365366367368369370371372373374375376377378379380381382383384385386387388389390391392393394395396397398399400401402403404405406407408409410411412413414415416417418419420421422423424425426427428429430431432433434435436437438439440441442443444445446447448449450451452453454455456457458459460461462463464465466467468469470471472473474475476477478479480481482483484485486487488489490491492493494495496497498499500501502503504505506507508509510511512513514515516517518519520521522523524525526527528529530531532533534535536537538539540541542543544545546547548549550551552553554555 |
- #pragma once
- #include <AP_Math/AP_Math.h>
- #include <AP_Param/AP_Param.h>
- #include <GCS_MAVLink/GCS_MAVLink.h>
- #include <AP_NavEKF/AP_Nav_Common.h>
- #include <AP_Airspeed/AP_Airspeed.h>
- #include <AP_Compass/AP_Compass.h>
- #include <AP_RangeFinder/AP_RangeFinder.h>
- #include <AP_Logger/LogStructure.h>
- class NavEKF3_core;
- class AP_AHRS;
- class NavEKF3 {
- friend class NavEKF3_core;
- public:
- NavEKF3(const AP_AHRS *ahrs, const RangeFinder &rng);
-
- NavEKF3(const NavEKF3 &other) = delete;
- NavEKF3 &operator=(const NavEKF3&) = delete;
- static const struct AP_Param::GroupInfo var_info[];
-
- uint8_t activeCores(void) const {
- return num_cores;
- }
-
- bool InitialiseFilter(void);
-
- void UpdateFilter(void);
-
- void check_log_write(void);
-
-
- bool healthy(void) const;
-
- bool all_cores_healthy(void) const;
-
-
- int8_t getPrimaryCoreIndex(void) const;
-
-
- int8_t getPrimaryCoreIMUIndex(void) const;
-
-
-
-
- bool getPosNE(int8_t instance, Vector2f &posNE) const;
-
-
-
-
- bool getPosD(int8_t instance, float &posD) const;
-
-
- void getVelNED(int8_t instance, Vector3f &vel) const;
-
-
-
-
- float getPosDownDerivative(int8_t instance) const;
-
- void getAccelNED(Vector3f &accelNED) const;
-
-
- void getGyroBias(int8_t instance, Vector3f &gyroBias) const;
-
-
- void getAccelBias(int8_t instance, Vector3f &accelBias) const;
-
-
- void getTiltError(int8_t instance, float &ang) const;
-
- void resetGyroBias(void);
-
-
-
-
-
- bool resetHeightDatum(void);
-
-
-
-
- uint8_t setInhibitGPS(void);
-
-
- void setInhibitGpsVertVelUse(const bool varIn) { inhibitGpsVertVelUse = varIn; };
-
-
- void getEkfControlLimits(float &ekfGndSpdLimit, float &ekfNavVelGainScaler) const;
-
-
- void getWind(int8_t instance, Vector3f &wind) const;
-
-
- void getMagNED(int8_t instance, Vector3f &magNED) const;
-
-
- void getMagXYZ(int8_t instance, Vector3f &magXYZ) const;
-
-
- uint8_t getActiveMag(int8_t instance) const;
-
-
- bool getMagOffsets(uint8_t mag_idx, Vector3f &magOffsets) const;
-
-
-
-
- bool getLLH(struct Location &loc) const;
-
-
-
-
- bool getOriginLLH(int8_t instance, struct Location &loc) const;
-
-
-
-
- bool setOriginLLH(const Location &loc);
-
-
- bool getHAGL(float &HAGL) const;
-
-
- void getEulerAngles(int8_t instance, Vector3f &eulers) const;
-
- void getRotationBodyToNED(Matrix3f &mat) const;
-
- void getQuaternionBodyToNED(int8_t instance, Quaternion &quat) const;
-
- void getQuaternion(int8_t instance, Quaternion &quat) const;
-
-
- void getInnovations(int8_t index, Vector3f &velInnov, Vector3f &posInnov, Vector3f &magInnov, float &tasInnov, float &yawInnov) const;
-
- void getOutputTrackingError(int8_t instance, Vector3f &error) const;
-
-
- void getVariances(int8_t instance, float &velVar, float &posVar, float &hgtVar, Vector3f &magVar, float &tasVar, Vector2f &offset) const;
-
- void getStateVariances(int8_t instance, float stateVar[24]) const;
-
-
- bool use_compass(void) const;
-
-
-
-
-
-
-
- void writeOptFlowMeas(const uint8_t rawFlowQuality, const Vector2f &rawFlowRates, const Vector2f &rawGyroRates, const uint32_t msecFlowMeas, const Vector3f &posOffset);
-
- void writeBodyFrameOdom(float quality, const Vector3f &delPos, const Vector3f &delAng, float delTime, uint32_t timeStamp_ms, const Vector3f &posOffset);
-
- void writeWheelOdom(float delAng, float delTime, uint32_t timeStamp_ms, const Vector3f &posOffset, float radius);
-
- uint32_t getBodyFrameOdomDebug(int8_t instance, Vector3f &velInnov, Vector3f &velInnovVar) const;
-
-
- void getFlowDebug(int8_t instance, float &varFlow, float &gndOffset, float &flowInnovX, float &flowInnovY, float &auxInnov, float &HAGL, float &rngInnov, float &range, float &gndOffsetErr) const;
-
- bool getRangeBeaconDebug(int8_t instance, uint8_t &ID, float &rng, float &innov, float &innovVar, float &testRatio, Vector3f &beaconPosNED,
- float &offsetHigh, float &offsetLow, Vector3f &posNED) const;
-
- void writeEulerYawAngle(float yawAngle, float yawAngleErr, uint32_t timeStamp_ms, uint8_t type);
-
-
- void setTakeoffExpected(bool val);
-
-
- void setTouchdownExpected(bool val);
-
-
-
- void setTerrainHgtStable(bool val);
-
- void getFilterFaults(int8_t instance, uint16_t &faults) const;
-
- void getFilterTimeouts(int8_t instance, uint8_t &timeouts) const;
-
- void getFilterGpsStatus(int8_t instance, nav_gps_status &faults) const;
-
- void getFilterStatus(int8_t instance, nav_filter_status &status) const;
-
- void send_status_report(mavlink_channel_t chan);
-
-
-
- bool getHeightControlLimit(float &height) const;
-
-
- uint32_t getLastYawResetAngle(float &yawAngDelta);
-
-
- uint32_t getLastPosNorthEastReset(Vector2f &posDelta);
-
-
- uint32_t getLastVelNorthEastReset(Vector2f &vel) const;
-
-
- uint32_t getLastPosDownReset(float &posDelta);
-
- const char *prearm_failure_reason(void) const;
-
- void set_baro_alt_noise(float noise) { _baroAltNoise.set_and_save(noise); };
-
- void set_enable(bool enable) { _enable.set(enable); }
-
- bool have_ekf_logging(void) const { return logging.enabled && _logging_mask != 0; }
-
- void getTimingStatistics(int8_t instance, struct ekf_timing &timing) const;
-
- void checkLaneSwitch(void);
-
- void Log_Write();
- private:
- uint8_t num_cores;
- uint8_t primary;
- NavEKF3_core *core = nullptr;
- const AP_AHRS *_ahrs;
- const RangeFinder &_rng;
- uint32_t _frameTimeUsec;
- uint8_t _framesPerPrediction;
-
-
- AP_Int8 _enable;
- AP_Float _gpsHorizVelNoise;
- AP_Float _gpsVertVelNoise;
- AP_Float _gpsHorizPosNoise;
- AP_Float _baroAltNoise;
- AP_Float _magNoise;
- AP_Float _easNoise;
- AP_Float _windVelProcessNoise;
- AP_Float _wndVarHgtRateScale;
- AP_Float _magEarthProcessNoise;
- AP_Float _magBodyProcessNoise;
- AP_Float _gyrNoise;
- AP_Float _accNoise;
- AP_Float _gyroBiasProcessNoise;
- AP_Float _accelBiasProcessNoise;
- AP_Int16 _hgtDelay_ms;
- AP_Int8 _fusionModeGPS;
- AP_Int16 _gpsVelInnovGate;
- AP_Int16 _gpsPosInnovGate;
- AP_Int16 _hgtInnovGate;
- AP_Int16 _magInnovGate;
- AP_Int16 _tasInnovGate;
- AP_Int8 _magCal;
- AP_Int8 _gpsGlitchRadiusMax;
- AP_Float _flowNoise;
- AP_Int16 _flowInnovGate;
- AP_Int8 _flowDelay_ms;
- AP_Int16 _rngInnovGate;
- AP_Float _maxFlowRate;
- AP_Int8 _altSource;
- AP_Float _rngNoise;
- AP_Int8 _gpsCheck;
- AP_Int8 _imuMask;
- AP_Int16 _gpsCheckScaler;
- AP_Float _noaidHorizNoise;
- AP_Int8 _logging_mask;
- AP_Float _yawNoise;
- AP_Int16 _yawInnovGate;
- AP_Int8 _tauVelPosOutput;
- AP_Int8 _useRngSwHgt;
- AP_Float _terrGradMax;
- AP_Float _rngBcnNoise;
- AP_Int16 _rngBcnInnovGate;
- AP_Int8 _rngBcnDelay_ms;
- AP_Float _useRngSwSpd;
- AP_Float _accBiasLim;
- AP_Int8 _magMask;
- AP_Int8 _originHgtMode;
- AP_Float _visOdmVelErrMax;
- AP_Float _visOdmVelErrMin;
- AP_Float _wencOdmVelErr;
- AP_Int8 _flowUse;
- #define FLOW_USE_NONE 0
- #define FLOW_USE_NAV 1
- #define FLOW_USE_TERRAIN 2
-
- const float gpsNEVelVarAccScale = 0.05f;
- const float gpsDVelVarAccScale = 0.07f;
- const float gpsPosVarAccScale = 0.05f;
- const uint16_t magDelay_ms = 60;
- const uint16_t tasDelay_ms = 100;
- const uint16_t tiltDriftTimeMax_ms = 15000;
- const uint16_t posRetryTimeUseVel_ms = 10000;
- const uint16_t posRetryTimeNoVel_ms = 7000;
- const uint16_t hgtRetryTimeMode0_ms = 10000;
- const uint16_t hgtRetryTimeMode12_ms = 5000;
- const uint16_t tasRetryTime_ms = 5000;
- const uint32_t magFailTimeLimit_ms = 10000;
- const float magVarRateScale = 0.005f;
- const float gyroBiasNoiseScaler = 2.0f;
- const uint16_t hgtAvg_ms = 100;
- const uint16_t betaAvg_ms = 100;
- const float covTimeStepMax = 0.1f;
- const float covDelAngMax = 0.05f;
- const float DCM33FlowMin = 0.71f;
- const float fScaleFactorPnoise = 1e-10f;
- const uint8_t flowTimeDeltaAvg_ms = 100;
- const uint32_t flowIntervalMax_ms = 100;
- const uint16_t gndEffectTimeout_ms = 1000;
- const float gndEffectBaroScaler = 4.0f;
- const uint8_t gndGradientSigma = 50;
- const uint16_t fusionTimeStep_ms = 10;
- const uint8_t sensorIntervalMin_ms = 50;
- const uint8_t flowIntervalMin_ms = 20;
- struct {
- bool enabled:1;
- bool log_compass:1;
- bool log_baro:1;
- bool log_imu:1;
- } logging;
-
- uint64_t imuSampleTime_us;
-
- uint32_t lastLaneSwitch_ms;
-
- struct {
- uint32_t last_function_call;
- bool core_changed;
- uint32_t last_primary_change;
- float core_delta;
- } yaw_reset_data;
- struct {
- uint32_t last_function_call;
- bool core_changed;
- uint32_t last_primary_change;
- Vector2f core_delta;
- } pos_reset_data;
- struct {
- uint32_t last_function_call;
- bool core_changed;
- uint32_t last_primary_change;
- float core_delta;
- } pos_down_reset_data;
- bool runCoreSelection;
- bool coreSetupRequired[7];
- uint8_t coreImuIndex[7];
- bool inhibitGpsVertVelUse;
-
- struct Location common_EKF_origin;
- bool common_origin_valid;
-
-
-
-
- void updateLaneSwitchYawResetData(uint8_t new_primary, uint8_t old_primary);
-
-
-
- void updateLaneSwitchPosResetData(uint8_t new_primary, uint8_t old_primary);
-
-
-
- void updateLaneSwitchPosDownResetData(uint8_t new_primary, uint8_t old_primary);
-
- void Log_Write_EKF1(uint8_t core, LogMessages msg_id, uint64_t time_us) const;
- void Log_Write_NKF2a(uint8_t core, LogMessages msg_id, uint64_t time_us) const;
- void Log_Write_NKF3(uint8_t core, LogMessages msg_id, uint64_t time_us) const;
- void Log_Write_NKF4(uint8_t core, LogMessages msg_id, uint64_t time_us) const;
- void Log_Write_NKF5(uint64_t time_us) const;
- void Log_Write_Quaternion(uint8_t core, LogMessages msg_id, uint64_t time_us) const;
- void Log_Write_Beacon(uint64_t time_us) const;
- void Log_Write_BodyOdom(uint64_t time_us) const;
- void Log_Write_State_Variances(uint64_t time_us) const;
- };
|