diff --git a/src/Vehicle/EventHandler.cc b/src/Vehicle/EventHandler.cc
index 7285f4a..0c8f578 100644
--- a/src/Vehicle/EventHandler.cc
+++ b/src/Vehicle/EventHandler.cc
@@ -45,6 +45,9 @@ EventHandler::EventHandler(QObject* parent, const QString& profile, handle_event
_parser.formatters().param = [](const std::string& content) {
return ""+content+""; };
+ _parser.formatters().escape = [](const std::string& str) {
+ return QString::fromStdString(str).toHtmlEscaped().toStdString(); };
+
events::ReceiveProtocol::Callbacks callbacks{error_cb, _sendRequestCB,
std::bind(&EventHandler::gotEvent, this, std::placeholders::_1), timeout_cb};
_protocol = new events::ReceiveProtocol(callbacks, ourSystemId, ourComponentId, systemId, componentId);
diff --git a/src/Vehicle/Vehicle.cc b/src/Vehicle/Vehicle.cc
index ea4d858..f4c91fe 100644
--- a/src/Vehicle/Vehicle.cc
+++ b/src/Vehicle/Vehicle.cc
@@ -925,7 +925,7 @@ void Vehicle::_chunkedStatusTextCompleted(uint8_t compId)
qgcApp()->toolbox()->audioOutput()->say(messageText);
}
}
- emit textMessageReceived(id(), compId, severity, messageText);
+ emit textMessageReceived(id(), compId, severity, messageText.toHtmlEscaped(), "");
}
void Vehicle::_handleStatusText(mavlink_message_t& message)
@@ -1605,24 +1605,19 @@ void Vehicle::_handleEvent(uint8_t comp_id, std::unique_ptr";
+ message += "\n";
}
if (messageChecks.size() == 1) {
message += messageChecks[0];
} else {
for (const auto& messageCheck : messageChecks) {
- message += "- " + messageCheck + "
";
+ message += "- " + messageCheck + "\n";
}
}
}
- if (message.size() > 0) {
- // TODO: handle this properly in the UI (e.g. with an expand button to display the description, clickable URL's + params)...
- QString msg = QString::fromStdString(message);
- if (description.size() > 0) {
- msg += "
" + QString::fromStdString(description).replace("\n", "
") + "";
- }
- emit textMessageReceived(id(), comp_id, severity, msg);
+ if (!message.empty()) {
+ emit textMessageReceived(id(), comp_id, severity, QString::fromStdString(message), QString::fromStdString(description));
}
}
}
@@ -2030,11 +2025,6 @@ void Vehicle::_handleTextMessage(int newCount)
_messageCount = newCount;
emit messageCountChanged();
}
- QString errMsg = pMh->getLatestError();
- if(errMsg != _latestError) {
- _latestError = errMsg;
- emit latestErrorChanged();
- }
}
void Vehicle::resetAllMessages()
diff --git a/src/Vehicle/Vehicle.h b/src/Vehicle/Vehicle.h
index b8f9b7c..9fc87f0 100644
--- a/src/Vehicle/Vehicle.h
+++ b/src/Vehicle/Vehicle.h
@@ -177,7 +177,6 @@ public:
Q_PROPERTY(int newMessageCount READ newMessageCount NOTIFY newMessageCountChanged)
Q_PROPERTY(int messageCount READ messageCount NOTIFY messageCountChanged)
Q_PROPERTY(QString formattedMessages READ formattedMessages NOTIFY formattedMessagesChanged)
- Q_PROPERTY(QString latestError READ latestError NOTIFY latestErrorChanged)
Q_PROPERTY(bool joystickEnabled READ joystickEnabled WRITE setJoystickEnabled NOTIFY joystickEnabledChanged)
Q_PROPERTY(int flowImageIndex READ flowImageIndex NOTIFY flowImageIndexChanged)
Q_PROPERTY(int rcRSSI READ rcRSSI NOTIFY rcRSSIChanged)
@@ -595,7 +594,6 @@ public:
int newMessageCount () const{ return _currentMessageCount; }
int messageCount () const{ return _messageCount; }
QString formattedMessages ();
- QString latestError () { return _latestError; }
float latitude () { return static_cast(_coordinate.latitude()); }
float longitude () { return static_cast(_coordinate.longitude()); }
bool mavPresent () { return _mav != nullptr; }
@@ -919,7 +917,7 @@ signals:
void capabilityBitsChanged (uint64_t capabilityBits);
void toolIndicatorsChanged ();
void modeIndicatorsChanged ();
- void textMessageReceived (int uasid, int componentid, int severity, QString text);
+ void textMessageReceived (int uasid, int componentid, int severity, QString text, QString description);
void calibrationEventReceived (int uasid, int componentid, int severity, QSharedPointer event);
void checkListStateChanged ();
void messagesReceivedChanged ();
@@ -930,7 +928,6 @@ signals:
void messageCountChanged ();
void formattedMessagesChanged ();
void newFormattedMessage (QString formattedMessage);
- void latestErrorChanged ();
void longitudeChanged ();
void currentConfigChanged ();
void flowImageIndexChanged ();
@@ -1129,7 +1126,6 @@ private:
int _currentWarningCount = 0;
int _currentNormalCount = 0;
MessageType_t _currentMessageType = MessageNone;
- QString _latestError;
int _updateCount = 0;
int _rcRSSI = 255;
double _rcRSSIstore = 255;
diff --git a/src/uas/UASMessageHandler.cc b/src/uas/UASMessageHandler.cc
index 9a4a264..13e9539 100644
--- a/src/uas/UASMessageHandler.cc
+++ b/src/uas/UASMessageHandler.cc
@@ -103,13 +103,19 @@ void UASMessageHandler::_activeVehicleChanged(Vehicle* vehicle)
}
}
-void UASMessageHandler::handleTextMessage(int, int compId, int severity, QString text)
+void UASMessageHandler::handleTextMessage(int, int compId, int severity, QString text, QString description)
{
// Hack to prevent calibration messages from cluttering things up
if (_activeVehicle->px4Firmware() && text.startsWith(QStringLiteral("[cal] "))) {
return;
}
+ text = text.replace("\n", "
");
+ // TODO: handle text + description separately in the UI
+ if (!description.isEmpty()) {
+ text += "
" + description.replace("\n", "
") + "";
+ }
+
// Color the output depending on the message severity. We have 3 distinct cases:
// 1: If we have an ERROR or worse, make it bigger, bolder, and highlight it red.
// 2: If we have a warning or notice, just make it bold and color it orange.
@@ -187,11 +193,7 @@ void UASMessageHandler::handleTextMessage(int, int compId, int severity, QString
if (_multiComp) {
compString = QString(" COMP:%1").arg(compId);
}
- message->_setFormatedText(QString("[%2%3]%4 %5
").arg(style).arg(dateString).arg(compString).arg(severityText).arg(text.toHtmlEscaped()));
-
- if (message->severityIsError()) {
- _latestError = severityText + " " + text;
- }
+ message->_setFormatedText(QString("[%2%3]%4 %5
").arg(style).arg(dateString).arg(compString).arg(severityText).arg(text));
_mutex.unlock();
@@ -202,7 +204,7 @@ void UASMessageHandler::handleTextMessage(int, int compId, int severity, QString
emit textMessageCountChanged(count);
if (_showErrorsInToolbar && message->severityIsError()) {
- _app->showCriticalVehicleMessage(message->getText().toHtmlEscaped());
+ _app->showCriticalVehicleMessage(message->getText());
}
}
diff --git a/src/uas/UASMessageHandler.h b/src/uas/UASMessageHandler.h
index 402eccd..6cb329d 100644
--- a/src/uas/UASMessageHandler.h
+++ b/src/uas/UASMessageHandler.h
@@ -37,7 +37,7 @@ public:
*/
int getSeverity() const { return _severity; }
/**
- * @brief Get message text (e.g. "[pm] sending list")
+ * @brief Get (html escaped) message text (e.g. "[pm] sending list")
*/
QString getText() { return _text; }
/**
@@ -98,10 +98,6 @@ public:
* @brief Get normal message count (Resets count once read)
*/
int getNormalCount();
- /**
- * @brief Get latest error message
- */
- QString getLatestError() { return _latestError; }
/// Begin to show message which are errors in the toolbar
void showErrorsInToolbar(void) { _showErrorsInToolbar = true; }
@@ -115,9 +111,10 @@ public slots:
* @param uasid UAS Id
* @param componentid Component Id
* @param severity Message severity
- * @param text Message Text
+ * @param text Message Text (html escaped)
+ * @param description Optional detailed description (html escaped)
*/
- void handleTextMessage(int uasid, int componentid, int severity, QString text);
+ void handleTextMessage(int uasid, int componentid, int severity, QString text, QString description);
signals:
/**
@@ -144,7 +141,6 @@ private:
int _errorCountTotal;
int _warningCount;
int _normalCount;
- QString _latestError;
bool _showErrorsInToolbar;
MultiVehicleManager* _multiVehicleManager;
};
diff --git a/src/ui/MainRootWindow.qml b/src/ui/MainRootWindow.qml
index ac7a16f..93274b3 100644
--- a/src/ui/MainRootWindow.qml
+++ b/src/ui/MainRootWindow.qml
@@ -617,6 +617,7 @@ ApplicationWindow {
anchors.centerIn: parent
wrapMode: Text.WordWrap
color: qgcPal.alertText
+ textFormat: TextEdit.RichText
}
MouseArea {