3 #if HAL_CPU_CLASS >= HAL_CPU_CLASS_150 49 P[4][4] =
P[3][3] =
sq(25.0
f);
260 if (!posOffsetBody.
is_zero()) {
265 Vector3f velOffsetBody = angRate % posOffsetBody;
416 bool fuseData[6] = {
false,
false,
false,
false,
false,
false};
450 for (uint8_t i=0; i<=2; i++) R_OBS_DATA_CHECKS[i] = R_OBS[i];
475 for (uint8_t i=3; i<=5; i++) R_OBS_DATA_CHECKS[i] = R_OBS[i];
485 if ((hgtErr*velDErr > 0.0
f) && (
sq(hgtErr) > 9.0
f * (
P[8][8] + R_OBS_DATA_CHECKS[5])) && (
sq(velDErr) > 9.0
f * (
P[5][5] + R_OBS_DATA_CHECKS[2]))) {
542 float innovVelSumSq = 0;
544 for (uint8_t i = 0; i<=imax; i++) {
552 innovVelSumSq +=
sq(velInnov[i]);
594 const float hgtInnovFiltTC = 2.0f;
631 for (obsIndex=0; obsIndex<=5; obsIndex++) {
632 if (fuseData[obsIndex]) {
641 else if (obsIndex == 3 || obsIndex == 4) {
644 }
else if (obsIndex == 5) {
646 const float gndMaxBaroErr = 4.0f;
647 const float gndBaroInnovFloor = -0.5f;
665 for (uint8_t i= 0; i<=15; i++) {
671 for (uint8_t i = 16; i<=21; i++) {
675 for (uint8_t i = 16; i<=21; i++) {
698 bool healthyFusion =
true;
700 if (
KHP[i][i] >
P[i][i]) {
701 healthyFusion =
false;
708 P[i][j] =
P[i][j] -
KHP[i][j];
737 }
else if (obsIndex == 1) {
739 }
else if (obsIndex == 2) {
741 }
else if (obsIndex == 3) {
743 }
else if (obsIndex == 4) {
745 }
else if (obsIndex == 5) {
752 }
else if (obsIndex == 1) {
754 }
else if (obsIndex == 2) {
756 }
else if (obsIndex == 3) {
758 }
else if (obsIndex == 4) {
760 }
else if (obsIndex == 5) {
789 if (sensor !=
nullptr) {
791 if (!posOffsetBody.
is_zero()) {
853 if (lostRngHgt || lostGpsHgt || lostExtNavHgt) {
866 const float gndHgtFiltTC = 0.5f;
949 #endif // HAL_CPU_CLASS
void calcFiltBaroOffset()
float norm(const T first, const U second, const Params... parameters)
gps_elements gpsDataDelayed
uint32_t lastVelPassTime_ms
AP_Float _gpsVertVelNoise
AP_RangeFinder_Backend * get_backend(uint8_t id) const
obs_ring_buffer_t< gps_elements > storedGPS
void controlMagYawReset()
uint32_t extNavMeasTime_ms
void zeroCols(Matrix24 &covMat, uint8_t first, uint8_t last)
imu_ring_buffer_t< output_elements > storedOutput
bool extNavYawResetRequest
void update_calibration(void)
const uint16_t hgtRetryTimeMode12_ms
const uint16_t hgtRetryTimeMode0_ms
output_elements outputDataNew
AP_Float _gpsHorizVelNoise
obs_ring_buffer_t< range_elements > storedRange
bool getTakeoffExpected()
void zeroRows(Matrix24 &covMat, uint8_t first, uint8_t last)
AP_Int16 _gpsPosInnovGate
uint32_t lastHgtPassTime_ms
uint32_t lastTimeGpsReceived_ms
const Vector3f & get_pos_offset() const
struct NavEKF2_core::state_elements & stateStruct
const float gpsDVelVarAccScale
uint32_t imuSampleTime_ms
bool inhibitGpsVertVelUse
output_elements outputDataDelayed
AP_Int16 _gpsVelInnovGate
static auto MAX(const A &one, const B &two) -> decltype(one > two ? one :two)
imu_elements imuDataDelayed
const float gndEffectBaroScaler
baro_elements baroDataDelayed
float receiverPosCov[3][3]
bool resetHeightDatum(void)
const Vector3f & get_antenna_offset(uint8_t instance) const
void SelectVelPosFusion()
struct NavEKF2_core::@145 faultStatus
const float gpsPosVarAccScale
bool getTouchdownExpected()
void correctEkfOriginHeight()
AP_Float _gpsHorizPosNoise
virtual void perf_end(perf_counter_t h)
int16_t max_distance_cm_orient(enum Rotation orientation) const
uint32_t rngBcnLast3DmeasTime_ms
bool use_compass(void) const
Vector3< T > mul_transpose(const Vector3< T > &v) const
void ConstrainVariances()
struct nav_filter_status::@138 flags
obs_ring_buffer_t< baro_elements > storedBaro
bool finalInflightYawInit
float constrain_float(const float amt, const float low, const float high)
const AP_HAL::HAL & hal
-*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*-
void selectHeightForFusion()
nav_filter_status filterStatus
ext_nav_elements extNavDataDelayed
AP_Float _noaidHorizNoise
virtual void perf_begin(perf_counter_t h)
uint32_t lastRngBcnPassTime_ms
const float gpsNEVelVarAccScale
obs_ring_buffer_t< ext_nav_elements > storedExtNav
AP_HAL::Util::perf_counter_t _perf_FuseVelPosNED
void rotate(const Vector3f &v)
range_elements rangeDataDelayed
uint32_t lastPosPassTime_ms
uint32_t rngValidMeaTime_ms
AP_Int8 _gpsGlitchRadiusMax
uint8_t imu_buffer_length
Vector2f lastKnownPositionNE
uint32_t lastPosResetD_ms