From b6810006eb8afa45e4dde9c0705d89100a7a4783 Mon Sep 17 00:00:00 2001 From: Tom Pittenger Date: Tue, 16 Aug 2016 16:18:58 -0700 Subject: [PATCH] AP_ADSB: move mavlink msg handling into library --- libraries/AP_ADSB/AP_ADSB.cpp | 23 +++++++++++++++++++++-- libraries/AP_ADSB/AP_ADSB.h | 14 ++++++++------ 2 files changed, 29 insertions(+), 8 deletions(-) diff --git a/libraries/AP_ADSB/AP_ADSB.cpp b/libraries/AP_ADSB/AP_ADSB.cpp index c29a7689ae..feffd56a90 100644 --- a/libraries/AP_ADSB/AP_ADSB.cpp +++ b/libraries/AP_ADSB/AP_ADSB.cpp @@ -325,7 +325,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::update_vehicle(const mavlink_message_t* packet) +void AP_ADSB::handle_vehicle(const mavlink_message_t* packet) { if (in_state.vehicle_list == nullptr) { // We are only null when disabled. Updating is inhibited. @@ -559,7 +559,7 @@ void AP_ADSB::send_configure(const mavlink_channel_t chan) * we determine which channel is on so we don't have to send out_state to all channels */ -void AP_ADSB::transceiver_report(const mavlink_channel_t chan, const mavlink_message_t* msg) +void AP_ADSB::handle_transceiver_report(const mavlink_channel_t chan, const mavlink_message_t* msg) { mavlink_uavionix_adsb_transceiver_health_report_t packet {}; mavlink_msg_uavionix_adsb_transceiver_health_report_decode(msg, &packet); @@ -658,3 +658,22 @@ bool AP_ADSB::next_sample(adsb_vehicle_t &vehicle) { return samples.pop_front(vehicle); } + +void AP_ADSB::handle_message(const mavlink_channel_t chan, const mavlink_message_t* msg) +{ + switch (msg->msgid) { + case MAVLINK_MSG_ID_ADSB_VEHICLE: + handle_vehicle(msg); + break; + case MAVLINK_MSG_ID_UAVIONIX_ADSB_TRANSCEIVER_HEALTH_REPORT: + handle_transceiver_report(chan, msg); + break; + + case MAVLINK_MSG_ID_UAVIONIX_ADSB_OUT_CFG: + case MAVLINK_MSG_ID_UAVIONIX_ADSB_OUT_DYNAMIC: + // unhandled, these are outbound packets only + default: + break; + } + +} diff --git a/libraries/AP_ADSB/AP_ADSB.h b/libraries/AP_ADSB/AP_ADSB.h index fd68a6142e..fbf73b1742 100644 --- a/libraries/AP_ADSB/AP_ADSB.h +++ b/libraries/AP_ADSB/AP_ADSB.h @@ -52,12 +52,6 @@ public: // periodic task that maintains vehicle_list void update(void); - // add or update vehicle_list from inbound mavlink msg - void update_vehicle(const mavlink_message_t* msg); - - // handle ADS-B transceiver report - void transceiver_report(mavlink_channel_t chan, const mavlink_message_t* msg); - uint16_t get_vehicle_count() { return in_state.vehicle_count; } // send ADSB_VEHICLE mavlink message, usually as a StreamRate @@ -78,6 +72,9 @@ public: } bool next_sample(adsb_vehicle_t &obstacle); + // mavlink message handler + void handle_message(const mavlink_channel_t chan, const mavlink_message_t* msg); + private: // initialize _vehicle_list @@ -107,6 +104,11 @@ private: void send_configure(const mavlink_channel_t chan); void send_dynamic_out(const mavlink_channel_t chan); + // add or update vehicle_list from inbound mavlink msg + void handle_vehicle(const mavlink_message_t* msg); + + // handle ADS-B transceiver report for ping2020 + void handle_transceiver_report(mavlink_channel_t chan, const mavlink_message_t* msg); // reference to AHRS, so we can ask for our position, // heading and speed