6#include <QtCore/QRegularExpression>
7#include <QtCore/QApplicationStatic>
8#include <QtTextToSpeech/QTextToSpeech>
16const QHash<QString, QString> AudioOutput::_textHash = {
18 {
"POSCTL",
"Position Control" },
19 {
"ALTCTL",
"Altitude Control" },
20 {
"AUTO_RTL",
"auto return to launch" },
21 {
"RTL",
"return To launch" },
22 {
"ACCEL",
"accelerometer" },
23 {
"RC_MAP_MODE_SW",
"RC mode switch" },
24 {
"REJ",
"rejected" },
27 {
"COMPID",
"component eye dee" },
28 {
"PARAMS",
"parameters" },
30 {
"ADSB",
"A.D.S.B." },
32 {
"PREARM",
"pre arm" },
33 {
"PITOT",
"pee toe" },
34 {
"SERVOX_FUNCTION",
"Servo X Function" },
41 , _engine(new QTextToSpeech(QStringLiteral(
"none"), this))
53 return _audioOutput();
58 Q_CHECK_PTR(volumeFact);
59 Q_CHECK_PTR(mutedFact);
65 if (QTextToSpeech::availableEngines().isEmpty()) {
66 qCWarning(AudioOutputLog) <<
"No available QTextToSpeech engines found.";
71 if (!_engine->setEngine(QString())) {
72 qCWarning(AudioOutputLog) <<
"Failed to set the TTS engine.";
76 (void) connect(_engine, &QTextToSpeech::engineChanged,
this, [
this](
const QString &engine) {
77 qCDebug(AudioOutputLog) <<
"TTS Engine set to:" << engine;
78 const QLocale defaultLocale = QLocale(
"en_US");
79 if (_engine->availableLocales().contains(defaultLocale)) {
80 _engine->setLocale(defaultLocale);
84 (void) connect(_engine, &QTextToSpeech::aboutToSynthesize,
this, [
this](qsizetype
id) {
85 qCDebug(AudioOutputLog) <<
"TTS About To Synthesize ID:" << id;
87 qCDebug(AudioOutputLog) <<
"Queue Size:" << _textQueueSize;
90 _volumeFact = volumeFact;
91 _mutedFact = mutedFact;
101 if (AudioOutputLog().isDebugEnabled()) {
102 (void) connect(_engine, &QTextToSpeech::stateChanged,
this, [](QTextToSpeech::State state) {
103 qCDebug(AudioOutputLog) <<
"TTS State changed to:" << state;
105 (void) connect(_engine, &QTextToSpeech::errorOccurred,
this, [](QTextToSpeech::ErrorReason reason,
const QString &
errorString) {
106 qCDebug(AudioOutputLog) <<
"TTS Error occurred. Reason:" << reason <<
", Message:" <<
errorString;
108 (void) connect(_engine, &QTextToSpeech::localeChanged,
this, [](
const QLocale &locale) {
109 qCDebug(AudioOutputLog) <<
"TTS Locale change to:" << locale;
111 (void) connect(_engine, &QTextToSpeech::volumeChanged,
this, [](
double volume) {
112 qCDebug(AudioOutputLog) <<
"TTS Volume changed to:" << volume;
114 (void) connect(_engine, &QTextToSpeech::sayingWord,
this, [](
const QString &word, qsizetype
id, qsizetype start, qsizetype length) {
115 qCDebug(AudioOutputLog) <<
"TTS Saying:" << word <<
"ID:" <<
id <<
"Start:" << start <<
"Length:" << length;
122 qCDebug(AudioOutputLog) <<
"AudioOutput initialized with volume:" << _volumeSetting() <<
"%";
125double AudioOutput::_volumeSetting()
const
127 return std::clamp(_volumeFact->
rawValue().toDouble(), 0.0, 100.0);
130bool AudioOutput::_mutedSetting()
const
132 return _mutedFact->
rawValue().toBool();
135void AudioOutput::_setVolume()
137 const bool muted = _mutedSetting();
138 const double volume = muted ? 0.0 : _volumeSetting();
141 if (qFuzzyCompare(1.0 + volume, 1.0 + _lastVolume)) {
144 _lastVolume = volume;
148 (void) QMetaObject::invokeMethod(_engine,
"stop", Qt::AutoConnection, QTextToSpeech::BoundaryHint::Default);
153 const double normalizedVolume = volume / 100.0;
154 (void) QMetaObject::invokeMethod(_engine,
"setVolume", Qt::AutoConnection, normalizedVolume);
155 qCDebug(AudioOutputLog) <<
"AudioOutput volume set to:" << volume <<
"%";
162 qCWarning(AudioOutputLog) <<
"AudioOutput not initialized. Call init() before using say().";
167 if (_volumeSetting() <= 0.0 || _mutedSetting()) {
171 if (!_engine->engineCapabilities().testFlag(QTextToSpeech::Capability::Speak)) {
172 qCWarning(AudioOutputLog) <<
"Speech Not Supported:" << text;
176 if (_textQueueSize >= kMaxTextQueueSize) {
177 (void) QMetaObject::invokeMethod(_engine,
"stop", Qt::AutoConnection, QTextToSpeech::BoundaryHint::Default);
179 qCWarning(AudioOutputLog) <<
"Text queue exceeded maximum size. Stopped current speech.";
182 QString outText = _fixTextMessageForAudio(text);
185 outText = tr(
"%1").arg(outText);
189 if (QMetaObject::invokeMethod(_engine,
"enqueue", Qt::AutoConnection, qReturnArg(index), outText)) {
192 qCDebug(AudioOutputLog) <<
"Enqueued text with index:" << index <<
", Queue Size:" << _textQueueSize;
195 qCWarning(AudioOutputLog) <<
"Failed to invoke Enqueue method.";
202 qCWarning(AudioOutputLog) <<
"AudioOutput not initialized. Call init() before using testAudioOutput().";
206 (void) QMetaObject::invokeMethod(_engine,
"stop", Qt::AutoConnection, QTextToSpeech::BoundaryHint::Default);
209 const QString testText = tr(
"Audio test. Volume is %1 percent").arg(_volumeSetting(), 0,
'f', 1);
213QString AudioOutput::_fixTextMessageForAudio(
const QString &
string)
215 QString result = string;
216 result = _replaceAbbreviations(result);
217 result = _replaceNegativeSigns(result);
218 result = _replaceDecimalPoints(result);
219 result = _replaceMeters(result);
220 result = _convertMilliseconds(result);
224QString AudioOutput::_replaceAbbreviations(
const QString &input)
226 QString output = input;
228 const QStringList wordList = input.split(
' ', Qt::SkipEmptyParts);
229 for (
const QString &word : wordList) {
230 const QString upperWord = word.toUpper();
231 if (_textHash.contains(upperWord)) {
232 (void) output.replace(word, _textHash.value(upperWord));
239QString AudioOutput::_replaceNegativeSigns(
const QString &input)
241 static const QRegularExpression negNumRegex(QStringLiteral(
"-\\s*(?=\\d)"));
242 Q_ASSERT(negNumRegex.isValid());
244 QString output = input;
245 (void) output.replace(negNumRegex,
"negative ");
249QString AudioOutput::_replaceDecimalPoints(
const QString &input)
251 static const QRegularExpression realNumRegex(QStringLiteral(
"([0-9]+)(\\.)([0-9]+)"));
252 Q_ASSERT(realNumRegex.isValid());
254 QString output = input;
255 QRegularExpressionMatch realNumRegexMatch = realNumRegex.match(output);
256 while (realNumRegexMatch.hasMatch()) {
257 if (!realNumRegexMatch.captured(2).isNull()) {
258 (void) output.replace(realNumRegexMatch.capturedStart(2), realNumRegexMatch.capturedEnd(2) - realNumRegexMatch.capturedStart(2), QStringLiteral(
" point "));
260 realNumRegexMatch = realNumRegex.match(output);
266QString AudioOutput::_replaceMeters(
const QString &input)
268 static const QRegularExpression realNumMeterRegex(QStringLiteral(
"[0-9]*\\.?[0-9]\\s?(m)([^A-Za-z]|$)"));
269 Q_ASSERT(realNumMeterRegex.isValid());
271 QString output = input;
272 QRegularExpressionMatch realNumMeterRegexMatch = realNumMeterRegex.match(output);
273 while (realNumMeterRegexMatch.hasMatch()) {
274 if (!realNumMeterRegexMatch.captured(1).isNull()) {
275 (void) output.replace(realNumMeterRegexMatch.capturedStart(1), realNumMeterRegexMatch.capturedEnd(1) - realNumMeterRegexMatch.capturedStart(1), QStringLiteral(
" meters"));
277 realNumMeterRegexMatch = realNumMeterRegex.match(output);
283QString AudioOutput::_convertMilliseconds(
const QString &input)
285 QString result = input;
289 if (_getMillisecondString(input, match, number) && (number >= 1000)) {
291 if (number < 60000) {
292 const int seconds = number / 1000;
293 const int ms = number - (seconds * 1000);
294 newNumber = QStringLiteral(
"%1 second%2").arg(seconds).arg(seconds > 1 ?
"s" :
"");
296 (void) newNumber.append(QStringLiteral(
" and %1 millisecond").arg(ms));
299 const int minutes = number / 60000;
300 const int seconds = (number - (minutes * 60000)) / 1000;
301 newNumber = QStringLiteral(
"%1 minute%2").arg(minutes).arg(minutes > 1 ?
"s" :
"");
303 (void) newNumber.append(QStringLiteral(
" and %1 second%2").arg(seconds).arg(seconds > 1 ?
"s" :
""));
306 (void) result.replace(match, newNumber);
312bool AudioOutput::_getMillisecondString(
const QString &
string, QString &match,
int &number)
314 static const QRegularExpression msRegex(
"((?<number>[0-9]+)ms)");
315 Q_ASSERT(msRegex.isValid());
319 QRegularExpressionMatch regexpMatch = msRegex.match(
string);
320 if (regexpMatch.hasMatch()) {
321 match = regexpMatch.captured(0);
322 const QString numberStr = regexpMatch.captured(
"number");
323 number = numberStr.toInt();
Q_APPLICATION_STATIC(AudioOutput, _audioOutput)
#define QGC_LOGGING_CATEGORY(name, categoryStr)
The AudioOutput class provides functionality for audio output using text-to-speech.
void say(const QString &text, TextMods textMods=TextMod::None)
AudioOutput(QObject *parent=nullptr)
void testAudioOutput()
Tests the audio output. Will stop current output before test.
static AudioOutput * instance()
~AudioOutput()
Destructor for the AudioOutput class.
void init(Fact *volumeFact, Fact *mutedFact)
Initialize the Singleton.
A Fact is used to hold a single value within the system.
QVariant rawValue() const
Value after translation.
void valueChanged(const QVariant &value)
This signal is only meant for use by the QT property system. It should not be connected to by client ...