mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-03 14:38:30 -04:00
AP_NavEKF2: Fix possible compass nullptr dereference
This commit is contained in:
parent
78f6a5a177
commit
dffa3d3b40
@ -403,6 +403,10 @@ void NavEKF2_core::getMagXYZ(Vector3f &magXYZ) const
|
|||||||
// return true if offsets are valid
|
// return true if offsets are valid
|
||||||
bool NavEKF2_core::getMagOffsets(uint8_t mag_idx, Vector3f &magOffsets) const
|
bool NavEKF2_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,
|
// 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
|
// primary compass is valid and state variances have converged
|
||||||
const float maxMagVar = 5E-6f;
|
const float maxMagVar = 5E-6f;
|
||||||
|
Loading…
Reference in New Issue
Block a user