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();