mirror of https://github.com/ArduPilot/ardupilot
AP_NavEKF3: handle compass fallback in yaw source reset
if we get to this point we must be using the compass fallback logic, and should do the reset
This commit is contained in:
parent
f257dc20d0
commit
36c946113d
|
@ -363,7 +363,8 @@ void NavEKF3_core::SelectMagFusion()
|
||||||
|
|
||||||
// Control reset of yaw and magnetic field states if we are using compass data
|
// Control reset of yaw and magnetic field states if we are using compass data
|
||||||
if (magDataToFuse) {
|
if (magDataToFuse) {
|
||||||
if (yaw_source_reset && (yaw_source == AP_NavEKF_Source::SourceYaw::COMPASS)) {
|
if (yaw_source_reset && (yaw_source == AP_NavEKF_Source::SourceYaw::COMPASS ||
|
||||||
|
yaw_source == AP_NavEKF_Source::SourceYaw::EXTERNAL_COMPASS_FALLBACK)) {
|
||||||
magYawResetRequest = true;
|
magYawResetRequest = true;
|
||||||
yaw_source_reset = false;
|
yaw_source_reset = false;
|
||||||
}
|
}
|
||||||
|
|
Loading…
Reference in New Issue