mirror of https://github.com/ArduPilot/ardupilot
AP_NavEKF3: Fix bug preventing yaw alignment to EKF-GSF estimate
This commit is contained in:
parent
fe81387433
commit
8561f5239d
|
@ -718,14 +718,14 @@ void NavEKF3_core::runYawEstimatorCorrection()
|
||||||
} else {
|
} else {
|
||||||
EKFGSF_yaw_valid_count = 0;
|
EKFGSF_yaw_valid_count = 0;
|
||||||
}
|
}
|
||||||
} else {
|
|
||||||
EKFGSF_yaw_valid_count = 0;
|
|
||||||
}
|
}
|
||||||
|
|
||||||
// action an external reset request
|
// action an external reset request
|
||||||
if (EKFGSF_yaw_reset_request_ms > 0 && imuSampleTime_ms - EKFGSF_yaw_reset_request_ms < YAW_RESET_TO_GSF_TIMEOUT_MS) {
|
if (EKFGSF_yaw_reset_request_ms > 0 && imuSampleTime_ms - EKFGSF_yaw_reset_request_ms < YAW_RESET_TO_GSF_TIMEOUT_MS) {
|
||||||
EKFGSF_resetMainFilterYaw();
|
EKFGSF_resetMainFilterYaw();
|
||||||
}
|
}
|
||||||
|
} else {
|
||||||
|
EKFGSF_yaw_valid_count = 0;
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
|
|
Loading…
Reference in New Issue