From 1d0fc4e87c6cacb782cbbdead6f759e37f411186 Mon Sep 17 00:00:00 2001 From: Andrew Tridgell Date: Thu, 28 Dec 2023 09:29:57 +1100 Subject: [PATCH] AP_ExternalAHRS: fixed InertialLabs gyro/accel data this fixes a flapping CI test --- libraries/AP_ExternalAHRS/AP_ExternalAHRS_InertialLabs.cpp | 2 ++ 1 file changed, 2 insertions(+) diff --git a/libraries/AP_ExternalAHRS/AP_ExternalAHRS_InertialLabs.cpp b/libraries/AP_ExternalAHRS/AP_ExternalAHRS_InertialLabs.cpp index a20beb13c0e92..ebf844f32493b 100644 --- a/libraries/AP_ExternalAHRS/AP_ExternalAHRS_InertialLabs.cpp +++ b/libraries/AP_ExternalAHRS/AP_ExternalAHRS_InertialLabs.cpp @@ -438,6 +438,8 @@ bool AP_ExternalAHRS_InertialLabs::check_uart() if (GOT_MSG(ACCEL_DATA_HR) && GOT_MSG(GYRO_DATA_HR)) { AP::ins().handle_external(ins_data); + state.accel = ins_data.accel; + state.gyro = ins_data.gyro; } if (GOT_MSG(GPS_INS_TIME_MS) && GOT_MSG(NUM_SATS) &&