QGroundControl
Ground Control Station for MAVLink Drones
Loading...
Searching...
No Matches
NTRIP.h
Go to the documentation of this file.
1#pragma once
2
3#include <atomic>
4
5#include <QtCore/QElapsedTimer>
6#include <QtCore/QLoggingCategory>
7#include <QtCore/QObject>
8#include <QtCore/QThread>
9#include <QtCore/QTimer>
10#include <QtNetwork/QTcpSocket>
11#include <QtPositioning/QGeoCoordinate>
12
14
15class RTCMMavlink;
16class NTRIPSettings;
17class Vehicle;
19class GpsTest;
20
21#define RTCM3_PREAMBLE 0xD3
22
24{
25public:
26 RTCMParser();
27 void reset();
28 bool addByte(uint8_t byte);
29 uint8_t* message() { return _buffer; }
30 uint16_t messageLength() { return _messageLength; }
31 uint16_t messageId();
32 const uint8_t* crcBytes() const { return _crcBytes; }
33 int crcSize() const { return 3; }
34
35private:
36 enum State {
37 WaitingForPreamble,
38 ReadingLength,
39 ReadingMessage,
40 ReadingCRC
41 };
42
43 State _state;
44 uint8_t _buffer[1024];
45 uint16_t _messageLength;
46 uint16_t _bytesRead;
47 uint16_t _lengthBytesRead;
48 uint8_t _lengthBytes[2];
49 uint16_t _crcBytesRead;
50 uint8_t _crcBytes[3];
51};
52
53class NTRIPTCPLink : public QObject
54{
55 Q_OBJECT
56
57public:
58#ifdef QGC_UNITTEST_BUILD
59 friend class GpsTest;
60#endif
61
62 NTRIPTCPLink(const QString& hostAddress,
63 int port,
64 const QString& username,
65 const QString& password,
66 const QString& mountpoint,
67 const QString& whitelist,
68 bool useSpartn,
69 bool autoStart = true,
70 QObject* parent = nullptr);
71
72 Q_INVOKABLE void debugFetchSourceTable();
73
75
76public slots:
77 void start();
78 void requestStop();
79 void sendNMEA(const QByteArray& sentence);
80
81signals:
82 void finished();
83 void error(const QString& errorMsg);
84 void RTCMDataUpdate(const QByteArray& message);
85 // Called when SPARTN corrections are received from the NTRIPTCPLink
86 // These corrections are forwarded to the connected vehicle (PX4/ArduPilot)
87 // using the same path as RTCM corrections via _rtcmDataReceived().
88 void SPARTNDataUpdate(const QByteArray& message);
89 void connected();
90
91
92private slots:
93 void _readBytes();
94
95private:
96 enum class NTRIPState {
97 uninitialised,
98 waiting_for_http_response,
99 waiting_for_spartn_data,
100 waiting_for_rtcm_header,
101 accumulating_rtcm_packet,
102 };
103
104 void _hardwareConnect();
105 void _parse(const QByteArray& buffer);
106 void _handleSpartnData(const QByteArray& data);
107
108 QTcpSocket* _socket = nullptr;
109
110 QString _hostAddress;
111 int _port;
112 QString _username;
113 QString _password;
114 QString _mountpoint;
115 bool _useSpartn = false;
116 QVector<int> _whitelist;
117
118 RTCMParser* _rtcmParser = nullptr;
119 NTRIPState _state;
120
121 std::atomic<bool> _stopping{false};
122 QMetaObject::Connection _readyReadConn;
123
124 // Small buffer to strip a response header only once if needed
125 QByteArray _spartnBuf;
126 bool _spartnNeedHeaderStrip = true;
127
128};
129
130class NTRIPManager : public QObject
131{
132 Q_OBJECT
133 Q_PROPERTY(QString ntripStatus READ ntripStatus NOTIFY ntripStatusChanged)
134 Q_PROPERTY(CasterStatus casterStatus READ casterStatus NOTIFY casterStatusChanged)
135 Q_PROPERTY(QString ggaSource READ ggaSource NOTIFY ggaSourceChanged)
136
137public:
138 enum class CasterStatus { Connected, NoLocationError, OtherError };
139
140 NTRIPManager(QObject* parent = nullptr);
142
143 static NTRIPManager* instance();
144
145 QString ntripStatus() const { return _ntripStatus; }
146 CasterStatus casterStatus() const { return _casterStatus; }
147 QString ggaSource() const { return _ggaSource; }
148
149 void startNTRIP();
150 void stopNTRIP();
151
152signals:
154 void casterStatusChanged(CasterStatus status);
156
157public slots:
158 void _tcpError(const QString& errorMsg);
159 void _rtcmDataReceived(const QByteArray& data);
160
161private:
162 void _checkSettings();
163 void _sendGGA();
164 void _onCasterDisconnected(const QString& reason);
165
166 QTimer* _ggaTimer = nullptr;
167
168 QString _ntripStatus;
169 QString _ggaSource;
170 QMetaObject::Connection _ntripEnableConn;
171
172 NTRIPTCPLink* _tcpLink = nullptr;
173 QThread* _tcpThread = nullptr;
174 RTCMMavlink* _rtcmMavlink = nullptr;
175 QTimer* _settingsCheckTimer = nullptr;
176 bool _startStopBusy = false;
177 bool _forcedOffOnce = false;
178 bool _useSpartn = false;
179
180 QElapsedTimer _startupTimer;
181 bool _startupSuppress = true;
182 int _startupStableTicks = 0;
183
184 CasterStatus _casterStatus = CasterStatus::OtherError;
185
186 static NTRIPManager* _instance;
187};
Q_DECLARE_LOGGING_CATEGORY(AndroidSerialLog)
void _rtcmDataReceived(const QByteArray &data)
Definition NTRIP.cc:994
void casterStatusChanged(CasterStatus status)
void ntripStatusChanged()
void ggaSourceChanged()
void _tcpError(const QString &errorMsg)
Definition NTRIP.cc:973
void reset()
Definition NTRIP.cc:115
int crcSize() const
Definition NTRIP.h:33
uint16_t messageId()
Definition NTRIP.cc:169
RTCMParser()
Definition NTRIP.cc:110
uint16_t messageLength()
Definition NTRIP.h:30
uint8_t * message()
Definition NTRIP.h:29
const uint8_t * crcBytes() const
Definition NTRIP.h:32
bool addByte(uint8_t byte)
Definition NTRIP.cc:124