mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-22 07:44:03 -04:00
AP_NavEKF3: fixed segfault when IMU mask covers more IMUs than GSF mask
This commit is contained in:
parent
6ee527d3e0
commit
458ade86f5
@ -246,7 +246,8 @@ void NavEKF3_core::SelectMagFusion()
|
||||
}
|
||||
|
||||
float yawEKFGSF, yawVarianceEKFGSF;
|
||||
bool canUseEKFGSF = yawEstimator->getYawData(yawEKFGSF, yawVarianceEKFGSF) &&
|
||||
bool canUseEKFGSF = yawEstimator != nullptr &&
|
||||
yawEstimator->getYawData(yawEKFGSF, yawVarianceEKFGSF) &&
|
||||
is_positive(yawVarianceEKFGSF) && yawVarianceEKFGSF < sq(radians(GSF_YAW_ACCURACY_THRESHOLD_DEG));
|
||||
if (yawAlignComplete && canUseEKFGSF && !assume_zero_sideslip()) {
|
||||
// use the EKF-GSF yaw estimator output as this is more robust than the EKF can achieve without a yaw measurement
|
||||
|
@ -410,7 +410,7 @@ void NavEKF3_core::detectFlight()
|
||||
if (!prevOnGround && onGround) {
|
||||
// landed so disable filter bank
|
||||
EKFGSF_run_filterbank = false;
|
||||
} else if (!EKFGSF_run_filterbank && ((!prevInFlight && inFlight) || expectTakeoff)) {
|
||||
} else if (yawEstimator && !EKFGSF_run_filterbank && ((!prevInFlight && inFlight) || expectTakeoff)) {
|
||||
// started flying so reset counters and enable filter bank
|
||||
EKFGSF_yaw_reset_ms = 0;
|
||||
EKFGSF_yaw_reset_request_ms = 0;
|
||||
|
Loading…
Reference in New Issue
Block a user