mirror of https://github.com/ArduPilot/ardupilot
AP_RCTelemetry: integrate ahrs::get_variances change
offset is no longer returned
This commit is contained in:
parent
4bf4872504
commit
bb25e4f6a3
|
@ -216,11 +216,10 @@ void AP_RCTelemetry::check_ekf_status(void)
|
||||||
bool get_variance;
|
bool get_variance;
|
||||||
float velVar, posVar, hgtVar, tasVar;
|
float velVar, posVar, hgtVar, tasVar;
|
||||||
Vector3f magVar;
|
Vector3f magVar;
|
||||||
Vector2f offset;
|
|
||||||
{
|
{
|
||||||
AP_AHRS &_ahrs = AP::ahrs();
|
AP_AHRS &_ahrs = AP::ahrs();
|
||||||
WITH_SEMAPHORE(_ahrs.get_semaphore());
|
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) {
|
if (get_variance) {
|
||||||
uint32_t now = AP_HAL::millis();
|
uint32_t now = AP_HAL::millis();
|
||||||
|
|
Loading…
Reference in New Issue