mirror of https://github.com/ArduPilot/ardupilot
AP_ADSB: support for provision of samples to other libraries
This commit is contained in:
parent
4639d12f0e
commit
1cdb97e605
|
@ -432,6 +432,9 @@ void AP_ADSB::update_vehicle(const mavlink_message_t* packet)
|
|||
avoid_state.highest_threat_index = index;
|
||||
}
|
||||
} // if buffer full
|
||||
|
||||
vehicle.last_update_ms = AP_HAL::millis() - vehicle.info.tslc;
|
||||
push_sample(vehicle); // note that set_vehicle modifies vehicle
|
||||
}
|
||||
|
||||
/*
|
||||
|
@ -677,3 +680,13 @@ void AP_ADSB::set_callsign(const char* str, const bool append_icao)
|
|||
out_state.cfg.callsign[sizeof(out_state.cfg.callsign)-1] = 0; // always null terminate just to be sure
|
||||
}
|
||||
|
||||
|
||||
void AP_ADSB::push_sample(adsb_vehicle_t &vehicle)
|
||||
{
|
||||
samples.push_back(vehicle);
|
||||
}
|
||||
|
||||
bool AP_ADSB::next_sample(adsb_vehicle_t &vehicle)
|
||||
{
|
||||
return samples.pop_front(vehicle);
|
||||
}
|
||||
|
|
|
@ -25,6 +25,10 @@
|
|||
#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_AHRS/AP_AHRS.h>
|
||||
|
||||
#include <AP_Buffer/AP_Buffer.h>
|
||||
|
||||
class AP_ADSB
|
||||
{
|
||||
|
@ -84,6 +88,14 @@ public:
|
|||
|
||||
UAVIONIX_ADSB_RF_HEALTH get_transceiver_status(void) { return out_state.status; }
|
||||
|
||||
// extract a location out of a vehicle item
|
||||
Location_Class get_location(const adsb_vehicle_t &vehicle) const;
|
||||
|
||||
bool enabled() const {
|
||||
return _enabled;
|
||||
}
|
||||
bool next_sample(adsb_vehicle_t &obstacle);
|
||||
|
||||
private:
|
||||
|
||||
// initialize _vehicle_list
|
||||
|
@ -95,9 +107,6 @@ private:
|
|||
// compares current vector against vehicle_list to detect threats
|
||||
void perform_threat_detection(void);
|
||||
|
||||
// extract a location out of a vehicle item
|
||||
Location_Class get_location(const adsb_vehicle_t &vehicle) const;
|
||||
|
||||
// return index of given vehicle if ICAO_ADDRESS matches. return -1 if no match
|
||||
bool find_index(const adsb_vehicle_t &vehicle, uint16_t *index) const;
|
||||
|
||||
|
@ -184,4 +193,9 @@ private:
|
|||
float highest_threat_distance;
|
||||
} avoid_state;
|
||||
|
||||
static const uint8_t max_samples = 30;
|
||||
AP_Buffer<adsb_vehicle_t, max_samples> samples;
|
||||
|
||||
void push_sample(adsb_vehicle_t &vehicle);
|
||||
|
||||
};
|
||||
|
|
Loading…
Reference in New Issue