From 84dc075853ad1d8633ac56817cc1466451c75af1 Mon Sep 17 00:00:00 2001 From: Don Gagne Date: Thu, 27 Sep 2018 17:31:53 -0700 Subject: [PATCH] Change to case insensitive compare --- src/QGCApplication.cc | 2 +- src/Vehicle/Vehicle.cc | 2 +- 2 files changed, 2 insertions(+), 2 deletions(-) diff --git a/src/QGCApplication.cc b/src/QGCApplication.cc index 40b974761..5fe1ab9bd 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 c64faf627..8f8c5172f 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; -- 2.22.0