diff --git a/src/QGCApplication.cc b/src/QGCApplication.cc index 40b97476125a53343f88102254a3017fc952c41a..5fe1ab9bd564b3fb8b2e30d3a285203ae91a4e8f 100644 --- a/src/QGCApplication.cc +++ b/src/QGCApplication.cc @@ -675,7 +675,7 @@ QObject* QGCApplication::_rootQmlObject() void QGCApplication::showMessage(const QString& message) { // PreArm messages are handled by Vehicle and shown in Map - if (message.startsWith(QStringLiteral("PreArm")) || message.startsWith(QStringLiteral("PREFLIGHT"))) { + if (message.startsWith(QStringLiteral("PreArm")) || message.startsWith(QStringLiteral("preflight"), Qt::CaseInsensitive)) { return; } diff --git a/src/Vehicle/Vehicle.cc b/src/Vehicle/Vehicle.cc index c64faf627bf826b992960cff311061f6a4a06267..8f8c5172f3acd997d6a70a688e4a95717b257af7 100644 --- a/src/Vehicle/Vehicle.cc +++ b/src/Vehicle/Vehicle.cc @@ -827,7 +827,7 @@ void Vehicle::_handleStatusText(mavlink_message_t& message) QString messageText = QString(b); bool skipSpoken = false; - if (messageText.startsWith(QStringLiteral("PreArm")) || messageText.startsWith(QStringLiteral("PREFLIGHT"))) { + if (messageText.startsWith(QStringLiteral("PreArm")) || messageText.startsWith(QStringLiteral("preflight"), Qt::CaseInsensitive)) { // Limit repeated PreArm message to once every 10 seconds if (_noisySpokenPrearmMap.contains(messageText) && _noisySpokenPrearmMap[messageText].msecsTo(QTime::currentTime()) < (10 * 1000)) { skipSpoken = true;