QGroundControl
Ground Control Station for MAVLink Drones
Loading...
Searching...
No Matches
StatusTextHandler.h
Go to the documentation of this file.
1#pragma once
2
3#include <QtCore/QList>
4#include <QtCore/QObject>
5#include <QtCore/QLoggingCategory>
6
7#include "MAVLinkLib.h"
8
9Q_DECLARE_LOGGING_CATEGORY(StatusTextHandlerLog)
10
12class QTimer;
13
15{
16public:
17 StatusText(MAV_COMPONENT componentid, MAV_SEVERITY severity, const QString &text);
18
19 bool severityIsError() const;
20
21 MAV_COMPONENT getComponentID() const { return m_compId; }
22 MAV_SEVERITY getSeverity() const { return m_severity; }
23 QString getText() const { return m_text; }
24 QString getFormattedText() const { return m_formatedText; }
25
26 void setFormatedText(const QString &formatedText) { m_formatedText = formatedText; }
27
28private:
29 MAV_COMPONENT m_compId;
30 MAV_SEVERITY m_severity;
31 QString m_text;
32 QString m_formatedText;
33};
34
35class StatusTextHandler : public QObject
36{
37 Q_OBJECT
38
39 enum class MessageType {
40 MessageNone,
41 MessageNormal,
42 MessageWarning,
43 MessageError
44 };
45
46public:
47 explicit StatusTextHandler(QObject *parent = nullptr);
49
50 void mavlinkMessageReceived(const mavlink_message_t &message);
51 void handleHTMLEscapedTextMessage(MAV_COMPONENT componentid, MAV_SEVERITY severity, const QString &text, const QString &description);
52
53 void clearMessages();
54 void resetAllMessages();
56
57 const QList<StatusText*>& messages() const { return m_messages; }
58 QString formattedMessages() const;
59
60 bool messageTypeNone() const { return (m_messageType == MessageType::MessageNone); }
61 bool messageTypeNormal() const { return (m_messageType == MessageType::MessageNormal); }
62 bool messageTypeWarning() const { return (m_messageType == MessageType::MessageWarning); }
63 bool messageTypeError() const { return (m_messageType == MessageType::MessageError); }
64
65 uint32_t getErrorCount() const { return m_errorCount; }
66 uint32_t getErrorCountTotal() const { return m_errorCountTotal; }
67 uint32_t getWarningCount() const { return m_warningCount; }
68 uint32_t getNormalCount() const { return m_normalCount; }
69 uint32_t messageCount() const { return m_messageCount; }
70
71 static QString getMessageText(const mavlink_message_t &message);
72
73signals:
74 void newFormattedMessage(QString message);
75 void textMessageReceived(MAV_COMPONENT componentid, MAV_SEVERITY severity, QString text, QString description);
76 void messageCountChanged(uint32_t newCount);
78 void newErrorMessage(QString message);
79
80private slots:
81 void _chunkedStatusTextTimeout();
82
83private:
84 void _handleStatusText(const mavlink_message_t &message);
85 void _handleTextMessage(uint32_t newCount, MessageType messageType = MessageType::MessageNone);
86 void _chunkedStatusTextCompleted(MAV_COMPONENT compId);
87
88 QTimer *m_chunkedStatusTextTimer = nullptr;
89
90 bool m_multiComp = false;
91 MAV_COMPONENT m_activeComponent = MAV_COMPONENT::MAV_COMPONENT_ENUM_END;
92 uint32_t m_errorCount = 0;
93 uint32_t m_errorCountTotal = 0;
94 uint32_t m_warningCount = 0;
95 uint32_t m_normalCount = 0;
96 uint32_t m_messageCount = 0;
97
98 QVector<StatusText*> m_messages;
99
100 MessageType m_messageType = MessageType::MessageNone;
101
102 typedef struct __ChunkedStatusTextInfo {
103 uint16_t chunkId;
104 MAV_SEVERITY severity;
105 QStringList rgMessageChunks;
106 } ChunkedStatusTextInfo_t;
107
108 QMap<MAV_COMPONENT, ChunkedStatusTextInfo_t> m_chunkedStatusTextInfoMap;
109};
Q_DECLARE_LOGGING_CATEGORY(AndroidSerialLog)
struct __mavlink_message mavlink_message_t
bool messageTypeNone() const
bool messageTypeError() const
void handleHTMLEscapedTextMessage(MAV_COMPONENT componentid, MAV_SEVERITY severity, const QString &text, const QString &description)
const QList< StatusText * > & messages() const
bool messageTypeNormal() const
void newErrorMessage(QString message)
static QString getMessageText(const mavlink_message_t &message)
uint32_t getErrorCount() const
void mavlinkMessageReceived(const mavlink_message_t &message)
void messageCountChanged(uint32_t newCount)
uint32_t getErrorCountTotal() const
void textMessageReceived(MAV_COMPONENT componentid, MAV_SEVERITY severity, QString text, QString description)
uint32_t messageCount() const
uint32_t getWarningCount() const
uint32_t getNormalCount() const
void newFormattedMessage(QString message)
QString formattedMessages() const
void messageTypeChanged()
bool messageTypeWarning() const
MAV_COMPONENT getComponentID() const
bool severityIsError() const
void setFormatedText(const QString &formatedText)
QString getFormattedText() const
QString getText() const
MAV_SEVERITY getSeverity() const