Browse Source

AP_Hott_Telem: cope with BARO_MAX_INSTANCES = 1

gps-1.3.1
Tatsuya Yamaguchi 4 years ago committed by Peter Barker
parent
commit
f249fe7eb2
  1. 2
      libraries/AP_Hott_Telem/AP_Hott_Telem.cpp

2
libraries/AP_Hott_Telem/AP_Hott_Telem.cpp

@ -128,9 +128,11 @@ void AP_Hott_Telem::send_EAM(void) @@ -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;

Loading…
Cancel
Save