AP_ADSB: use baro singleton

This commit is contained in:
Peter Barker 2018-03-09 08:15:12 +11:00 committed by Lucas De Marchi
parent 0675f41d1e
commit 02205a0cb3
1 changed files with 1 additions and 1 deletions

View File

@ -506,7 +506,7 @@ void AP_ADSB::send_dynamic_out(const mavlink_channel_t chan)
const uint64_t gps_time = gps.time_epoch_usec();
const uint32_t utcTime = gps_time / 1000000ULL;
const AP_Baro &baro = AP::ahrs().get_baro();
const AP_Baro &baro = AP::baro();
int32_t altPres = INT_MAX;
if (baro.healthy()) {
// Altitude difference between 101325 (Pascals) and current pressure. Result in millimeters