AP_ExternalAHRS: fixed InertialLabs gyro/accel data

this fixes a flapping CI test
This commit is contained in:
Andrew Tridgell 2023-12-28 09:29:57 +11:00
parent 6c24f80669
commit 1d0fc4e87c

View File

@ -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) &&