diff --git a/libraries/AP_NavEKF2/AP_NavEKF2_MagFusion.cpp b/libraries/AP_NavEKF2/AP_NavEKF2_MagFusion.cpp index a61fa099d3..cc31369690 100644 --- a/libraries/AP_NavEKF2/AP_NavEKF2_MagFusion.cpp +++ b/libraries/AP_NavEKF2/AP_NavEKF2_MagFusion.cpp @@ -149,8 +149,8 @@ void NavEKF2_core::SelectMagFusion() // If we haven't performed the first airborne magnetic field update or have inhibited magnetic field learning, then we use the simple method of declination to maintain heading if(inhibitMagStates) { fuseCompass(); - magHealth = true; - magTimeout = false; + // zero the test ratio output from the inactive 3-axis magneteometer fusion + magTestRatio.zero(); } else { // if we are not doing aiding with earth relative observations (eg GPS) then the declination is // maintained by fusing declination as a synthesised observation @@ -163,6 +163,8 @@ void NavEKF2_core::SelectMagFusion() FuseMagnetometer(); hal.util->perf_end(_perf_test[0]); } + // zero the test ratio output from the inactive simple magnetometer yaw fusion + yawTestRatio = 0.0f; } } @@ -652,6 +654,21 @@ void NavEKF2_core::fuseCompass() innovation = -0.5f; } + // calculate the innovation test ratio + yawTestRatio = sq(innovation) / (sq(frontend._magInnovGate) * varInnov); + + // Declare the magnetometer unhealthy if the innovation test fails + if (yawTestRatio > 1.0f) { + magHealth = false; + // On the ground a large innovation could be due to large initial gyro bias or magnetic interference from nearby objects + // If we are flying, then it is more likely due to a magnetometer fault and we should not fuse the data + if (inFlight) { + return; + } + } else { + magHealth = true; + } + // correct the state vector stateStruct.angErr.zero(); for (uint8_t i=0; i<=stateIndexLim; i++) { diff --git a/libraries/AP_NavEKF2/AP_NavEKF2_Outputs.cpp b/libraries/AP_NavEKF2/AP_NavEKF2_Outputs.cpp index bc6e2a5380..ed61bf9f4a 100644 --- a/libraries/AP_NavEKF2/AP_NavEKF2_Outputs.cpp +++ b/libraries/AP_NavEKF2/AP_NavEKF2_Outputs.cpp @@ -343,9 +343,10 @@ void NavEKF2_core::getVariances(float &velVar, float &posVar, float &hgtVar, Ve velVar = sqrtf(velTestRatio); posVar = sqrtf(posTestRatio); hgtVar = sqrtf(hgtTestRatio); - magVar.x = sqrtf(magTestRatio.x); - magVar.y = sqrtf(magTestRatio.y); - magVar.z = sqrtf(magTestRatio.z); + // If we are using simple compass yaw fusion, populate all three components with the yaw test ratio to provide an equivalent output + magVar.x = sqrtf(max(magTestRatio.x,yawTestRatio)); + magVar.y = sqrtf(max(magTestRatio.y,yawTestRatio)); + magVar.z = sqrtf(max(magTestRatio.z,yawTestRatio)); tasVar = sqrtf(tasTestRatio); offset = posResetNE; } diff --git a/libraries/AP_NavEKF2/AP_NavEKF2_VehicleStatus.cpp b/libraries/AP_NavEKF2/AP_NavEKF2_VehicleStatus.cpp index d509cf8335..8196094824 100644 --- a/libraries/AP_NavEKF2/AP_NavEKF2_VehicleStatus.cpp +++ b/libraries/AP_NavEKF2/AP_NavEKF2_VehicleStatus.cpp @@ -81,7 +81,7 @@ bool NavEKF2_core::calcGpsGoodToAlign(void) // If we have good magnetometer consistency and bad innovations for longer than 5 seconds then we reset heading and field states // This enables us to handle large changes to the external magnetic field environment that occur before arming - if ((magTestRatio.x <= 1.0f && magTestRatio.y <= 1.0f) || !consistentMagData) { + if ((magTestRatio.x <= 1.0f && magTestRatio.y <= 1.0f && yawTestRatio <= 1.0f) || !consistentMagData) { magYawResetTimer_ms = imuSampleTime_ms; } if (imuSampleTime_ms - magYawResetTimer_ms > 5000) { @@ -96,7 +96,7 @@ bool NavEKF2_core::calcGpsGoodToAlign(void) // fail if magnetometer innovations are outside limits indicating bad yaw // with bad yaw we are unable to use GPS bool yawFail; - if ((magTestRatio.x > 1.0f || magTestRatio.y > 1.0f) && (frontend._gpsCheck & MASK_GPS_YAW_ERR)) { + if ((magTestRatio.x > 1.0f || magTestRatio.y > 1.0f || yawTestRatio > 1.0f) && (frontend._gpsCheck & MASK_GPS_YAW_ERR)) { yawFail = true; } else { yawFail = false; @@ -106,9 +106,10 @@ bool NavEKF2_core::calcGpsGoodToAlign(void) if (yawFail) { hal.util->snprintf(prearm_fail_string, sizeof(prearm_fail_string), - "Mag yaw error x=%.1f y=%.1f", + "Mag yaw error x=%.1f y=%.1f yaw=%.1f", (double)magTestRatio.x, - (double)magTestRatio.y); + (double)magTestRatio.y, + (double)yawTestRatio); gpsCheckStatus.bad_yaw = true; } else { gpsCheckStatus.bad_yaw = false; diff --git a/libraries/AP_NavEKF2/AP_NavEKF2_core.h b/libraries/AP_NavEKF2/AP_NavEKF2_core.h index eff1b1c340..aa928a400d 100644 --- a/libraries/AP_NavEKF2/AP_NavEKF2_core.h +++ b/libraries/AP_NavEKF2/AP_NavEKF2_core.h @@ -774,6 +774,7 @@ private: uint32_t lastPosReset_ms; // System time at which the last position reset occurred. Returned by getLastPosNorthEastReset Vector2f velResetNE; // Change in North/East velocity due to last in-flight reset in metres/sec. Returned by getLastVelNorthEastReset uint32_t lastVelReset_ms; // System time at which the last velocity reset occurred. Returned by getLastVelNorthEastReset + float yawTestRatio; // square of magnetometer yaw angle innovation divided by fail threshold // variables used to calulate a vertical velocity that is kinematically consistent with the verical position float posDownDerivative; // Rate of chage of vertical position (dPosD/dt) in m/s. This is the first time derivative of PosD.