diff --git a/src/modules/mavlink/mavlink_main.cpp b/src/modules/mavlink/mavlink_main.cpp index b065b38e05..5ca2c091e4 100644 --- a/src/modules/mavlink/mavlink_main.cpp +++ b/src/modules/mavlink/mavlink_main.cpp @@ -487,18 +487,6 @@ Mavlink::forward_message(const mavlink_message_t *msg, Mavlink *self) } } -int -Mavlink::get_uart_fd(unsigned index) -{ - Mavlink *inst = get_instance(index); - - if (inst) { - return inst->get_uart_fd(); - } - - return -1; -} - int Mavlink::mavlink_open_uart(const int baud, const char *uart_name, const bool force_flow_control) { diff --git a/src/modules/mavlink/mavlink_main.h b/src/modules/mavlink/mavlink_main.h index b29c901748..4fad5312a8 100644 --- a/src/modules/mavlink/mavlink_main.h +++ b/src/modules/mavlink/mavlink_main.h @@ -164,8 +164,6 @@ public: static void forward_message(const mavlink_message_t *msg, Mavlink *self); - static int get_uart_fd(unsigned index); - int get_uart_fd() const { return _uart_fd; } /**