4#include <QtCore/QTimer>
5#include <QtCore/QDateTime>
10 : m_compId(componentid)
11 , m_severity(severity)
20 case MAV_SEVERITY_EMERGENCY:
21 case MAV_SEVERITY_ALERT:
22 case MAV_SEVERITY_CRITICAL:
23 case MAV_SEVERITY_ERROR:
33 , m_chunkedStatusTextTimer(new QTimer(this))
37 m_chunkedStatusTextTimer->setSingleShot(
true);
38 m_chunkedStatusTextTimer->setInterval(1000);
39 (void) connect(m_chunkedStatusTextTimer, &QTimer::timeout,
this, &StatusTextHandler::_chunkedStatusTextTimeout);
54 mavlink_statustext_t statusText;
55 mavlink_msg_statustext_decode(&message, &statusText);
57 char buffer[MAVLINK_MSG_STATUSTEXT_FIELD_TEXT_LEN + 1];
58 memcpy(buffer, statusText.text, MAVLINK_MSG_STATUSTEXT_FIELD_TEXT_LEN);
59 buffer[MAVLINK_MSG_STATUSTEXT_FIELD_TEXT_LEN] =
'\0';
61 return QString(buffer);
68 (void) result.prepend(message->getFormattedText());
76 qDeleteAll(m_messages);
83 _handleTextMessage(0);
89 const MessageType type = m_messageType;
95 m_messageType = MessageType::MessageNone;
101 if (type != m_messageType) {
109 const MessageType prevMessagetype = m_messageType;
115 m_messageType = MessageType::MessageWarning;
117 m_messageType = MessageType::MessageNormal;
119 m_messageType = MessageType::MessageNone;
126 if (prevMessagetype != m_messageType) {
133 QString htmlText(text);
135 (void) htmlText.replace(
"\n",
"<br/>");
138 if (!description.isEmpty()) {
139 QString htmlDescription(description);
140 (void) htmlDescription.replace(
"\n",
"<br/>");
141 (void) htmlText.append(QStringLiteral(
"<br/><small><small>"));
142 (void) htmlText.append(htmlDescription);
143 (void) htmlText.append(QStringLiteral(
"</small></small>"));
146 if (m_activeComponent == MAV_COMPONENT::MAV_COMPONENT_ENUM_END) {
147 m_activeComponent = compId;
150 if (compId != m_activeComponent) {
154 MessageType messageType = MessageType::MessageNone;
162 case MAV_SEVERITY_EMERGENCY:
163 case MAV_SEVERITY_ALERT:
164 case MAV_SEVERITY_CRITICAL:
165 case MAV_SEVERITY_ERROR:
166 style = QStringLiteral(
"<#E>");
167 messageType = MessageType::MessageError;
170 case MAV_SEVERITY_NOTICE:
171 case MAV_SEVERITY_WARNING:
172 style = QStringLiteral(
"<#I>");
173 messageType = MessageType::MessageWarning;
177 style = QStringLiteral(
"<#N>");
178 messageType = MessageType::MessageNormal;
182 QString severityText;
184 case MAV_SEVERITY_EMERGENCY:
185 severityText = tr(
"EMERGENCY");
188 case MAV_SEVERITY_ALERT:
189 severityText = tr(
"ALERT");
192 case MAV_SEVERITY_CRITICAL:
193 severityText = tr(
"Critical");
196 case MAV_SEVERITY_ERROR:
197 severityText = tr(
"Error");
200 case MAV_SEVERITY_WARNING:
201 severityText = tr(
"Warning");
204 case MAV_SEVERITY_NOTICE:
205 severityText = tr(
"Notice");
208 case MAV_SEVERITY_INFO:
209 severityText = tr(
"Info");
212 case MAV_SEVERITY_DEBUG:
213 severityText = tr(
"Debug");
217 qCWarning(StatusTextHandlerLog) << Q_FUNC_INFO <<
"Invalid MAV_SEVERITY";
223 compString = QString(
"COMP:%1").arg(compId);
226 const QString dateString = QDateTime::currentDateTime().toString(
"hh:mm:ss.zzz");
228 const QString formatText = QString(
"<font style=\"%1\">[%2 %3] %4: %5</font><br/>").arg(style, dateString, compString, severityText, htmlText);
235 (void) m_messages.append(message);
236 const uint32_t count = m_messages.count();
238 _handleTextMessage(count, messageType);
247 if (message.msgid != MAVLINK_MSG_ID_STATUSTEXT) {
251 _handleStatusText(message);
256 mavlink_statustext_t statustext;
257 mavlink_msg_statustext_decode(&message, &statustext);
260 const bool includesNullTerminator = messageText.length() < MAVLINK_MSG_STATUSTEXT_FIELD_TEXT_LEN;
262 const MAV_COMPONENT compId =
static_cast<MAV_COMPONENT
>(message.compid);
263 if (m_chunkedStatusTextInfoMap.contains(compId) && (m_chunkedStatusTextInfoMap.value(compId).chunkId != statustext.id)) {
265 (void) m_chunkedStatusTextInfoMap.value(compId).rgMessageChunks.append(QString());
266 _chunkedStatusTextCompleted(compId);
269 if (statustext.id == 0) {
271 ChunkedStatusTextInfo_t chunkedInfo;
272 chunkedInfo.chunkId = 0;
273 chunkedInfo.severity =
static_cast<MAV_SEVERITY
>(statustext.severity);
274 (void) chunkedInfo.rgMessageChunks.append(messageText);
275 (void) m_chunkedStatusTextInfoMap.insert(compId, chunkedInfo);
277 if (m_chunkedStatusTextInfoMap.contains(compId)) {
279 QStringList& chunks = m_chunkedStatusTextInfoMap[compId].rgMessageChunks;
280 if (statustext.chunk_seq > chunks.size()) {
282 for (
size_t i = chunks.size(); i < statustext.chunk_seq; i++) {
283 (void) chunks.append(QString());
287 (void) chunks.append(messageText);
290 ChunkedStatusTextInfo_t chunkedInfo;
291 chunkedInfo.chunkId = statustext.id;
292 chunkedInfo.severity =
static_cast<MAV_SEVERITY
>(statustext.severity);
293 (void) chunkedInfo.rgMessageChunks.append(messageText);
294 (void) m_chunkedStatusTextInfoMap.insert(compId, chunkedInfo);
297 m_chunkedStatusTextTimer->start();
300 if ((statustext.id == 0) || includesNullTerminator) {
301 m_chunkedStatusTextTimer->stop();
302 _chunkedStatusTextCompleted(compId);
306void StatusTextHandler::_chunkedStatusTextTimeout()
308 for (
auto compId : m_chunkedStatusTextInfoMap.keys()) {
309 auto& chunkedInfo = m_chunkedStatusTextInfoMap[compId];
310 (void) chunkedInfo.rgMessageChunks.append(QString());
311 _chunkedStatusTextCompleted(compId);
315void StatusTextHandler::_chunkedStatusTextCompleted(MAV_COMPONENT compId)
317 const ChunkedStatusTextInfo_t& chunkedInfo = m_chunkedStatusTextInfoMap.value(compId);
318 const MAV_SEVERITY severity = chunkedInfo.severity;
321 for (
const QString& chunk : std::as_const(chunkedInfo.rgMessageChunks)) {
322 if (chunk.isEmpty()) {
323 (void) messageText.append(tr(
" ... ",
"Indicates missing chunk from chunked STATUS_TEXT"));
325 (void) messageText.append(chunk);
329 (void) m_chunkedStatusTextInfoMap.remove(compId);
334void StatusTextHandler::_handleTextMessage(uint32_t newCount, MessageType messageType)
341 switch (messageType) {
342 case MessageType::MessageNormal:
346 case MessageType::MessageWarning:
350 case MessageType::MessageError:
355 case MessageType::MessageNone:
357 qCWarning(StatusTextHandlerLog) << Q_FUNC_INFO <<
"Invalid MessageType";
363 m_messageCount = count;
368 MessageType newMessageType = MessageType::MessageNone;
370 newMessageType = MessageType::MessageError;
372 newMessageType = MessageType::MessageWarning;
374 newMessageType = MessageType::MessageNormal;
377 if (newMessageType != m_messageType) {
378 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)