From a55c40949b5ea9d2b5b0844de92fc66e01dbf282 Mon Sep 17 00:00:00 2001 From: Peter Barker Date: Wed, 19 Jun 2019 14:31:40 +1000 Subject: [PATCH] GCS_MAVLink: remove pointless protocol parameter to setup_uart --- libraries/GCS_MAVLink/GCS.h | 3 +-- libraries/GCS_MAVLink/GCS_Common.cpp | 10 ++++++---- 2 files changed, 7 insertions(+), 6 deletions(-) diff --git a/libraries/GCS_MAVLink/GCS.h b/libraries/GCS_MAVLink/GCS.h index c0a29fba23..68b4502ba5 100644 --- a/libraries/GCS_MAVLink/GCS.h +++ b/libraries/GCS_MAVLink/GCS.h @@ -9,7 +9,6 @@ #include #include #include "MAVLink_routing.h" -#include #include #include #include @@ -297,7 +296,7 @@ public: void update_receive(uint32_t max_time_us=1000); void update_send(); void init(AP_HAL::UARTDriver *port, mavlink_channel_t mav_chan); - void setup_uart(AP_SerialManager::SerialProtocol protocol, uint8_t instance); + void setup_uart(uint8_t instance); void send_message(enum ap_message id); void send_text(MAV_SEVERITY severity, const char *fmt, ...) const; void send_textv(MAV_SEVERITY severity, const char *fmt, va_list arg_list) const; diff --git a/libraries/GCS_MAVLink/GCS_Common.cpp b/libraries/GCS_MAVLink/GCS_Common.cpp index 93e3b7ec44..80329ad91c 100644 --- a/libraries/GCS_MAVLink/GCS_Common.cpp +++ b/libraries/GCS_MAVLink/GCS_Common.cpp @@ -28,6 +28,7 @@ #include #include #include +#include #include #include #include @@ -105,12 +106,13 @@ GCS_MAVLINK::init(AP_HAL::UARTDriver *port, mavlink_channel_t mav_chan) setup a UART, handling begin() and init() */ void -GCS_MAVLINK::setup_uart(AP_SerialManager::SerialProtocol protocol, uint8_t instance) +GCS_MAVLINK::setup_uart(uint8_t instance) { // search for serial port const AP_SerialManager& serial_manager = AP::serialmanager(); - AP_HAL::UARTDriver *uart; - uart = serial_manager.find_serial(protocol, instance); + const AP_SerialManager::SerialProtocol protocol = AP_SerialManager::SerialProtocol_MAVLink; + + AP_HAL::UARTDriver *uart = serial_manager.find_serial(protocol, instance); if (uart == nullptr) { // return immediately if not found return; @@ -2273,7 +2275,7 @@ void GCS::send_mission_item_reached_message(uint16_t mission_index) void GCS::setup_uarts() { for (uint8_t i = 1; i < MAVLINK_COMM_NUM_BUFFERS; i++) { - chan(i).setup_uart(AP_SerialManager::SerialProtocol_MAVLink, i); + chan(i).setup_uart(i); } frsky.init();