mirror of https://github.com/ArduPilot/ardupilot
AP_Frsky_Telem: fix periph-heavy compile errors with different things enabled
This commit is contained in:
parent
d45526ff42
commit
fcfaab4beb
|
@ -546,7 +546,10 @@ bool AP_Frsky_SPort_Passthrough::is_passthrough_byte(const uint8_t byte) const
|
|||
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 = (uint8_t) roundf(constrain_float(AP::ins().get_temperature(0), AP_IMU_TEMP_MIN, AP_IMU_TEMP_MAX) - AP_IMU_TEMP_MIN);
|
||||
uint8_t imu_temp = 0;
|
||||
#if HAL_INS_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
|
||||
|
||||
// control/flight mode number (limit to 31 (0x1F) since the value is stored on 5 bits)
|
||||
uint32_t ap_status = (uint8_t)((gcs().custom_mode()+1) & AP_CONTROL_MODE_LIMIT);
|
||||
|
|
Loading…
Reference in New Issue