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