From 6163ce95e3915edacb18bfc084d9285668266ba2 Mon Sep 17 00:00:00 2001 From: Don Gagne Date: Fri, 28 Sep 2018 13:34:53 -0700 Subject: [PATCH] Fix critical check --- src/Vehicle/Vehicle.cc | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/src/Vehicle/Vehicle.cc b/src/Vehicle/Vehicle.cc index 94992d1b7..85ebddb38 100644 --- a/src/Vehicle/Vehicle.cc +++ b/src/Vehicle/Vehicle.cc @@ -829,7 +829,7 @@ void Vehicle::_handleStatusText(mavlink_message_t& message) bool skipSpoken = false; bool ardupilotPrearm = messageText.startsWith(QStringLiteral("PreArm")); - bool px4Prearm = messageText.startsWith(QStringLiteral("preflight"), Qt::CaseInsensitive) && severity == MAV_SEVERITY_CRITICAL; + bool px4Prearm = messageText.startsWith(QStringLiteral("preflight"), Qt::CaseInsensitive) && severity >= MAV_SEVERITY_CRITICAL; if (ardupilotPrearm || px4Prearm) { // Limit repeated PreArm message to once every 10 seconds if (_noisySpokenPrearmMap.contains(messageText) && _noisySpokenPrearmMap[messageText].msecsTo(QTime::currentTime()) < (10 * 1000)) { -- 2.22.0