|
|
|
@ -891,6 +891,15 @@ void Vehicle::_chunkedStatusTextCompleted(uint8_t compId)
@@ -891,6 +891,15 @@ void Vehicle::_chunkedStatusTextCompleted(uint8_t compId)
|
|
|
|
|
bool ardupilotPrearm = messageText.startsWith(QStringLiteral("PreArm")); |
|
|
|
|
bool px4Prearm = messageText.startsWith(QStringLiteral("preflight"), Qt::CaseInsensitive) && severity >= MAV_SEVERITY_CRITICAL; |
|
|
|
|
if (ardupilotPrearm || px4Prearm) { |
|
|
|
|
// check if expected as event
|
|
|
|
|
auto eventData = _events.find(compId); |
|
|
|
|
if (eventData != _events.end()) { |
|
|
|
|
if (eventData->data()->healthAndArmingChecksSupported()) { |
|
|
|
|
qCDebug(VehicleLog) << "Dropping preflight message (expected as event):" << messageText; |
|
|
|
|
return; |
|
|
|
|
} |
|
|
|
|
} |
|
|
|
|
|
|
|
|
|
// Limit repeated PreArm message to once every 10 seconds
|
|
|
|
|
if (_noisySpokenPrearmMap.contains(messageText) && _noisySpokenPrearmMap[messageText].msecsTo(QTime::currentTime()) < (10 * 1000)) { |
|
|
|
|
skipSpoken = true; |
|
|
|
|