5#include <QtCore/QTimer>
6#include <QtCore/QDateTime>
11 : m_compId(componentid)
12 , m_severity(severity)
21 case MAV_SEVERITY_EMERGENCY:
22 case MAV_SEVERITY_ALERT:
23 case MAV_SEVERITY_CRITICAL:
24 case MAV_SEVERITY_ERROR:
34 , m_chunkedStatusTextTimer(new QTimer(this))
38 m_chunkedStatusTextTimer->setSingleShot(
true);
39 m_chunkedStatusTextTimer->setInterval(1000);
40 (void) connect(m_chunkedStatusTextTimer, &QTimer::timeout,
this, &StatusTextHandler::_chunkedStatusTextTimeout);
55 mavlink_statustext_t statusText;
56 mavlink_msg_statustext_decode(&message, &statusText);
58 char buffer[MAVLINK_MSG_STATUSTEXT_FIELD_TEXT_LEN + 1];
59 memcpy(buffer, statusText.text, MAVLINK_MSG_STATUSTEXT_FIELD_TEXT_LEN);
60 buffer[MAVLINK_MSG_STATUSTEXT_FIELD_TEXT_LEN] =
'\0';
62 return QString(buffer);
69 (void) result.prepend(message->getFormattedText());
77 qDeleteAll(m_messages);
84 _handleTextMessage(0);
90 const MessageType type = m_messageType;
96 m_messageType = MessageType::MessageNone;
102 if (type != m_messageType) {
110 const MessageType prevMessagetype = m_messageType;
116 m_messageType = MessageType::MessageWarning;
118 m_messageType = MessageType::MessageNormal;
120 m_messageType = MessageType::MessageNone;
127 if (prevMessagetype != m_messageType) {
134 QString htmlText(text);
136 (void) htmlText.replace(
"\n",
"<br/>");
139 if (!description.isEmpty()) {
140 QString htmlDescription(description);
141 (void) htmlDescription.replace(
"\n",
"<br/>");
142 (void) htmlText.append(QStringLiteral(
"<br/><small><small>"));
143 (void) htmlText.append(htmlDescription);
144 (void) htmlText.append(QStringLiteral(
"</small></small>"));
147 if (m_activeComponent == MAV_COMPONENT::MAV_COMPONENT_ENUM_END) {
148 m_activeComponent = compId;
151 if (compId != m_activeComponent) {
155 MessageType messageType = MessageType::MessageNone;
163 case MAV_SEVERITY_EMERGENCY:
164 case MAV_SEVERITY_ALERT:
165 case MAV_SEVERITY_CRITICAL:
166 case MAV_SEVERITY_ERROR:
167 style = QStringLiteral(
"<#E>");
168 messageType = MessageType::MessageError;
171 case MAV_SEVERITY_NOTICE:
172 case MAV_SEVERITY_WARNING:
173 style = QStringLiteral(
"<#I>");
174 messageType = MessageType::MessageWarning;
178 style = QStringLiteral(
"<#N>");
179 messageType = MessageType::MessageNormal;
183 QString severityText;
185 case MAV_SEVERITY_EMERGENCY:
186 severityText = tr(
"EMERGENCY");
189 case MAV_SEVERITY_ALERT:
190 severityText = tr(
"ALERT");
193 case MAV_SEVERITY_CRITICAL:
194 severityText = tr(
"Critical");
197 case MAV_SEVERITY_ERROR:
198 severityText = tr(
"Error");
201 case MAV_SEVERITY_WARNING:
202 severityText = tr(
"Warning");
205 case MAV_SEVERITY_NOTICE:
206 severityText = tr(
"Notice");
209 case MAV_SEVERITY_INFO:
210 severityText = tr(
"Info");
213 case MAV_SEVERITY_DEBUG:
214 severityText = tr(
"Debug");
218 qCWarning(StatusTextHandlerLog) << Q_FUNC_INFO <<
"Invalid MAV_SEVERITY";
224 compString = QString(
"COMP:%1").arg(compId);
227 const QString dateString = QDateTime::currentDateTime().toString(
"hh:mm:ss.zzz");
229 const QString formatText = QString(
"<font style=\"%1\">[%2 %3] %4: %5</font><br/>").arg(style, dateString, compString, severityText, htmlText);
236 (void) m_messages.append(message);
237 const uint32_t count = m_messages.count();
239 _handleTextMessage(count, messageType);
248 if (message.msgid != MAVLINK_MSG_ID_STATUSTEXT) {
252 _handleStatusText(message);
257 mavlink_statustext_t statustext;
258 mavlink_msg_statustext_decode(&message, &statustext);
261 const bool includesNullTerminator = messageText.length() < MAVLINK_MSG_STATUSTEXT_FIELD_TEXT_LEN;
263 const MAV_COMPONENT compId =
static_cast<MAV_COMPONENT
>(message.compid);
264 if (m_chunkedStatusTextInfoMap.contains(compId) && (m_chunkedStatusTextInfoMap.value(compId).chunkId != statustext.id)) {
266 (void) m_chunkedStatusTextInfoMap.value(compId).rgMessageChunks.append(QString());
267 _chunkedStatusTextCompleted(compId);
270 if (statustext.id == 0) {
272 ChunkedStatusTextInfo_t chunkedInfo;
273 chunkedInfo.chunkId = 0;
274 chunkedInfo.severity =
static_cast<MAV_SEVERITY
>(statustext.severity);
275 (void) chunkedInfo.rgMessageChunks.append(messageText);
276 (void) m_chunkedStatusTextInfoMap.insert(compId, chunkedInfo);
278 if (m_chunkedStatusTextInfoMap.contains(compId)) {
280 QStringList& chunks = m_chunkedStatusTextInfoMap[compId].rgMessageChunks;
281 if (statustext.chunk_seq > chunks.size()) {
283 for (
size_t i = chunks.size(); i < statustext.chunk_seq; i++) {
284 (void) chunks.append(QString());
288 (void) chunks.append(messageText);
291 ChunkedStatusTextInfo_t chunkedInfo;
292 chunkedInfo.chunkId = statustext.id;
293 chunkedInfo.severity =
static_cast<MAV_SEVERITY
>(statustext.severity);
294 (void) chunkedInfo.rgMessageChunks.append(messageText);
295 (void) m_chunkedStatusTextInfoMap.insert(compId, chunkedInfo);
298 m_chunkedStatusTextTimer->start();
301 if ((statustext.id == 0) || includesNullTerminator) {
302 m_chunkedStatusTextTimer->stop();
303 _chunkedStatusTextCompleted(compId);
307void StatusTextHandler::_chunkedStatusTextTimeout()
309 for (
auto compId : m_chunkedStatusTextInfoMap.keys()) {
310 auto& chunkedInfo = m_chunkedStatusTextInfoMap[compId];
311 (void) chunkedInfo.rgMessageChunks.append(QString());
312 _chunkedStatusTextCompleted(compId);
316void StatusTextHandler::_chunkedStatusTextCompleted(MAV_COMPONENT compId)
318 const ChunkedStatusTextInfo_t& chunkedInfo = m_chunkedStatusTextInfoMap.value(compId);
319 const MAV_SEVERITY severity = chunkedInfo.severity;
322 for (
const QString& chunk : std::as_const(chunkedInfo.rgMessageChunks)) {
323 if (chunk.isEmpty()) {
324 (void) messageText.append(tr(
" ... ",
"Indicates missing chunk from chunked STATUS_TEXT"));
326 (void) messageText.append(chunk);
330 (void) m_chunkedStatusTextInfoMap.remove(compId);
335void StatusTextHandler::_handleTextMessage(uint32_t newCount, MessageType messageType)
342 switch (messageType) {
343 case MessageType::MessageNormal:
347 case MessageType::MessageWarning:
351 case MessageType::MessageError:
356 case MessageType::MessageNone:
358 qCWarning(StatusTextHandlerLog) << Q_FUNC_INFO <<
"Invalid MessageType";
364 m_messageCount = count;
369 MessageType newMessageType = MessageType::MessageNone;
371 newMessageType = MessageType::MessageError;
373 newMessageType = MessageType::MessageWarning;
375 newMessageType = MessageType::MessageNormal;
378 if (newMessageType != m_messageType) {
379 m_messageType = newMessageType;
struct __mavlink_message mavlink_message_t
#define QGC_LOGGING_CATEGORY(name, categoryStr)
StatusTextHandler(QObject *parent=nullptr)
void handleHTMLEscapedTextMessage(MAV_COMPONENT componentid, MAV_SEVERITY severity, const QString &text, const QString &description)
const QList< StatusText * > & messages() 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)
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 severityIsError() const
void setFormatedText(const QString &formatedText)