From bb25e4f6a317c018d60654a9b3432344339d0e2b Mon Sep 17 00:00:00 2001 From: Randy Mackay Date: Tue, 20 Oct 2020 13:25:15 +0900 Subject: [PATCH] AP_RCTelemetry: integrate ahrs::get_variances change offset is no longer returned --- libraries/AP_RCTelemetry/AP_RCTelemetry.cpp | 3 +-- 1 file changed, 1 insertion(+), 2 deletions(-) diff --git a/libraries/AP_RCTelemetry/AP_RCTelemetry.cpp b/libraries/AP_RCTelemetry/AP_RCTelemetry.cpp index f0fb270300..40921309b3 100644 --- a/libraries/AP_RCTelemetry/AP_RCTelemetry.cpp +++ b/libraries/AP_RCTelemetry/AP_RCTelemetry.cpp @@ -216,11 +216,10 @@ void AP_RCTelemetry::check_ekf_status(void) bool get_variance; float velVar, posVar, hgtVar, tasVar; Vector3f magVar; - Vector2f offset; { AP_AHRS &_ahrs = AP::ahrs(); WITH_SEMAPHORE(_ahrs.get_semaphore()); - get_variance = _ahrs.get_variances(velVar, posVar, hgtVar, magVar, tasVar, offset); + get_variance = _ahrs.get_variances(velVar, posVar, hgtVar, magVar, tasVar); } if (get_variance) { uint32_t now = AP_HAL::millis();