From df90cee8a02ac2bf93cff6a2e517ed73954e3ab1 Mon Sep 17 00:00:00 2001 From: Andrew Tridgell Date: Wed, 2 Oct 2019 20:54:35 +1000 Subject: [PATCH] AP_ADSB: added handle_adsb_vehicle() API this allows for UAVCAN ADSB adapters --- libraries/AP_ADSB/AP_ADSB.cpp | 22 +++++++++++++++------- libraries/AP_ADSB/AP_ADSB.h | 5 ++++- 2 files changed, 19 insertions(+), 8 deletions(-) diff --git a/libraries/AP_ADSB/AP_ADSB.cpp b/libraries/AP_ADSB/AP_ADSB.cpp index 28fcaed8f1..5dfb7944fd 100644 --- a/libraries/AP_ADSB/AP_ADSB.cpp +++ b/libraries/AP_ADSB/AP_ADSB.cpp @@ -413,7 +413,7 @@ bool AP_ADSB::find_index(const adsb_vehicle_t &vehicle, uint16_t *index) const * Update the vehicle list. If the vehicle is already in the * list then it will update it, otherwise it will be added. */ -void AP_ADSB::handle_vehicle(const mavlink_message_t &packet) +void AP_ADSB::handle_adsb_vehicle(const adsb_vehicle_t &vehicle) { if (in_state.vehicle_list == nullptr) { // We are only null when disabled. Updating is inhibited. @@ -421,8 +421,6 @@ void AP_ADSB::handle_vehicle(const mavlink_message_t &packet) } uint16_t index = in_state.list_size + 1; // initialize with invalid index - adsb_vehicle_t vehicle {}; - mavlink_msg_adsb_vehicle_decode(&packet, &vehicle.info); const Location vehicle_loc = AP_ADSB::get_location(vehicle); const bool my_loc_is_zero = _my_loc.is_zero(); const float my_loc_distance_to_vehicle = _my_loc.get_distance(vehicle_loc); @@ -432,9 +430,6 @@ void AP_ADSB::handle_vehicle(const mavlink_message_t &packet) const bool is_tracked_in_list = find_index(vehicle, &index); const uint32_t now = AP_HAL::millis(); - // note the last time the receiver got a packet from the aircraft - vehicle.last_update_ms = now - (vehicle.info.tslc * 1000); - const uint16_t required_flags_position = ADSB_FLAGS_VALID_COORDS | ADSB_FLAGS_VALID_ALTITUDE; const bool detected_ourself = (out_state.cfg.ICAO_id != 0) && ((uint32_t)out_state.cfg.ICAO_id == vehicle.info.ICAO_address); @@ -500,6 +495,19 @@ void AP_ADSB::handle_vehicle(const mavlink_message_t &packet) } } +/* + * Update the vehicle list. If the vehicle is already in the + * list then it will update it, otherwise it will be added. + */ +void AP_ADSB::handle_vehicle(const mavlink_message_t &packet) +{ + adsb_vehicle_t vehicle {}; + const uint32_t now = AP_HAL::millis(); + mavlink_msg_adsb_vehicle_decode(&packet, &vehicle.info); + vehicle.last_update_ms = now - (vehicle.info.tslc * 1000); + handle_adsb_vehicle(vehicle); +} + /* * Copy a vehicle's data into the list */ @@ -871,7 +879,7 @@ void AP_ADSB::set_callsign(const char* str, const bool append_icao) } -void AP_ADSB::push_sample(adsb_vehicle_t &vehicle) +void AP_ADSB::push_sample(const adsb_vehicle_t &vehicle) { samples.push(vehicle); } diff --git a/libraries/AP_ADSB/AP_ADSB.h b/libraries/AP_ADSB/AP_ADSB.h index 954970bedf..123ce97548 100644 --- a/libraries/AP_ADSB/AP_ADSB.h +++ b/libraries/AP_ADSB/AP_ADSB.h @@ -73,6 +73,9 @@ public: } bool next_sample(adsb_vehicle_t &obstacle); + // handle a adsb_vehicle_t from an external source (used for UAVCAN) + void handle_adsb_vehicle(const adsb_vehicle_t &vehicle); + // mavlink message handler void handle_message(const mavlink_channel_t chan, const mavlink_message_t &msg); @@ -197,7 +200,7 @@ private: static const uint8_t max_samples = 30; ObjectBuffer samples{max_samples}; - void push_sample(adsb_vehicle_t &vehicle); + void push_sample(const adsb_vehicle_t &vehicle); // logging AP_Int8 _log;