QGroundControl
Ground Control Station for MAVLink Drones
Loading...
Searching...
No Matches
NTRIPManager.h
Go to the documentation of this file.
1#pragma once
2
4
5#include <QtCore/QObject>
6#include <QtCore/QTimer>
7#include <QtNetwork/QHostAddress>
8#include <QtNetwork/QUdpSocket>
9#include <QtPositioning/QGeoCoordinate>
10#include <QtQmlIntegration/QtQmlIntegration>
11
12class RTCMMavlink;
13class RTCMUdpInput;
14class NTRIPSettings;
15class Vehicle;
20
21class NTRIPManager : public QObject
22{
23 Q_OBJECT
24 QML_ELEMENT
25 QML_UNCREATABLE("")
26 Q_MOC_INCLUDE("QmlObjectListModel.h")
28 Q_PROPERTY(QString statusMessage READ statusMessage NOTIFY statusMessageChanged)
30 Q_PROPERTY(QString ggaSource READ ggaSource NOTIFY ggaSourceChanged)
34 Q_PROPERTY(quint64 bytesReceived READ bytesReceived NOTIFY bytesReceivedChanged)
35 Q_PROPERTY(quint32 messagesReceived READ messagesReceived NOTIFY messagesReceivedChanged)
36 Q_PROPERTY(double dataRateBytesPerSec READ dataRateBytesPerSec NOTIFY dataRateChanged)
37
38public:
39 enum class ConnectionStatus {
44 Error
45 };
46 Q_ENUM(ConnectionStatus)
47
49 Q_ENUM(CasterStatus)
50
58
59 static constexpr int kMinReconnectMs = 1000;
60 static constexpr int kMaxReconnectMs = 30000;
61 static constexpr int kMaxReconnectAttempts = 100;
62 static constexpr int kSourceTableCacheTtlMs = 60000;
63
64 explicit NTRIPManager(QObject* parent = nullptr);
65 ~NTRIPManager() override;
66
67 static NTRIPManager* instance();
68
69 ConnectionStatus connectionStatus() const { return _connectionStatus; }
70 QString statusMessage() const { return _statusMessage; }
71 CasterStatus casterStatus() const { return _casterStatus; }
72 QString ggaSource() const { return _ggaSource; }
74 MountpointFetchStatus mountpointFetchStatus() const { return _mountpointFetchStatus; }
75 QString mountpointFetchError() const { return _mountpointFetchError; }
76 quint64 bytesReceived() const { return _bytesReceived; }
77 quint32 messagesReceived() const { return _messagesReceived; }
78 double dataRateBytesPerSec() const { return _dataRateBytesPerSec; }
79
80 Q_INVOKABLE void fetchMountpoints();
81 Q_INVOKABLE void selectMountpoint(const QString& mountpoint);
82
83 void startNTRIP();
84 void stopNTRIP();
85
86 static QByteArray makeGGA(const QGeoCoordinate& coord, double altitude_msl);
87
88signals:
99
100private:
101 void _tcpError(const QString& errorMsg);
102 void _rtcmDataReceived(const QByteArray& data);
103 void _onSettingChanged();
104 void _sendGGA();
105 void _scheduleReconnect();
106 void _setStatus(ConnectionStatus status, const QString& msg = {});
107
108 NTRIPTransportConfig _configFromSettings() const;
109 QPair<QGeoCoordinate, QString> _getBestPosition() const;
110
111 QTimer* _ggaTimer = nullptr;
112
114 QString _statusMessage;
115 QString _ggaSource;
116
117 NTRIPHttpTransport* _transport = nullptr;
118 RTCMMavlink* _rtcmMavlink = nullptr;
119 RTCMUdpInput* _rtcmUdpInput = nullptr;
120 QTimer* _reconnectTimer = nullptr;
121 int _reconnectAttempts = 0;
122 bool _startStopBusy = false;
123
125
126 QUdpSocket* _udpSocket = nullptr;
127 QHostAddress _udpTargetAddress;
128 quint16 _udpTargetPort = 0;
129 bool _udpForwardEnabled = false;
130
131 NTRIPTransportConfig _runningConfig;
132 bool _runningUdpForward = false;
133 QString _runningUdpAddr;
134 quint16 _runningUdpPort = 0;
135
136 NTRIPSourceTableModel* _sourceTableModel = nullptr;
137 NTRIPSourceTableFetcher* _sourceTableFetcher = nullptr;
139 QString _mountpointFetchError;
140
141 quint64 _bytesReceived = 0;
142 quint32 _messagesReceived = 0;
143 double _dataRateBytesPerSec = 0.0;
144 quint64 _dataRatePrevBytes = 0;
145 QTimer* _dataRateTimer = nullptr;
146
147 qint64 _sourceTableFetchedAtMs = 0;
148};
QString mountpointFetchError() const
static constexpr int kMaxReconnectMs
static constexpr int kMaxReconnectAttempts
void statusMessageChanged()
void messagesReceivedChanged()
void bytesReceivedChanged()
ConnectionStatus connectionStatus() const
void mountpointFetchStatusChanged()
void casterStatusChanged(CasterStatus status)
QmlObjectListModel * mountpointModel() const
MountpointFetchStatus mountpointFetchStatus() const
quint32 messagesReceived() const
Q_INVOKABLE void fetchMountpoints()
static NTRIPManager * instance()
void dataRateChanged()
void ggaSourceChanged()
Q_INVOKABLE void selectMountpoint(const QString &mountpoint)
CasterStatus casterStatus() const
quint64 bytesReceived() const
QString statusMessage() const
QString ggaSource() const
static constexpr int kMinReconnectMs
static constexpr int kSourceTableCacheTtlMs
void connectionStatusChanged()
void mountpointFetchErrorChanged()
double dataRateBytesPerSec() const
static QByteArray makeGGA(const QGeoCoordinate &coord, double altitude_msl)
void mountpointModelChanged()
Listens on a UDP port for raw RTCM3 correction data and emits it for forwarding to connected vehicles...