From 0362895720c6cd02333b45dbfac40a1322c30347 Mon Sep 17 00:00:00 2001 From: Randy Mackay Date: Tue, 20 Oct 2020 13:24:39 +0900 Subject: [PATCH] Plane: integrate ahrs::get_variances change offset is no longer returned --- ArduPlane/ekf_check.cpp | 3 +-- 1 file changed, 1 insertion(+), 2 deletions(-) diff --git a/ArduPlane/ekf_check.cpp b/ArduPlane/ekf_check.cpp index 620ea0f714..709935babe 100644 --- a/ArduPlane/ekf_check.cpp +++ b/ArduPlane/ekf_check.cpp @@ -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; };