diff --git a/libraries/AP_NavEKF2/AP_NavEKF2_Measurements.cpp b/libraries/AP_NavEKF2/AP_NavEKF2_Measurements.cpp index 18f4158427..10e198a2d0 100644 --- a/libraries/AP_NavEKF2/AP_NavEKF2_Measurements.cpp +++ b/libraries/AP_NavEKF2/AP_NavEKF2_Measurements.cpp @@ -145,6 +145,10 @@ void NavEKF2_core::writeOptFlowMeas(uint8_t &rawFlowQuality, Vector2f &rawFlowRa // check for new magnetometer data and update store measurements if available void NavEKF2_core::readMagData() { + if (!_ahrs->get_compass()) { + allMagSensorsFailed = true; + return; + } // If we are a vehicle with a sideslip constraint to aid yaw estimation and we have timed out on our last avialable // magnetometer, then declare the magnetometers as failed for this flight uint8_t maxCount = _ahrs->get_compass()->get_count(); diff --git a/libraries/AP_NavEKF2/AP_NavEKF2_core.cpp b/libraries/AP_NavEKF2/AP_NavEKF2_core.cpp index 4369556ec7..e0977ebdbc 100644 --- a/libraries/AP_NavEKF2/AP_NavEKF2_core.cpp +++ b/libraries/AP_NavEKF2/AP_NavEKF2_core.cpp @@ -243,7 +243,9 @@ void NavEKF2_core::InitialiseVariables() posResetNE.zero(); velResetNE.zero(); hgtInnovFiltState = 0.0f; - magSelectIndex = _ahrs->get_compass()->get_primary(); + if (_ahrs->get_compass()) { + magSelectIndex = _ahrs->get_compass()->get_primary(); + } imuDataDownSampledNew.delAng.zero(); imuDataDownSampledNew.delVel.zero(); imuDataDownSampledNew.delAngDT = 0.0f;