QGroundControl
Ground Control Station for MAVLink Drones
Loading...
Searching...
No Matches
NTRIPManager.cc
Go to the documentation of this file.
1#include "NTRIPManager.h"
3#include "NTRIPSourceTable.h"
4#include "NTRIPSettings.h"
6#include "Fact.h"
7#include "FactGroup.h"
8#include "QGCApplication.h"
10#include "RTCMMavlink.h"
11#include "RTCMUdpInput.h"
12#include "SettingsManager.h"
13
14#include "MultiVehicleManager.h"
15#include "PositionManager.h"
16#include "Vehicle.h"
17#include <QtPositioning/QGeoCoordinate>
18#include <QtCore/QDateTime>
19
20#include <QtCore/QApplicationStatic>
21#include <QtCore/QCoreApplication>
22#include <QtCore/QDebug>
23#include <QtCore/QtGlobal>
24
25QGC_LOGGING_CATEGORY(NTRIPManagerLog, "GPS.NTRIPManager")
26
27Q_APPLICATION_STATIC(NTRIPManager, _ntripManagerInstance);
28
30{
31 return _ntripManagerInstance();
32}
33
35 : QObject(parent)
36{
37 qCDebug(NTRIPManagerLog) << "NTRIPManager created";
38
39 _rtcmMavlink = qgcApp() ? qgcApp()->findChild<RTCMMavlink*>() : nullptr;
40 if (!_rtcmMavlink) {
41 QObject* parentObj = qgcApp() ? static_cast<QObject*>(qgcApp()) : static_cast<QObject*>(this);
42 _rtcmMavlink = new RTCMMavlink(parentObj);
43 _rtcmMavlink->setObjectName(QStringLiteral("RTCMMavlink"));
44 }
45
47 if (settings) {
48 const quint16 port = static_cast<quint16>(
49 settings->rtcmUdpInputPort()->rawValue().toUInt());
50
51 _rtcmUdpInput = new RTCMUdpInput(port, this);
52 connect(_rtcmUdpInput, &RTCMUdpInput::rtcmDataReceived,
53 _rtcmMavlink, &RTCMMavlink::RTCMDataUpdate);
54
55 auto applyUdpInputSettings = [this, settings]() {
56 const quint16 uin_port = static_cast<quint16>(
57 settings->rtcmUdpInputPort()->rawValue().toUInt());
58 _rtcmUdpInput->setPort(uin_port);
59 if (settings->rtcmUdpInputEnabled()->rawValue().toBool()) {
60 _rtcmUdpInput->start();
61 } else {
62 _rtcmUdpInput->stop();
63 }
64 };
65 connect(settings->rtcmUdpInputEnabled(), &Fact::rawValueChanged,
66 this, applyUdpInputSettings);
67 connect(settings->rtcmUdpInputPort(), &Fact::rawValueChanged,
68 this, applyUdpInputSettings);
69
70 auto connectSetting = [this](Fact* fact) {
71 if (fact) {
72 connect(fact, &Fact::rawValueChanged, this, &NTRIPManager::_onSettingChanged);
73 }
74 };
75
76 connectSetting(settings->ntripServerConnectEnabled());
77 connectSetting(settings->ntripServerHostAddress());
78 connectSetting(settings->ntripServerPort());
79 connectSetting(settings->ntripUsername());
80 connectSetting(settings->ntripPassword());
81 connectSetting(settings->ntripMountpoint());
82 connectSetting(settings->ntripWhitelist());
83 connectSetting(settings->ntripUseTls());
84 connectSetting(settings->ntripUdpForwardEnabled());
85 connectSetting(settings->ntripUdpTargetAddress());
86 connectSetting(settings->ntripUdpTargetPort());
87 applyUdpInputSettings();
88 }
89
90 // Check initial state (handles connect-on-start)
91 QTimer::singleShot(0, this, &NTRIPManager::_onSettingChanged);
92
93 _ggaTimer = new QTimer(this);
94 _ggaTimer->setInterval(5000);
95 connect(_ggaTimer, &QTimer::timeout, this, &NTRIPManager::_sendGGA);
96
97 _dataRateTimer = new QTimer(this);
98 _dataRateTimer->setInterval(1000);
99 connect(_dataRateTimer, &QTimer::timeout, this, [this]() {
100 const double rate = static_cast<double>(_bytesReceived - _dataRatePrevBytes);
101 _dataRatePrevBytes = _bytesReceived;
102 if (!qFuzzyCompare(_dataRateBytesPerSec + 1.0, rate + 1.0)) {
103 _dataRateBytesPerSec = rate;
104 emit dataRateChanged();
105 }
108 });
109
110 connect(qApp, &QCoreApplication::aboutToQuit, this, &NTRIPManager::stopNTRIP, Qt::QueuedConnection);
111}
112
114{
115 qCDebug(NTRIPManagerLog) << "NTRIPManager destroyed";
116 stopNTRIP();
117}
118
119void NTRIPManager::_setStatus(ConnectionStatus status, const QString& msg)
120{
121 bool changed = false;
122
123 if (_connectionStatus != status) {
124 _connectionStatus = status;
125 changed = true;
127 }
128
129 if (_statusMessage != msg) {
130 _statusMessage = msg;
131 changed = true;
133 }
134
135 if (changed) {
136 qCDebug(NTRIPManagerLog) << "NTRIP status:" << static_cast<int>(status) << msg;
137 }
138}
139
140NTRIPTransportConfig NTRIPManager::_configFromSettings() const
141{
144 if (!settings) {
145 return config;
146 }
147
148 if (settings->ntripServerHostAddress()) config.host = settings->ntripServerHostAddress()->rawValue().toString();
149 if (settings->ntripServerPort()) config.port = settings->ntripServerPort()->rawValue().toInt();
150 if (settings->ntripUsername()) config.username = settings->ntripUsername()->rawValue().toString();
151 if (settings->ntripPassword()) config.password = settings->ntripPassword()->rawValue().toString();
152 if (settings->ntripMountpoint()) config.mountpoint = settings->ntripMountpoint()->rawValue().toString();
153 if (settings->ntripWhitelist()) config.whitelist = settings->ntripWhitelist()->rawValue().toString();
154 if (settings->ntripUseTls()) config.useTls = settings->ntripUseTls()->rawValue().toBool();
155
156 return config;
157}
158
160{
161 if (_startStopBusy || _transport) {
162 if (_startStopBusy) {
163 qCWarning(NTRIPManagerLog) << "startNTRIP called while start/stop in progress";
164 }
165 return;
166 }
167 _startStopBusy = true;
168
169 if (_reconnectTimer) {
170 _reconnectTimer->stop();
171 }
172
173 NTRIPTransportConfig config = _configFromSettings();
174
176 if (settings && settings->ntripUdpForwardEnabled()) {
177 _udpForwardEnabled = settings->ntripUdpForwardEnabled()->rawValue().toBool();
178 }
179
180 if (_udpForwardEnabled && settings) {
181 const QString udpAddr = settings->ntripUdpTargetAddress()->rawValue().toString();
182 const quint16 udpPort = static_cast<quint16>(settings->ntripUdpTargetPort()->rawValue().toUInt());
183 const QHostAddress parsedAddr(udpAddr);
184 if (!udpAddr.isEmpty() && !parsedAddr.isNull() && udpPort > 0) {
185 _udpTargetAddress = parsedAddr;
186 _udpTargetPort = udpPort;
187 if (!_udpSocket) {
188 _udpSocket = new QUdpSocket(this);
189 }
190 qCDebug(NTRIPManagerLog) << "NTRIP UDP forwarding enabled:" << udpAddr << ":" << udpPort;
191 } else {
192 qCWarning(NTRIPManagerLog) << "NTRIP UDP forwarding enabled but address/port invalid";
193 _udpForwardEnabled = false;
194 }
195 }
196
197 if (config.host.isEmpty()) {
198 qCWarning(NTRIPManagerLog) << "NTRIP host address is empty";
199 _setStatus(ConnectionStatus::Error, tr("No host address"));
200 _startStopBusy = false;
201 return;
202 }
203
204 if (config.port <= 0 || config.port > 65535) {
205 qCWarning(NTRIPManagerLog) << "NTRIP port is invalid:" << config.port;
206 _setStatus(ConnectionStatus::Error, tr("Invalid port"));
207 _startStopBusy = false;
208 return;
209 }
210
211 qCDebug(NTRIPManagerLog) << "startNTRIP: host=" << config.host << " port=" << config.port
212 << " mount=" << config.mountpoint;
213
214 _setStatus(ConnectionStatus::Connecting, tr("Connecting to %1:%2...").arg(config.host).arg(config.port));
215
216 _bytesReceived = 0;
217 _messagesReceived = 0;
218 _dataRateBytesPerSec = 0.0;
219 _dataRatePrevBytes = 0;
222 emit dataRateChanged();
223
224 _runningConfig = config;
225 _runningUdpForward = _udpForwardEnabled;
226 _runningUdpAddr = _udpForwardEnabled ? _udpTargetAddress.toString() : QString();
227 _runningUdpPort = _udpForwardEnabled ? _udpTargetPort : 0;
228
229 _transport = new NTRIPHttpTransport(config, this);
230
231 connect(_transport, &NTRIPHttpTransport::error,
232 this, &NTRIPManager::_tcpError);
233
234 connect(_transport, &NTRIPHttpTransport::connected, this, [this]() {
235 _reconnectAttempts = 0;
236 _casterStatus = CasterStatus::CasterConnected;
237 emit casterStatusChanged(_casterStatus);
238
239 _setStatus(ConnectionStatus::Connected, tr("Connected"));
240
241 if (_ggaTimer && !_ggaTimer->isActive()) {
242 _ggaTimer->setInterval(1000);
243 _sendGGA();
244 _ggaTimer->start();
245 }
246 _dataRateTimer->start();
247 });
248
249 connect(_transport, &NTRIPHttpTransport::RTCMDataUpdate, this, &NTRIPManager::_rtcmDataReceived);
250
251 _transport->start();
252 qCDebug(NTRIPManagerLog) << "NTRIP started";
253
254 _startStopBusy = false;
255}
256
258{
259 if (_startStopBusy) {
260 qCWarning(NTRIPManagerLog) << "stopNTRIP called while start/stop in progress";
261 return;
262 }
263 _startStopBusy = true;
264
265 if (_reconnectTimer) {
266 _reconnectTimer->stop();
267 }
268
269 if (_transport) {
270 disconnect(_transport, &NTRIPHttpTransport::error, this, &NTRIPManager::_tcpError);
271 _transport->stop();
272 _transport->deleteLater();
273 _transport = nullptr;
274
275 _runningConfig = {};
276 _runningUdpForward = false;
277 _runningUdpAddr.clear();
278 _runningUdpPort = 0;
279
280 _setStatus(ConnectionStatus::Disconnected, tr("Disconnected"));
281 qCDebug(NTRIPManagerLog) << "NTRIP stopped";
282 }
283
284 if (_ggaTimer && _ggaTimer->isActive()) {
285 _ggaTimer->stop();
286 }
287 _dataRateTimer->stop();
288 if (_dataRateBytesPerSec != 0.0) {
289 _dataRateBytesPerSec = 0.0;
290 _dataRatePrevBytes = 0;
291 emit dataRateChanged();
292 }
293
294 if (_udpSocket) {
295 _udpSocket->close();
296 delete _udpSocket;
297 _udpSocket = nullptr;
298 }
299 _udpForwardEnabled = false;
300
301 _startStopBusy = false;
302}
303
304void NTRIPManager::_tcpError(const QString& errorMsg)
305{
306 qCWarning(NTRIPManagerLog) << "NTRIP error:" << errorMsg;
307 _setStatus(ConnectionStatus::Error, errorMsg);
308
309 if (errorMsg.contains("NO_LOCATION_PROVIDED", Qt::CaseInsensitive)) {
310 _casterStatus = CasterStatus::CasterNoLocation;
311 } else {
312 _casterStatus = CasterStatus::CasterError;
313 }
314 emit casterStatusChanged(_casterStatus);
315
316 _scheduleReconnect();
317}
318
319void NTRIPManager::_scheduleReconnect()
320{
322 bool shouldRun = settings && settings->ntripServerConnectEnabled() &&
323 settings->ntripServerConnectEnabled()->rawValue().toBool();
324 if (!shouldRun) {
325 return;
326 }
327
328 stopNTRIP();
329
330 int backoffMs = qMin(kMinReconnectMs * (1 << qMin(_reconnectAttempts, 4)), kMaxReconnectMs);
331 _reconnectAttempts = qMin(_reconnectAttempts + 1, kMaxReconnectAttempts);
332
333 qCDebug(NTRIPManagerLog) << "NTRIP reconnecting in" << backoffMs << "ms (attempt" << _reconnectAttempts << ")";
334
335 _setStatus(ConnectionStatus::Reconnecting, tr("Reconnecting in %1s...").arg(backoffMs / 1000));
336
337 if (!_reconnectTimer) {
338 _reconnectTimer = new QTimer(this);
339 _reconnectTimer->setSingleShot(true);
340 connect(_reconnectTimer, &QTimer::timeout, this, [this]() {
341 if (!_transport) {
342 startNTRIP();
343 }
344 });
345 }
346
347 _reconnectTimer->start(backoffMs);
348}
349
350void NTRIPManager::_rtcmDataReceived(const QByteArray& data)
351{
352 _bytesReceived += static_cast<quint64>(data.size());
353 _messagesReceived++;
354
355 qCDebug(NTRIPManagerLog) << "NTRIP Forwarding RTCM to vehicle:" << data.size() << "bytes";
356
357 if (!_rtcmMavlink && qgcApp()) {
358 _rtcmMavlink = qgcApp()->findChild<RTCMMavlink*>();
359 }
360
361 if (_rtcmMavlink) {
362 _rtcmMavlink->RTCMDataUpdate(data);
363
364 if (_connectionStatus != ConnectionStatus::Connected) {
365 _setStatus(ConnectionStatus::Connected, tr("Connected"));
366 }
367 } else {
368 qCWarning(NTRIPManagerLog) << "RTCMMavlink not ready; dropping" << data.size() << "bytes";
369 }
370
371 if (_udpForwardEnabled && _udpSocket && _udpTargetPort > 0) {
372 const qint64 sent = _udpSocket->writeDatagram(data, _udpTargetAddress, _udpTargetPort);
373 if (sent < 0) {
374 qCWarning(NTRIPManagerLog) << "NTRIP UDP forward failed:" << _udpSocket->errorString();
375 }
376 }
377}
378
379QByteArray NTRIPManager::makeGGA(const QGeoCoordinate& coord, double altitude_msl)
380{
381 const QTime utc = QDateTime::currentDateTimeUtc().time();
382 const QString hhmmss = QString("%1%2%3")
383 .arg(utc.hour(), 2, 10, QChar('0'))
384 .arg(utc.minute(), 2, 10, QChar('0'))
385 .arg(utc.second(), 2, 10, QChar('0'));
386
387 auto dmm = [](double deg, bool lat) -> QString {
388 double a = qFabs(deg);
389 int d = int(a);
390 double m = (a - d) * 60.0;
391
392 int m10000 = int(m * 10000.0 + 0.5);
393 double m_rounded = m10000 / 10000.0;
394 if (m_rounded >= 60.0) {
395 m_rounded -= 60.0;
396 d += 1;
397 }
398
399 QString mm = QString::number(m_rounded, 'f', 4);
400 if (m_rounded < 10.0) {
401 mm.prepend("0");
402 }
403
404 if (lat) {
405 return QString("%1%2").arg(d, 2, 10, QChar('0')).arg(mm);
406 } else {
407 return QString("%1%2").arg(d, 3, 10, QChar('0')).arg(mm);
408 }
409 };
410
411 const bool latNorth = coord.latitude() >= 0.0;
412 const bool lonEast = coord.longitude() >= 0.0;
413
414 const QString latField = dmm(coord.latitude(), true);
415 const QString lonField = dmm(coord.longitude(), false);
416
417 const QString core = QString("GPGGA,%1,%2,%3,%4,%5,1,12,1.0,%6,M,0.0,M,,")
418 .arg(hhmmss)
419 .arg(latField)
420 .arg(latNorth ? "N" : "S")
421 .arg(lonField)
422 .arg(lonEast ? "E" : "W")
423 .arg(QString::number(altitude_msl, 'f', 1));
424
425 quint8 cksum = 0;
426 const QByteArray coreBytes = core.toUtf8();
427 for (char ch : coreBytes) {
428 cksum ^= static_cast<quint8>(ch);
429 }
430
431 const QString cks = QString("%1").arg(cksum, 2, 16, QChar('0')).toUpper();
432 const QByteArray sentence = QByteArray("$") + coreBytes + QByteArray("*") + cks.toUtf8();
433 return sentence;
434}
435
436QPair<QGeoCoordinate, QString> NTRIPManager::_getBestPosition() const
437{
439 if (mvm) {
440 if (Vehicle* veh = mvm->activeVehicle()) {
441 FactGroup* gps = veh->gpsFactGroup();
442 if (gps) {
443 Fact* latF = gps->getFact(QStringLiteral("lat"));
444 Fact* lonF = gps->getFact(QStringLiteral("lon"));
445
446 if (latF && lonF) {
447 const double lat = latF->rawValue().toDouble();
448 const double lon = lonF->rawValue().toDouble();
449
450 if (qIsFinite(lat) && qIsFinite(lon) &&
451 !(lat == 0.0 && lon == 0.0) &&
452 qAbs(lat) <= 90.0 && qAbs(lon) <= 180.0) {
453
454 return {QGeoCoordinate(lat, lon, veh->coordinate().altitude()),
455 QStringLiteral("GPS Raw")};
456 }
457 }
458 }
459
460 QGeoCoordinate coord = veh->coordinate();
461 if (coord.isValid() && !(coord.latitude() == 0.0 && coord.longitude() == 0.0)) {
462 return {coord, QStringLiteral("Vehicle EKF")};
463 }
464 }
465 }
466
468 if (posMgr) {
469 QGeoCoordinate coord = posMgr->gcsPosition();
470 if (coord.isValid() && !(coord.latitude() == 0.0 && coord.longitude() == 0.0)) {
471 return {coord, QStringLiteral("GCS Position")};
472 }
473 }
474
475 return {QGeoCoordinate(), QString()};
476}
477
478void NTRIPManager::_sendGGA()
479{
480 if (!_transport) {
481 return;
482 }
483
484 const auto [coord, srcUsed] = _getBestPosition();
485
486 if (!coord.isValid()) {
487 qCDebug(NTRIPManagerLog) << "NTRIP: No valid position, skipping GGA";
488 return;
489 }
490
491 if (_ggaTimer && _ggaTimer->interval() != 5000) {
492 _ggaTimer->setInterval(5000);
493 qCDebug(NTRIPManagerLog) << "NTRIP: Position acquired, reducing GGA to 5s";
494 }
495
496 double alt_msl = coord.altitude();
497 if (!qIsFinite(alt_msl)) {
498 alt_msl = 0.0;
499 }
500
501 const QByteArray gga = makeGGA(coord, alt_msl);
502 _transport->sendNMEA(gga);
503
504 if (!srcUsed.isEmpty() && srcUsed != _ggaSource) {
505 _ggaSource = srcUsed;
506 emit ggaSourceChanged();
507 }
508}
509
510void NTRIPManager::_onSettingChanged()
511{
512 if (_startStopBusy) {
513 return;
514 }
515
517 bool shouldRun = settings && settings->ntripServerConnectEnabled() &&
518 settings->ntripServerConnectEnabled()->rawValue().toBool();
519 bool isRunning = (_transport != nullptr);
520
521 if (shouldRun && isRunning && settings) {
522 NTRIPTransportConfig config = _configFromSettings();
523 const bool udpFwd = settings->ntripUdpForwardEnabled()->rawValue().toBool();
524 const QString udpAddr = settings->ntripUdpTargetAddress()->rawValue().toString();
525 const quint16 udpPort = static_cast<quint16>(settings->ntripUdpTargetPort()->rawValue().toUInt());
526
527 if (config != _runningConfig ||
528 udpFwd != _runningUdpForward || udpAddr != _runningUdpAddr || udpPort != _runningUdpPort) {
529 qCDebug(NTRIPManagerLog) << "NTRIP settings changed while running, restarting";
530 stopNTRIP();
531 startNTRIP();
532 return;
533 }
534 }
535
536 const bool reconnectPending = _reconnectTimer && _reconnectTimer->isActive();
537
538 if (shouldRun && !isRunning && !reconnectPending) {
539 startNTRIP();
540 } else if (!shouldRun) {
541 if (_reconnectTimer) {
542 _reconnectTimer->stop();
543 }
544 if (isRunning) {
545 stopNTRIP();
546 } else if (reconnectPending) {
547 _reconnectAttempts = 0;
548 _setStatus(ConnectionStatus::Disconnected, tr("Disconnected"));
549 }
550 }
551}
552
554{
555 if (_sourceTableModel) {
556 return _sourceTableModel->mountpoints();
557 }
558 return nullptr;
559}
560
562{
563 if (_mountpointFetchStatus == MountpointFetchStatus::FetchInProgress) {
564 return;
565 }
566
567 if (_sourceTableModel && _sourceTableModel->count() > 0 && _sourceTableFetchedAtMs > 0) {
568 const qint64 age = QDateTime::currentMSecsSinceEpoch() - _sourceTableFetchedAtMs;
569 if (age < kSourceTableCacheTtlMs) {
570 qCDebug(NTRIPManagerLog) << "Source table cache hit, age:" << age << "ms";
571 _mountpointFetchStatus = MountpointFetchStatus::FetchSuccess;
573 return;
574 }
575 }
576
578 if (!settings) {
579 return;
580 }
581
582 const QString host = settings->ntripServerHostAddress()->rawValue().toString();
583 const int port = settings->ntripServerPort()->rawValue().toInt();
584 const QString user = settings->ntripUsername()->rawValue().toString();
585 const QString pass = settings->ntripPassword()->rawValue().toString();
586 const bool useTls = settings->ntripUseTls() ? settings->ntripUseTls()->rawValue().toBool() : false;
587
588 if (host.isEmpty()) {
589 _mountpointFetchError = tr("Host address is empty");
590 _mountpointFetchStatus = MountpointFetchStatus::FetchError;
593 return;
594 }
595
596 if (!_sourceTableModel) {
597 _sourceTableModel = new NTRIPSourceTableModel(this);
599 }
600
601 if (_sourceTableFetcher) {
602 _sourceTableFetcher->deleteLater();
603 _sourceTableFetcher = nullptr;
604 }
605
606 _mountpointFetchStatus = MountpointFetchStatus::FetchInProgress;
607 _mountpointFetchError.clear();
610
611 _sourceTableFetcher = new NTRIPSourceTableFetcher(host, port, user, pass, useTls, this);
612
613 connect(_sourceTableFetcher, &NTRIPSourceTableFetcher::sourceTableReceived, this, [this](const QString& table) {
614 _sourceTableModel->parseSourceTable(table);
615 _sourceTableFetchedAtMs = QDateTime::currentMSecsSinceEpoch();
616
618 if (mvm) {
619 if (Vehicle* veh = mvm->activeVehicle()) {
620 QGeoCoordinate coord = veh->coordinate();
621 if (coord.isValid()) {
622 _sourceTableModel->updateDistances(coord);
623 }
624 }
625 }
626
627 _mountpointFetchStatus = MountpointFetchStatus::FetchSuccess;
629 qCDebug(NTRIPManagerLog) << "NTRIP source table fetched:" << _sourceTableModel->count() << "mountpoints";
630 });
631
632 connect(_sourceTableFetcher, &NTRIPSourceTableFetcher::error, this, [this](const QString& errorMsg) {
633 _mountpointFetchError = errorMsg;
634 _mountpointFetchStatus = MountpointFetchStatus::FetchError;
637 qCWarning(NTRIPManagerLog) << "NTRIP source table fetch error:" << errorMsg;
638 });
639
640 connect(_sourceTableFetcher, &NTRIPSourceTableFetcher::finished, this, [this]() {
641 _sourceTableFetcher->deleteLater();
642 _sourceTableFetcher = nullptr;
643 });
644
645 _sourceTableFetcher->fetch();
646}
647
648void NTRIPManager::selectMountpoint(const QString& mountpoint)
649{
651 if (settings && settings->ntripMountpoint()) {
652 settings->ntripMountpoint()->setRawValue(mountpoint);
653 qCDebug(NTRIPManagerLog) << "NTRIP mountpoint selected:" << mountpoint;
654 }
655}
Q_APPLICATION_STATIC(NTRIPManager, _ntripManagerInstance)
#define qgcApp()
#define qApp
#define QGC_LOGGING_CATEGORY(name, categoryStr)
Used to group Facts together into an object hierarachy.
Definition FactGroup.h:16
Q_INVOKABLE Fact * getFact(const QString &name) const
Definition FactGroup.cc:72
A Fact is used to hold a single value within the system.
Definition Fact.h:17
void rawValueChanged(const QVariant &value)
QVariant rawValue() const
Value after translation.
Definition Fact.h:85
static MultiVehicleManager * instance()
Vehicle * activeVehicle() const
void error(const QString &errorMsg)
void sendNMEA(const QByteArray &nmea)
void RTCMDataUpdate(const QByteArray &message)
static constexpr int kMaxReconnectMs
static constexpr int kMaxReconnectAttempts
void statusMessageChanged()
void messagesReceivedChanged()
void bytesReceivedChanged()
void mountpointFetchStatusChanged()
void casterStatusChanged(CasterStatus status)
QmlObjectListModel * mountpointModel() const
Q_INVOKABLE void fetchMountpoints()
void dataRateChanged()
void ggaSourceChanged()
Q_INVOKABLE void selectMountpoint(const QString &mountpoint)
NTRIPManager(QObject *parent=nullptr)
static constexpr int kMinReconnectMs
static constexpr int kSourceTableCacheTtlMs
~NTRIPManager() override
void connectionStatusChanged()
void mountpointFetchErrorChanged()
static QByteArray makeGGA(const QGeoCoordinate &coord, double altitude_msl)
void mountpointModelChanged()
void error(const QString &errorMsg)
void sourceTableReceived(const QString &table)
void updateDistances(const QGeoCoordinate &from)
void parseSourceTable(const QString &raw)
QmlObjectListModel * mountpoints() const
static QGCPositionManager * instance()
QGeoCoordinate gcsPosition() const
Listens on a UDP port for raw RTCM3 correction data and emits it for forwarding to connected vehicles...
void stop()
Unbind the socket and stop accepting datagrams.
void rtcmDataReceived(const QByteArray &data)
void setPort(quint16 port)
Change the listen port. If already running, restarts automatically.
static SettingsManager * instance()
NTRIPSettings * ntripSettings() const