AP_Hott_Telem: cope with BARO_MAX_INSTANCES = 1

This commit is contained in:
Tatsuya Yamaguchi 2021-08-31 10:46:27 +09:00 committed by Peter Barker
parent f3173174f3
commit f249fe7eb2
1 changed files with 2 additions and 0 deletions

View File

@ -128,9 +128,11 @@ void AP_Hott_Telem::send_EAM(void)
const AP_Baro &baro = AP::baro();
msg.temp1 = uint8_t(baro.get_temperature(0) + 20.5);
#if BARO_MAX_INSTANCES > 1
if (baro.healthy(1)) {
msg.temp2 = uint8_t(baro.get_temperature(1) + 20.5);
}
#endif
AP_AHRS &ahrs = AP::ahrs();
float alt = 0;