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/QLoggingCategory>
4#include <QtCore/QObject>
5#include <QtNetwork/QHostAddress>
6
7#include "ADSB.h"
8
9Q_DECLARE_LOGGING_CATEGORY(ADSBTCPLinkLog)
10
11class QTcpSocket;
12class QTimer;
13
16class ADSBTCPLink : public QObject
17{
18 Q_OBJECT
19
20public:
25 explicit ADSBTCPLink(const QHostAddress &hostAddress, quint16 port = 30003, QObject *parent = nullptr);
26
29
31 bool init();
32
33signals:
36 void adsbVehicleUpdate(const ADSB::VehicleInfo_t &vehicleInfo);
37
40 void errorOccurred(const QString &errorMsg, bool stopped = false);
41
42private slots:
44 void _readBytes();
45
47 void _processLines();
48
49private:
52 void _parseLine(const QString &line);
53
57 void _parseAndEmitCallsign(ADSB::VehicleInfo_t &adsbInfo, const QStringList &values);
58
62 void _parseAndEmitLocation(ADSB::VehicleInfo_t &adsbInfo, const QStringList &values);
63
67 void _parseAndEmitHeading(ADSB::VehicleInfo_t &adsbInfo, const QStringList &values);
68
69 QHostAddress _hostAddress;
70 quint16 _port = 30003;
71
72 QTcpSocket *_socket = nullptr;
73 QTimer *_processTimer = nullptr;
74 QStringList _lineBuffer;
75
76 static constexpr int _processInterval = 50;
77 static constexpr int _maxLinesToProcess = 100;
78};
Q_DECLARE_LOGGING_CATEGORY(AndroidSerialLog)