From dfee9ca4c63de9c0b2ff2949dcba93e415061ab8 Mon Sep 17 00:00:00 2001 From: Matthias Grob Date: Mon, 27 May 2024 18:11:41 +0200 Subject: [PATCH] MAVLink: remove never used `_mavlink_link_termination_allowed` --- src/modules/mavlink/mavlink_main.cpp | 4 ---- src/modules/mavlink/mavlink_main.h | 2 -- 2 files changed, 6 deletions(-) diff --git a/src/modules/mavlink/mavlink_main.cpp b/src/modules/mavlink/mavlink_main.cpp index 186bfe793631..3abd4f71a2ae 100644 --- a/src/modules/mavlink/mavlink_main.cpp +++ b/src/modules/mavlink/mavlink_main.cpp @@ -1963,10 +1963,6 @@ Mavlink::task_main(int argc, char *argv[]) break; #endif -// case 'e': -// _mavlink_link_termination_allowed = true; -// break; - case 'm': { int mode; diff --git a/src/modules/mavlink/mavlink_main.h b/src/modules/mavlink/mavlink_main.h index 9444b8058a48..17925f8ed8e4 100644 --- a/src/modules/mavlink/mavlink_main.h +++ b/src/modules/mavlink/mavlink_main.h @@ -597,8 +597,6 @@ class Mavlink final : public ModuleParams */ unsigned int _mavlink_param_queue_index{0}; - bool _mavlink_link_termination_allowed{false}; - char *_subscribe_to_stream{nullptr}; float _subscribe_to_stream_rate{0.0f}; ///< rate of stream to subscribe to (0=disable, -1=unlimited, -2=default) bool _udp_initialised{false};