From 02205a0cb3b8ad4d0ae8ef5c8f653fcde35d60d9 Mon Sep 17 00:00:00 2001 From: Peter Barker Date: Fri, 9 Mar 2018 08:15:12 +1100 Subject: [PATCH] AP_ADSB: use baro singleton --- libraries/AP_ADSB/AP_ADSB.cpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/libraries/AP_ADSB/AP_ADSB.cpp b/libraries/AP_ADSB/AP_ADSB.cpp index 5ca2358faf..dc4e671c3f 100644 --- a/libraries/AP_ADSB/AP_ADSB.cpp +++ b/libraries/AP_ADSB/AP_ADSB.cpp @@ -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