Browse Source

AP_ADSB: use ObjectBuffer in place of AP_Buffer

master
Peter Barker 5 years ago committed by Andrew Tridgell
parent
commit
08623c1712
  1. 4
      libraries/AP_ADSB/AP_ADSB.cpp
  2. 5
      libraries/AP_ADSB/AP_ADSB.h

4
libraries/AP_ADSB/AP_ADSB.cpp

@ -844,12 +844,12 @@ void AP_ADSB::set_callsign(const char* str, const bool append_icao) @@ -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)

5
libraries/AP_ADSB/AP_ADSB.h

@ -21,13 +21,12 @@ @@ -21,13 +21,12 @@
Tom Pittenger, November 2015
*/
#include <AP_HAL/AP_HAL.h>
#include <AP_Common/AP_Common.h>
#include <AP_Param/AP_Param.h>
#include <AP_Common/Location.h>
#include <GCS_MAVLink/GCS_MAVLink.h>
#include <AP_Buffer/AP_Buffer.h>
class AP_ADSB {
public:
AP_ADSB()
@ -189,7 +188,7 @@ private: @@ -189,7 +188,7 @@ private:
AP_Int32 _special_ICAO_target;
static const uint8_t max_samples = 30;
AP_Buffer<adsb_vehicle_t, max_samples> samples;
ObjectBuffer<adsb_vehicle_t> samples{max_samples};
void push_sample(adsb_vehicle_t &vehicle);

Loading…
Cancel
Save