mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-03 06:28:27 -04:00
AP_Hott_Telem: cope with BARO_MAX_INSTANCES = 1
This commit is contained in:
parent
f3173174f3
commit
f249fe7eb2
@ -128,9 +128,11 @@ void AP_Hott_Telem::send_EAM(void)
|
|||||||
|
|
||||||
const AP_Baro &baro = AP::baro();
|
const AP_Baro &baro = AP::baro();
|
||||||
msg.temp1 = uint8_t(baro.get_temperature(0) + 20.5);
|
msg.temp1 = uint8_t(baro.get_temperature(0) + 20.5);
|
||||||
|
#if BARO_MAX_INSTANCES > 1
|
||||||
if (baro.healthy(1)) {
|
if (baro.healthy(1)) {
|
||||||
msg.temp2 = uint8_t(baro.get_temperature(1) + 20.5);
|
msg.temp2 = uint8_t(baro.get_temperature(1) + 20.5);
|
||||||
}
|
}
|
||||||
|
#endif
|
||||||
|
|
||||||
AP_AHRS &ahrs = AP::ahrs();
|
AP_AHRS &ahrs = AP::ahrs();
|
||||||
float alt = 0;
|
float alt = 0;
|
||||||
|
Loading…
Reference in New Issue
Block a user