diff --git a/src/modules/mavlink/mavlink_main.cpp b/src/modules/mavlink/mavlink_main.cpp index ac9456d064..17eff600e6 100644 --- a/src/modules/mavlink/mavlink_main.cpp +++ b/src/modules/mavlink/mavlink_main.cpp @@ -250,7 +250,6 @@ Mavlink::Mavlink() : _message_buffer_mutex {}, _send_mutex {}, _param_initialized(false), - _logging_enabled(false), _broadcast_mode(Mavlink::BROADCAST_MODE_OFF), _param_system_id(PARAM_INVALID), _param_component_id(PARAM_INVALID), diff --git a/src/modules/mavlink/mavlink_main.h b/src/modules/mavlink/mavlink_main.h index 5310bb601b..1f791e1e28 100644 --- a/src/modules/mavlink/mavlink_main.h +++ b/src/modules/mavlink/mavlink_main.h @@ -418,13 +418,6 @@ public: bool accepting_commands() { return true; /* non-trivial side effects ((!_config_link_on) || (_mode == MAVLINK_MODE_CONFIG));*/ } - /** - * Whether or not the system should be logging - */ - bool get_logging_enabled() { return _logging_enabled; } - - void set_logging_enabled(bool logging) { _logging_enabled = logging; } - int get_data_rate() { return _datarate; } void set_data_rate(int rate) { if (rate > 0) { _datarate = rate; } } @@ -561,7 +554,6 @@ private: pthread_mutex_t _send_mutex; bool _param_initialized; - bool _logging_enabled; uint32_t _broadcast_mode; param_t _param_system_id; diff --git a/src/modules/mavlink/mavlink_messages.cpp b/src/modules/mavlink/mavlink_messages.cpp index 4a8ed483b4..89942c6329 100644 --- a/src/modules/mavlink/mavlink_messages.cpp +++ b/src/modules/mavlink/mavlink_messages.cpp @@ -534,15 +534,6 @@ protected: const bool updated_cpuload = _cpuload_sub->update(&cpuload); const bool updated_battery = _battery_status_sub->update(&battery_status); - if (updated_status) { - if (status.arming_state >= vehicle_status_s::ARMING_STATE_ARMED) { - _mavlink->set_logging_enabled(true); - - } else { - _mavlink->set_logging_enabled(false); - } - } - if (updated_status || updated_battery || updated_cpuload) { mavlink_sys_status_t msg = {};