Browse Source

Plane: integrate ahrs::get_variances change

offset is no longer returned
zr-v5.1
Randy Mackay 4 years ago
parent
commit
0362895720
  1. 3
      ArduPlane/ekf_check.cpp

3
ArduPlane/ekf_check.cpp

@ -110,8 +110,7 @@ bool Plane::ekf_over_threshold() @@ -110,8 +110,7 @@ bool Plane::ekf_over_threshold()
// A value above 1.0 means the EKF has rejected that sensor data
float position_variance, vel_variance, height_variance, tas_variance;
Vector3f mag_variance;
Vector2f offset;
if (!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)) {
return false;
};

Loading…
Cancel
Save