From ed8a30d73ef3306b5bc18f8993600e5d0f85e148 Mon Sep 17 00:00:00 2001 From: Daniel Agar Date: Sat, 14 Nov 2020 21:56:53 -0500 Subject: [PATCH] mavlink: STATUSTEXT directly use mavlink_log subscription - ORB_ID(mavlink_log) increase queue depth now that mavlink ringbuffer is gone --- msg/mavlink_log.msg | 2 +- src/modules/mavlink/mavlink_main.cpp | 11 +-- src/modules/mavlink/mavlink_main.h | 7 -- src/modules/mavlink/mavlink_messages.cpp | 97 +----------------- src/modules/mavlink/streams/STATUSTEXT.hpp | 109 +++++++++++++++++++++ 5 files changed, 115 insertions(+), 111 deletions(-) create mode 100644 src/modules/mavlink/streams/STATUSTEXT.hpp diff --git a/msg/mavlink_log.msg b/msg/mavlink_log.msg index e1ed1e98c9..8f52ec7dbf 100644 --- a/msg/mavlink_log.msg +++ b/msg/mavlink_log.msg @@ -3,4 +3,4 @@ uint64 timestamp # time since system start (microseconds) char[127] text uint8 severity # log level (same as in the linux kernel, starting with 0) -uint8 ORB_QUEUE_LENGTH = 4 +uint8 ORB_QUEUE_LENGTH = 8 diff --git a/src/modules/mavlink/mavlink_main.cpp b/src/modules/mavlink/mavlink_main.cpp index 4b92d0c64b..f3764fb594 100644 --- a/src/modules/mavlink/mavlink_main.cpp +++ b/src/modules/mavlink/mavlink_main.cpp @@ -50,6 +50,7 @@ #include #include +#include #include #include @@ -2151,8 +2152,6 @@ Mavlink::task_main(int argc, char *argv[]) /* command ack */ uORB::Publication command_ack_pub{ORB_ID(vehicle_command_ack)}; - uORB::Subscription mavlink_log_sub{ORB_ID(mavlink_log)}; - vehicle_status_s status{}; status_sub.copy(&status); @@ -2170,7 +2169,7 @@ Mavlink::task_main(int argc, char *argv[]) /* HEARTBEAT is constant rate stream, rate never adjusted */ configure_stream("HEARTBEAT", 1.0f); - /* STATUSTEXT stream is like normal stream but gets messages from logbuffer instead of uORB */ + /* STATUSTEXT stream */ configure_stream("STATUSTEXT", 20.0f); /* COMMAND_LONG stream: use unlimited rate to send all commands */ @@ -2362,12 +2361,6 @@ Mavlink::task_main(int argc, char *argv[]) } } - mavlink_log_s mavlink_log; - - if (mavlink_log_sub.update(&mavlink_log)) { - _logbuffer.put(&mavlink_log); - } - /* check for shell output */ if (_mavlink_shell && _mavlink_shell->available() > 0) { if (get_free_tx_buf() >= MAVLINK_MSG_ID_SERIAL_CONTROL_LEN + MAVLINK_NUM_NON_PAYLOAD_BYTES) { diff --git a/src/modules/mavlink/mavlink_main.h b/src/modules/mavlink/mavlink_main.h index d639a11270..93c6d7e153 100644 --- a/src/modules/mavlink/mavlink_main.h +++ b/src/modules/mavlink/mavlink_main.h @@ -59,7 +59,6 @@ #endif #include -#include #include #include #include @@ -69,10 +68,8 @@ #include #include #include -#include #include #include -#include #include #include #include @@ -437,8 +434,6 @@ public: void update_radio_status(const radio_status_s &radio_status); - ringbuffer::RingBuffer *get_logbuffer() { return &_logbuffer; } - unsigned get_system_type() { return _param_mav_type.get(); } Protocol get_protocol() const { return _protocol; } @@ -565,8 +560,6 @@ private: mavlink_channel_t _channel{MAVLINK_COMM_0}; - ringbuffer::RingBuffer _logbuffer{5, sizeof(mavlink_log_s)}; - pthread_t _receive_thread {}; bool _forwarding_on{false}; diff --git a/src/modules/mavlink/mavlink_messages.cpp b/src/modules/mavlink/mavlink_messages.cpp index 3a17f5a43c..cca97f0f94 100644 --- a/src/modules/mavlink/mavlink_messages.cpp +++ b/src/modules/mavlink/mavlink_messages.cpp @@ -51,7 +51,6 @@ #include #include #include -#include #include #include @@ -74,7 +73,6 @@ #include #include #include -#include #include #include #include @@ -124,6 +122,7 @@ using matrix::wrap_2pi; #include "streams/PING.hpp" #include "streams/PROTOCOL_VERSION.hpp" #include "streams/RAW_RPM.hpp" +#include "streams/STATUSTEXT.hpp" #include "streams/STORAGE_INFORMATION.hpp" #include "streams/WIND_COV.hpp" @@ -464,98 +463,6 @@ protected: } }; -class MavlinkStreamStatustext : public MavlinkStream -{ -public: - const char *get_name() const override - { - return MavlinkStreamStatustext::get_name_static(); - } - - static constexpr const char *get_name_static() - { - return "STATUSTEXT"; - } - - static constexpr uint16_t get_id_static() - { - return MAVLINK_MSG_ID_STATUSTEXT; - } - - uint16_t get_id() override - { - return get_id_static(); - } - - static MavlinkStream *new_instance(Mavlink *mavlink) - { - return new MavlinkStreamStatustext(mavlink); - } - - unsigned get_size() override - { - return _mavlink->get_logbuffer()->empty() ? 0 : (MAVLINK_MSG_ID_STATUSTEXT_LEN + MAVLINK_NUM_NON_PAYLOAD_BYTES); - } - -private: - /* do not allow top copying this class */ - MavlinkStreamStatustext(MavlinkStreamStatustext &) = delete; - MavlinkStreamStatustext &operator = (const MavlinkStreamStatustext &) = delete; - -protected: - int _id{0}; - - explicit MavlinkStreamStatustext(Mavlink *mavlink) : MavlinkStream(mavlink) - {} - - bool send() override - { - if (!_mavlink->get_logbuffer()->empty() && _mavlink->is_connected() && _mavlink->get_free_tx_buf() >= get_size()) { - - mavlink_log_s mavlink_log; - - if (_mavlink->get_logbuffer()->get(&mavlink_log)) { - - mavlink_statustext_t msg{}; - const char *text = mavlink_log.text; - constexpr unsigned max_chunk_size = sizeof(msg.text); - msg.severity = mavlink_log.severity; - msg.chunk_seq = 0; - msg.id = _id++; - unsigned text_size; - - while ((text_size = strlen(text)) > 0) { - unsigned chunk_size = math::min(text_size, max_chunk_size); - - if (chunk_size < max_chunk_size) { - memcpy(&msg.text[0], &text[0], chunk_size); - // pad with zeros - memset(&msg.text[0] + chunk_size, 0, max_chunk_size - chunk_size); - - } else { - memcpy(&msg.text[0], &text[0], chunk_size); - } - - mavlink_msg_statustext_send_struct(_mavlink->get_channel(), &msg); - - if (text_size <= max_chunk_size) { - break; - - } else { - text += max_chunk_size; - } - - msg.chunk_seq += 1; - } - - return true; - } - } - - return false; - } -}; - class MavlinkStreamCommandLong : public MavlinkStream { public: @@ -4377,7 +4284,9 @@ protected: static const StreamListItem streams_list[] = { create_stream_list_item(), +#if defined(STATUSTEXT_HPP) create_stream_list_item(), +#endif // STATUSTEXT_HPP create_stream_list_item(), create_stream_list_item(), create_stream_list_item(), diff --git a/src/modules/mavlink/streams/STATUSTEXT.hpp b/src/modules/mavlink/streams/STATUSTEXT.hpp new file mode 100644 index 0000000000..cfff53cb6a --- /dev/null +++ b/src/modules/mavlink/streams/STATUSTEXT.hpp @@ -0,0 +1,109 @@ +/**************************************************************************** + * + * Copyright (c) 2020 PX4 Development Team. All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * 1. Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * 2. Redistributions in binary form must reproduce the above copyright + * notice, this list of conditions and the following disclaimer in + * the documentation and/or other materials provided with the + * distribution. + * 3. Neither the name PX4 nor the names of its contributors may be + * used to endorse or promote products derived from this software + * without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS + * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED + * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + ****************************************************************************/ + +#ifndef STATUSTEXT_HPP +#define STATUSTEXT_HPP + +#include + +class MavlinkStreamStatustext : public MavlinkStream +{ +public: + static MavlinkStream *new_instance(Mavlink *mavlink) { return new MavlinkStreamStatustext(mavlink); } + + static constexpr const char *get_name_static() { return "STATUSTEXT"; } + static constexpr uint16_t get_id_static() { return MAVLINK_MSG_ID_STATUSTEXT; } + + const char *get_name() const override { return get_name_static(); } + uint16_t get_id() override { return get_id_static(); } + + unsigned get_size() override + { + return _mavlink_log_sub.updated() ? (MAVLINK_MSG_ID_STATUSTEXT_LEN + MAVLINK_NUM_NON_PAYLOAD_BYTES) : 0; + } + +private: + explicit MavlinkStreamStatustext(Mavlink *mavlink) : MavlinkStream(mavlink) {} + + uORB::Subscription _mavlink_log_sub{ORB_ID(mavlink_log)}; + uint16_t _id{0}; + + bool send() override + { + if (_mavlink->is_connected() && (_mavlink->get_free_tx_buf() >= get_size())) { + + mavlink_log_s mavlink_log; + + if (_mavlink_log_sub.update(&mavlink_log)) { + + mavlink_statustext_t msg{}; + const char *text = mavlink_log.text; + constexpr unsigned max_chunk_size = sizeof(msg.text); + msg.severity = mavlink_log.severity; + msg.chunk_seq = 0; + msg.id = _id++; + unsigned text_size; + + while ((text_size = strlen(text)) > 0) { + unsigned chunk_size = math::min(text_size, max_chunk_size); + + if (chunk_size < max_chunk_size) { + memcpy(&msg.text[0], &text[0], chunk_size); + // pad with zeros + memset(&msg.text[0] + chunk_size, 0, max_chunk_size - chunk_size); + + } else { + memcpy(&msg.text[0], &text[0], chunk_size); + } + + mavlink_msg_statustext_send_struct(_mavlink->get_channel(), &msg); + + if (text_size <= max_chunk_size) { + break; + + } else { + text += max_chunk_size; + } + + msg.chunk_seq += 1; + } + + return true; + } + } + + return false; + } +}; + +#endif // STATUSTEXT_HPP