From 78c1f51f1120a8c6ef9d1a4b79f3508225e2129c Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?Beat=20K=C3=BCng?= Date: Fri, 12 May 2017 14:26:48 +0200 Subject: [PATCH] mavlink main: remove mission_manager, param manager, ftp & log handler Will be moved to the receiver thread --- src/modules/mavlink/mavlink_main.cpp | 43 ++-------------------------- src/modules/mavlink/mavlink_main.h | 8 ------ 2 files changed, 3 insertions(+), 48 deletions(-) diff --git a/src/modules/mavlink/mavlink_main.cpp b/src/modules/mavlink/mavlink_main.cpp index 14b8c03ca2..b49130f294 100644 --- a/src/modules/mavlink/mavlink_main.cpp +++ b/src/modules/mavlink/mavlink_main.cpp @@ -194,10 +194,6 @@ Mavlink::Mavlink() : _main_loop_delay(1000), _subscriptions(nullptr), _streams(nullptr), - _mission_manager(nullptr), - _parameters_manager(nullptr), - _mavlink_ftp(nullptr), - _mavlink_log_handler(nullptr), _mavlink_shell(nullptr), _mavlink_ulog(nullptr), _mavlink_ulog_stop_requested(false), @@ -1234,17 +1230,9 @@ Mavlink::handle_message(const mavlink_message_t *msg) return; } - /* handle packet with mission manager */ - _mission_manager->handle_message(msg); - - /* handle packet with parameter component */ - _parameters_manager->handle_message(msg); - - /* handle packet with ftp component */ - _mavlink_ftp->handle_message(msg); - - /* handle packet with log component */ - _mavlink_log_handler->handle_message(msg); + /* + * NOTE: this is called from the receiver thread + */ if (get_forwarding_on()) { /* forward any messages to other mavlink instances */ @@ -1960,29 +1948,6 @@ Mavlink::task_main(int argc, char *argv[]) } - /* PARAM_VALUE stream */ - _parameters_manager = (MavlinkParametersManager *) MavlinkParametersManager::new_instance(this); - _parameters_manager->set_interval(interval_from_rate(300.0f)); - LL_APPEND(_streams, _parameters_manager); - - /* MAVLINK_FTP stream */ - _mavlink_ftp = (MavlinkFTP *) MavlinkFTP::new_instance(this); - _mavlink_ftp->set_interval(interval_from_rate(80.0f)); - LL_APPEND(_streams, _mavlink_ftp); - - /* MAVLINK_Log_Handler */ - _mavlink_log_handler = (MavlinkLogHandler *) MavlinkLogHandler::new_instance(this); - _mavlink_log_handler->set_interval(interval_from_rate(80.0f)); - LL_APPEND(_streams, _mavlink_log_handler); - - /* MISSION_STREAM stream, actually sends all MISSION_XXX messages at some rate depending on - * remote requests rate. Rate specified here controls how much bandwidth we will reserve for - * mission messages. */ - _mission_manager = (MavlinkMissionManager *) MavlinkMissionManager::new_instance(this); - _mission_manager->set_interval(interval_from_rate(10.0f)); - _mission_manager->set_verbose(_verbose); - LL_APPEND(_streams, _mission_manager); - switch (_mode) { case MAVLINK_MODE_NORMAL: configure_stream("SYS_STATUS", 1.0f); @@ -2145,8 +2110,6 @@ Mavlink::task_main(int argc, char *argv[]) update_rate_mult(); - _mission_manager->check_active_mission(); - if (param_sub->update(¶m_time, nullptr)) { /* parameters updated */ mavlink_update_system(); diff --git a/src/modules/mavlink/mavlink_main.h b/src/modules/mavlink/mavlink_main.h index a3a709f9bf..5310bb601b 100644 --- a/src/modules/mavlink/mavlink_main.h +++ b/src/modules/mavlink/mavlink_main.h @@ -65,10 +65,6 @@ #include "mavlink_orb_subscription.h" #include "mavlink_stream.h" #include "mavlink_messages.h" -#include "mavlink_mission.h" -#include "mavlink_parameters.h" -#include "mavlink_ftp.h" -#include "mavlink_log_handler.h" #include "mavlink_shell.h" #include "mavlink_ulog.h" @@ -480,10 +476,6 @@ private: MavlinkOrbSubscription *_subscriptions; MavlinkStream *_streams; - MavlinkMissionManager *_mission_manager; - MavlinkParametersManager *_parameters_manager; - MavlinkFTP *_mavlink_ftp; - MavlinkLogHandler *_mavlink_log_handler; MavlinkShell *_mavlink_shell; MavlinkULog *_mavlink_ulog; volatile bool _mavlink_ulog_stop_requested;