39 enum class MessageType {
57 const QList<StatusText*>&
messages()
const {
return m_messages; }
60 bool messageTypeNone()
const {
return (m_messageType == MessageType::MessageNone); }
75 void textMessageReceived(MAV_COMPONENT componentid, MAV_SEVERITY severity, QString text, QString description);
81 void _chunkedStatusTextTimeout();
85 void _handleTextMessage(uint32_t newCount, MessageType messageType = MessageType::MessageNone);
86 void _chunkedStatusTextCompleted(MAV_COMPONENT compId);
88 QTimer *m_chunkedStatusTextTimer =
nullptr;
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;
98 QVector<StatusText*> m_messages;
100 MessageType m_messageType = MessageType::MessageNone;
102 typedef struct __ChunkedStatusTextInfo {
104 MAV_SEVERITY severity;
105 QStringList rgMessageChunks;
106 } ChunkedStatusTextInfo_t;
108 QMap<MAV_COMPONENT, ChunkedStatusTextInfo_t> m_chunkedStatusTextInfoMap;
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 resetErrorLevelMessages()
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
MAV_SEVERITY getSeverity() const