diff --git a/libraries/AP_ADSB/AP_ADSB.cpp b/libraries/AP_ADSB/AP_ADSB.cpp index 3c8e55bfe1..507d49f8eb 100644 --- a/libraries/AP_ADSB/AP_ADSB.cpp +++ b/libraries/AP_ADSB/AP_ADSB.cpp @@ -844,12 +844,12 @@ void AP_ADSB::set_callsign(const char* str, const bool append_icao) void AP_ADSB::push_sample(adsb_vehicle_t &vehicle) { - samples.push_back(vehicle); + samples.push(vehicle); } bool AP_ADSB::next_sample(adsb_vehicle_t &vehicle) { - return samples.pop_front(vehicle); + return samples.pop(vehicle); } void AP_ADSB::handle_message(const mavlink_channel_t chan, const mavlink_message_t &msg) diff --git a/libraries/AP_ADSB/AP_ADSB.h b/libraries/AP_ADSB/AP_ADSB.h index 747345afee..891191c521 100644 --- a/libraries/AP_ADSB/AP_ADSB.h +++ b/libraries/AP_ADSB/AP_ADSB.h @@ -21,13 +21,12 @@ Tom Pittenger, November 2015 */ +#include #include #include #include #include -#include - class AP_ADSB { public: AP_ADSB() @@ -189,7 +188,7 @@ private: AP_Int32 _special_ICAO_target; static const uint8_t max_samples = 30; - AP_Buffer samples; + ObjectBuffer samples{max_samples}; void push_sample(adsb_vehicle_t &vehicle);