diff --git a/ArduCopter/GCS_Mavlink.cpp b/ArduCopter/GCS_Mavlink.cpp index 4bf3cec298..b71c1e9824 100644 --- a/ArduCopter/GCS_Mavlink.cpp +++ b/ArduCopter/GCS_Mavlink.cpp @@ -955,6 +955,13 @@ void GCS_MAVLINK_Copter::handle_change_alt_request(AP_Mission::Mission_Command & // To-Do: update target altitude for loiter or waypoint controller depending upon nav mode } +void GCS_MAVLINK_Copter::packetReceived(const mavlink_status_t &status, + mavlink_message_t &msg) +{ + copter.avoidance_adsb.handle_msg(msg); + GCS_MAVLINK::packetReceived(status, msg); +} + void GCS_MAVLINK_Copter::handleMessage(mavlink_message_t* msg) { uint8_t result = MAV_RESULT_FAILED; // assume failure. Each messages id is responsible for return ACK or NAK if required diff --git a/ArduCopter/GCS_Mavlink.h b/ArduCopter/GCS_Mavlink.h index bee241f320..9d9400441c 100644 --- a/ArduCopter/GCS_Mavlink.h +++ b/ArduCopter/GCS_Mavlink.h @@ -20,4 +20,6 @@ private: void handle_change_alt_request(AP_Mission::Mission_Command &cmd) override; bool try_send_message(enum ap_message id) override; + void packetReceived(const mavlink_status_t &status, + mavlink_message_t &msg) override; };