81 bool getPosD(int8_t instance,
float &posD)
const;
172 bool getHAGL(
float &HAGL)
const;
232 void writeWheelOdom(
float delAng,
float delTime, uint32_t timeStamp_ms,
const Vector3f &posOffset,
float radius);
246 void getFlowDebug(int8_t instance,
float &varFlow,
float &gndOffset,
float &flowInnovX,
float &flowInnovY,
float &auxInnov,
float &HAGL,
float &rngInnov,
float &
range,
float &gndOffsetErr)
const;
262 bool getRangeBeaconDebug(int8_t instance, uint8_t &ID,
float &rng,
float &innov,
float &innovVar,
float &testRatio,
Vector3f &beaconPosNED,
263 float &offsetHigh,
float &offsetLow,
Vector3f &posNED)
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
AP_Int8 _gpsGlitchRadiusMax
void writeBodyFrameOdom(float quality, const Vector3f &delPos, const Vector3f &delAng, float delTime, uint32_t timeStamp_ms, const Vector3f &posOffset)
void getTiltError(int8_t instance, float &ang) const
AP_Float _magEarthProcessNoise
uint32_t last_function_call
bool resetHeightDatum(void)
const uint16_t tasRetryTime_ms
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
struct NavEKF3::@148 logging
AP_Int16 _gpsVelInnovGate
void send_status_report(mavlink_channel_t chan)
struct NavEKF3::@151 pos_down_reset_data
static const struct AP_Param::GroupInfo var_info[]
void set_enable(bool enable)
void getFilterGpsStatus(int8_t instance, nav_gps_status &faults) const
void getVariances(int8_t instance, float &velVar, float &posVar, float &hgtVar, Vector3f &magVar, float &tasVar, Vector2f &offset) const
bool setOriginLLH(const Location &loc)
struct NavEKF3::@150 pos_reset_data
AP_Float _wndVarHgtRateScale
uint32_t getBodyFrameOdomDebug(int8_t instance, Vector3f &velInnov, Vector3f &velInnovVar) const
struct NavEKF3::@149 yaw_reset_data
void set_baro_alt_noise(float noise)
AP_Int16 _rngBcnInnovGate
bool use_compass(void) const
void getGyroBias(int8_t instance, Vector3f &gyroBias) const
void getFilterStatus(int8_t instance, nav_filter_status &status) const
AP_Float _gpsHorizPosNoise
const char * prearm_failure_reason(void) const
bool have_ekf_logging(void) const
void getMagXYZ(int8_t instance, Vector3f &magXYZ) const
AP_Float _noaidHorizNoise
bool getHeightControlLimit(float &height) const
const uint16_t tasDelay_ms
bool InitialiseFilter(void)
void getTimingStatistics(int8_t instance, struct ekf_timing &timing) const
const uint8_t gndGradientSigma
AP_Float _visOdmVelErrMin
uint8_t activeCores(void) const
void setTerrainHgtStable(bool val)
const uint8_t flowTimeDeltaAvg_ms
void getRotationBodyToNED(Matrix3f &mat) const
const uint8_t sensorIntervalMin_ms
void setTouchdownExpected(bool val)
A system for managing and storing variables that are of general interest to the system.
void writeWheelOdom(float delAng, float delTime, uint32_t timeStamp_ms, const Vector3f &posOffset, float radius)
uint32_t last_primary_change
void updateLaneSwitchYawResetData(uint8_t new_primary, uint8_t old_primary)
uint32_t getLastYawResetAngle(float &yawAngDelta)
NavEKF3 & operator=(const NavEKF3 &)=delete
void setTakeoffExpected(bool val)
bool inhibitGpsVertVelUse
bool getLLH(struct Location &loc) const
AP_Float _windVelProcessNoise
void updateLaneSwitchPosResetData(uint8_t new_primary, uint8_t old_primary)
void getVelNED(int8_t instance, Vector3f &vel) const
void getInnovations(int8_t index, Vector3f &velInnov, Vector3f &posInnov, Vector3f &magInnov, float &tasInnov, float &yawInnov) const
AP_Float _magBodyProcessNoise
const uint16_t hgtRetryTimeMode0_ms
bool getPosD(int8_t instance, float &posD) const
int8_t getPrimaryCoreIMUIndex(void) const
AP_Int16 _gpsPosInnovGate
void getEulerAngles(int8_t instance, Vector3f &eulers) const
const uint16_t hgtRetryTimeMode12_ms
void check_log_write(void)
uint32_t getLastPosNorthEastReset(Vector2f &posDelta)
const float gpsPosVarAccScale
uint64_t imuSampleTime_us
void getFilterFaults(int8_t instance, uint16_t &faults) const
const uint16_t betaAvg_ms
AP_Float _visOdmVelErrMax
bool getMagOffsets(uint8_t mag_idx, Vector3f &magOffsets) const
uint32_t getLastPosDownReset(float &posDelta)
NavEKF3(const AP_AHRS *ahrs, const RangeFinder &rng)
const float covTimeStepMax
bool coreSetupRequired[7]
const uint32_t magFailTimeLimit_ms
const float fScaleFactorPnoise
const uint16_t magDelay_ms
bool getHAGL(float &HAGL) const
void getMagNED(int8_t instance, Vector3f &magNED) const
bool getPosNE(int8_t instance, Vector2f &posNE) const
void setInhibitGpsVertVelUse(const bool varIn)
void getFilterTimeouts(int8_t instance, uint8_t &timeouts) const
void getQuaternion(int8_t instance, Quaternion &quat) const
int8_t getPrimaryCoreIndex(void) const
const float gndEffectBaroScaler
AP_HAL::AnalogSource * chan
bool getOriginLLH(int8_t instance, struct Location &loc) const
const uint16_t fusionTimeStep_ms
uint8_t setInhibitGPS(void)
#define error(fmt, args ...)
const float magVarRateScale
const uint32_t flowIntervalMax_ms
const uint16_t posRetryTimeNoVel_ms
const uint16_t gndEffectTimeout_ms
void getStateVariances(int8_t instance, float stateVar[24]) const
void getEkfControlLimits(float &ekfGndSpdLimit, float &ekfNavVelGainScaler) const
AP_Float _accelBiasProcessNoise
float getPosDownDerivative(int8_t instance) const
AP_Float _gpsVertVelNoise
const uint16_t tiltDriftTimeMax_ms
Catch-all header that defines all supported RangeFinder classes.
void getAccelBias(int8_t instance, Vector3f &accelBias) const
void getWind(int8_t instance, Vector3f &wind) const
uint8_t _framesPerPrediction
uint32_t getLastVelNorthEastReset(Vector2f &vel) const
const uint16_t posRetryTimeUseVel_ms
void getOutputTrackingError(int8_t instance, Vector3f &error) const
AP_Float _gyroBiasProcessNoise
const float gyroBiasNoiseScaler
const float gpsDVelVarAccScale
const float gpsNEVelVarAccScale
uint8_t getActiveMag(int8_t instance) const
AP_Float _gpsHorizVelNoise
void writeOptFlowMeas(uint8_t &rawFlowQuality, Vector2f &rawFlowRates, Vector2f &rawGyroRates, uint32_t &msecFlowMeas, const Vector3f &posOffset)
void updateLaneSwitchPosDownResetData(uint8_t new_primary, uint8_t old_primary)
void getAccelNED(Vector3f &accelNED) const