diff --git a/libraries/AP_Frsky_Telem/AP_Frsky_SPort_Passthrough.cpp b/libraries/AP_Frsky_Telem/AP_Frsky_SPort_Passthrough.cpp index ee55f8cd50..2f3acb0fb3 100644 --- a/libraries/AP_Frsky_Telem/AP_Frsky_SPort_Passthrough.cpp +++ b/libraries/AP_Frsky_Telem/AP_Frsky_SPort_Passthrough.cpp @@ -567,7 +567,7 @@ uint32_t AP_Frsky_SPort_Passthrough::calc_ap_status(void) { // IMU temperature: offset -19, 0 means temp =< 19°, 63 means temp => 82° uint8_t imu_temp = 0; -#if HAL_INS_ENABLED +#if AP_INERTIALSENSOR_ENABLED imu_temp = (uint8_t) roundf(constrain_float(AP::ins().get_temperature(0), AP_IMU_TEMP_MIN, AP_IMU_TEMP_MAX) - AP_IMU_TEMP_MIN); #endif