Browse Source

AP_NavEKF3: Fix possible compass nullptr dereference

master
Michael du Breuil 8 years ago committed by Francisco Ferreira
parent
commit
efe70c8d3a
  1. 3
      libraries/AP_NavEKF3/AP_NavEKF3_Outputs.cpp

3
libraries/AP_NavEKF3/AP_NavEKF3_Outputs.cpp

@ -404,6 +404,9 @@ void NavEKF3_core::getMagXYZ(Vector3f &magXYZ) const @@ -404,6 +404,9 @@ void NavEKF3_core::getMagXYZ(Vector3f &magXYZ) const
// return true if offsets are valid
bool NavEKF3_core::getMagOffsets(uint8_t mag_idx, Vector3f &magOffsets) const
{
if (!_ahrs->get_compass()) {
return false;
}
// compass offsets are valid if we have finalised magnetic field initialisation, magnetic field learning is not prohibited,
// primary compass is valid and state variances have converged
const float maxMagVar = 5E-6f;

Loading…
Cancel
Save