QGroundControl
Ground Control Station for MAVLink Drones
Loading...
Searching...
No Matches
NTRIPHttpTransport.h
Go to the documentation of this file.
1#pragma once
2
3#include <QtCore/QObject>
4#include <QtCore/QTimer>
5#include <QtNetwork/QSslSocket>
6#include <QtNetwork/QTcpSocket>
7
8#include "RTCMParser.h"
9
11 QString host;
12 int port = 2101;
13 QString username;
14 QString password;
15 QString mountpoint;
16 QString whitelist;
17 bool useTls = false;
18
19 bool operator==(const NTRIPTransportConfig& other) const {
20 return host == other.host && port == other.port &&
21 username == other.username && password == other.password &&
22 mountpoint == other.mountpoint && whitelist == other.whitelist &&
23 useTls == other.useTls;
24 }
25 bool operator!=(const NTRIPTransportConfig& other) const { return !(*this == other); }
26};
27
28class NTRIPHttpTransport : public QObject
29{
30 Q_OBJECT
32
33public:
34 static constexpr int kConnectTimeoutMs = 10000;
35 static constexpr int kDataWatchdogMs = 30000;
36 static constexpr int kMaxHttpHeaderSize = 32768;
37
38 explicit NTRIPHttpTransport(const NTRIPTransportConfig& config, QObject* parent = nullptr);
39 ~NTRIPHttpTransport() override;
40
41 void start();
42 void stop();
43 void sendNMEA(const QByteArray& nmea);
44
45signals:
46 void connected();
47 void error(const QString& errorMsg);
48 void RTCMDataUpdate(const QByteArray& message);
49 void finished();
50
51protected:
52 struct HttpStatus {
53 int code = 0;
54 QString reason;
55 bool valid = false;
56 };
57
58 static HttpStatus parseHttpStatusLine(const QString& line);
59 static QByteArray repairNmeaChecksum(const QByteArray& sentence);
60 static bool isHttpSuccess(int code) { return code >= 200 && code < 300; }
61
62private:
63 void _connect();
64 void _sendHttpRequest();
65 void _readBytes();
66 void _parseRtcm(const QByteArray& buffer);
67
68 QTcpSocket* _socket = nullptr;
69 QTimer* _connectTimeoutTimer = nullptr;
70 QTimer* _dataWatchdogTimer = nullptr;
71
72 QString _hostAddress;
73 int _port;
74 QString _username;
75 QString _password;
76 QString _mountpoint;
77 QVector<int> _whitelist;
78
79 RTCMParser _rtcmParser;
80 bool _httpHandshakeDone = false;
81 bool _useTls = false;
82 bool _stopped = false;
83
84 qint64 _postOkTimestampMs = 0;
85
86 QByteArray _httpResponseBuf;
87};
static HttpStatus parseHttpStatusLine(const QString &line)
void error(const QString &errorMsg)
void sendNMEA(const QByteArray &nmea)
static constexpr int kConnectTimeoutMs
friend class NTRIPHttpTransportTest
static constexpr int kDataWatchdogMs
void RTCMDataUpdate(const QByteArray &message)
static bool isHttpSuccess(int code)
static constexpr int kMaxHttpHeaderSize
static QByteArray repairNmeaChecksum(const QByteArray &sentence)
bool operator==(const NTRIPTransportConfig &other) const
bool operator!=(const NTRIPTransportConfig &other) const