From aab0c3138561c89c15e55f03fe8775c515ebe4f8 Mon Sep 17 00:00:00 2001 From: Andrew Tridgell Date: Wed, 26 Jan 2022 17:36:46 +1100 Subject: [PATCH] AP_DAL: prevent logical loop between AHRS and EKF this prevents the EKF using its own rejecting_airspeed flag --- libraries/AP_DAL/AP_DAL.cpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/libraries/AP_DAL/AP_DAL.cpp b/libraries/AP_DAL/AP_DAL.cpp index c48f6887f4..706cb6ac23 100644 --- a/libraries/AP_DAL/AP_DAL.cpp +++ b/libraries/AP_DAL/AP_DAL.cpp @@ -63,7 +63,7 @@ void AP_DAL::start_frame(AP_DAL::FrameType frametype) _RFRN.fly_forward = ahrs.get_fly_forward(); _RFRN.takeoff_expected = ahrs.get_takeoff_expected(); _RFRN.touchdown_expected = ahrs.get_touchdown_expected(); - _RFRN.ahrs_airspeed_sensor_enabled = AP::ahrs().airspeed_sensor_enabled(); + _RFRN.ahrs_airspeed_sensor_enabled = ahrs.airspeed_sensor_enabled(ahrs.get_active_airspeed_index()); _RFRN.available_memory = hal.util->available_memory(); _RFRN.ahrs_trim = ahrs.get_trim(); #if AP_OPTICALFLOW_ENABLED