mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-08 17:08:28 -04:00
ArduPlane: Don't check variances if not available
This commit is contained in:
parent
70a02f31ab
commit
3a10838c65
@ -110,7 +110,9 @@ bool Plane::ekf_over_threshold()
|
||||
float position_variance, vel_variance, height_variance, tas_variance;
|
||||
Vector3f mag_variance;
|
||||
Vector2f offset;
|
||||
ahrs.get_variances(vel_variance, position_variance, height_variance, mag_variance, tas_variance, offset);
|
||||
if (!ahrs.get_variances(vel_variance, position_variance, height_variance, mag_variance, tas_variance, offset)) {
|
||||
return false;
|
||||
};
|
||||
|
||||
const float mag_max = fmaxf(fmaxf(mag_variance.x,mag_variance.y),mag_variance.z);
|
||||
|
||||
|
Loading…
Reference in New Issue
Block a user