From b83ade2b0713b30ba8b56c93e8110782e2d970f3 Mon Sep 17 00:00:00 2001 From: Randy Mackay Date: Tue, 20 Oct 2020 13:24:52 +0900 Subject: [PATCH] Rover: integrate ahrs::get_variances change offset is no longer returned --- Rover/ekf_check.cpp | 3 +-- 1 file changed, 1 insertion(+), 2 deletions(-) diff --git a/Rover/ekf_check.cpp b/Rover/ekf_check.cpp index ebb46f800d..9b89eec79c 100644 --- a/Rover/ekf_check.cpp +++ b/Rover/ekf_check.cpp @@ -94,8 +94,7 @@ bool Rover::ekf_over_threshold() // use EKF to get variance 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); + ahrs.get_variances(vel_variance, position_variance, height_variance, mag_variance, tas_variance); // return true if two of compass, velocity and position variances are over the threshold uint8_t over_thresh_count = 0;