QGroundControl
Ground Control Station for MAVLink Drones
Loading...
Searching...
No Matches
ADSBTCPLink.h
Go to the documentation of this file.
1#pragma once
2
3#include <QtCore/QObject>
4#include <QtNetwork/QHostAddress>
5
6#include "ADSB.h"
7
8class QTcpSocket;
9class QTimer;
10
13
14class ADSBTCPLink : public QObject
15{
16 Q_OBJECT
17
18public:
23 explicit ADSBTCPLink(const QHostAddress &hostAddress, quint16 port = 30003, QObject *parent = nullptr);
24
27
29 bool init();
30
31signals:
34 void adsbVehicleUpdate(const ADSB::VehicleInfo_t &vehicleInfo);
35
38 void errorOccurred(const QString &errorMsg, bool stopped = false);
39
40private slots:
42 void _readBytes();
43
45 void _processLines();
46
47private:
50 void _parseLine(const QString &line);
51
55 void _parseAndEmitCallsign(ADSB::VehicleInfo_t &adsbInfo, const QStringList &values);
56
60 void _parseAndEmitLocation(ADSB::VehicleInfo_t &adsbInfo, const QStringList &values);
61
65 void _parseAndEmitHeading(ADSB::VehicleInfo_t &adsbInfo, const QStringList &values);
66
67 QHostAddress _hostAddress;
68 quint16 _port = 30003;
69
70 QTcpSocket *_socket = nullptr;
71 QTimer *_processTimer = nullptr;
72 QStringList _lineBuffer;
73
74 static constexpr int _processInterval = 50;
75 static constexpr int _maxLinesToProcess = 100;
76};