Browse Source

AP_RCTelemetry: integrate ahrs::get_variances change

offset is no longer returned
zr-v5.1
Randy Mackay 4 years ago
parent
commit
bb25e4f6a3
  1. 3
      libraries/AP_RCTelemetry/AP_RCTelemetry.cpp

3
libraries/AP_RCTelemetry/AP_RCTelemetry.cpp

@ -216,11 +216,10 @@ void AP_RCTelemetry::check_ekf_status(void) @@ -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();

Loading…
Cancel
Save