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 NTRIPSettings;
14class Vehicle;
19
20class NTRIPManager : public QObject
21{
22 Q_OBJECT
23 QML_ELEMENT
24 QML_UNCREATABLE("")
25 Q_MOC_INCLUDE("QmlObjectListModel.h")
26 Q_PROPERTY(ConnectionStatus connectionStatus READ connectionStatus NOTIFY connectionStatusChanged)
27 Q_PROPERTY(QString statusMessage READ statusMessage NOTIFY statusMessageChanged)
28 Q_PROPERTY(CasterStatus casterStatus READ casterStatus NOTIFY casterStatusChanged)
29 Q_PROPERTY(QString ggaSource READ ggaSource NOTIFY ggaSourceChanged)
30 Q_PROPERTY(QmlObjectListModel* mountpointModel READ mountpointModel NOTIFY mountpointModelChanged)
31 Q_PROPERTY(MountpointFetchStatus mountpointFetchStatus READ mountpointFetchStatus NOTIFY mountpointFetchStatusChanged)
32 Q_PROPERTY(QString mountpointFetchError READ mountpointFetchError NOTIFY mountpointFetchErrorChanged)
33 Q_PROPERTY(quint64 bytesReceived READ bytesReceived NOTIFY bytesReceivedChanged)
34 Q_PROPERTY(quint32 messagesReceived READ messagesReceived NOTIFY messagesReceivedChanged)
35 Q_PROPERTY(double dataRateBytesPerSec READ dataRateBytesPerSec NOTIFY dataRateChanged)
36
37public:
38 enum class ConnectionStatus {
39 Disconnected,
40 Connecting,
41 Connected,
42 Reconnecting,
43 Error
44 };
45 Q_ENUM(ConnectionStatus)
46
47 enum class CasterStatus { CasterConnected, CasterNoLocation, CasterError };
48 Q_ENUM(CasterStatus)
49
50 enum class MountpointFetchStatus {
51 FetchIdle,
52 FetchInProgress,
53 FetchSuccess,
54 FetchError
55 };
56 Q_ENUM(MountpointFetchStatus)
57
58 static constexpr int kMinReconnectMs = 1000;
59 static constexpr int kMaxReconnectMs = 30000;
60 static constexpr int kMaxReconnectAttempts = 100;
61 static constexpr int kSourceTableCacheTtlMs = 60000;
62
63 explicit NTRIPManager(QObject* parent = nullptr);
64 ~NTRIPManager() override;
65
66 static NTRIPManager* instance();
67
68 ConnectionStatus connectionStatus() const { return _connectionStatus; }
69 QString statusMessage() const { return _statusMessage; }
70 CasterStatus casterStatus() const { return _casterStatus; }
71 QString ggaSource() const { return _ggaSource; }
72 QmlObjectListModel* mountpointModel() const;
73 MountpointFetchStatus mountpointFetchStatus() const { return _mountpointFetchStatus; }
74 QString mountpointFetchError() const { return _mountpointFetchError; }
75 quint64 bytesReceived() const { return _bytesReceived; }
76 quint32 messagesReceived() const { return _messagesReceived; }
77 double dataRateBytesPerSec() const { return _dataRateBytesPerSec; }
78
79 Q_INVOKABLE void fetchMountpoints();
80 Q_INVOKABLE void selectMountpoint(const QString& mountpoint);
81
82 void startNTRIP();
83 void stopNTRIP();
84
85 static QByteArray makeGGA(const QGeoCoordinate& coord, double altitude_msl);
86
87signals:
90 void casterStatusChanged(CasterStatus status);
98
99private:
100 void _tcpError(const QString& errorMsg);
101 void _rtcmDataReceived(const QByteArray& data);
102 void _onSettingChanged();
103 void _sendGGA();
104 void _scheduleReconnect();
105 void _setStatus(ConnectionStatus status, const QString& msg = {});
106
107 NTRIPTransportConfig _configFromSettings() const;
108 QPair<QGeoCoordinate, QString> _getBestPosition() const;
109
110 QTimer* _ggaTimer = nullptr;
111
112 ConnectionStatus _connectionStatus = ConnectionStatus::Disconnected;
113 QString _statusMessage;
114 QString _ggaSource;
115
116 NTRIPHttpTransport* _transport = nullptr;
117 RTCMMavlink* _rtcmMavlink = nullptr;
118 QTimer* _reconnectTimer = nullptr;
119 int _reconnectAttempts = 0;
120 bool _startStopBusy = false;
121
122 CasterStatus _casterStatus = CasterStatus::CasterError;
123
124 QUdpSocket* _udpSocket = nullptr;
125 QHostAddress _udpTargetAddress;
126 quint16 _udpTargetPort = 0;
127 bool _udpForwardEnabled = false;
128
129 NTRIPTransportConfig _runningConfig;
130 bool _runningUdpForward = false;
131 QString _runningUdpAddr;
132 quint16 _runningUdpPort = 0;
133
134 NTRIPSourceTableModel* _sourceTableModel = nullptr;
135 NTRIPSourceTableFetcher* _sourceTableFetcher = nullptr;
136 MountpointFetchStatus _mountpointFetchStatus = MountpointFetchStatus::FetchIdle;
137 QString _mountpointFetchError;
138
139 quint64 _bytesReceived = 0;
140 quint32 _messagesReceived = 0;
141 double _dataRateBytesPerSec = 0.0;
142 quint64 _dataRatePrevBytes = 0;
143 QTimer* _dataRateTimer = nullptr;
144
145 qint64 _sourceTableFetchedAtMs = 0;
146};
void statusMessageChanged()
void messagesReceivedChanged()
void bytesReceivedChanged()
void mountpointFetchStatusChanged()
void casterStatusChanged(CasterStatus status)
void dataRateChanged()
void ggaSourceChanged()
void connectionStatusChanged()
void mountpointFetchErrorChanged()
void mountpointModelChanged()