QGroundControl
Ground Control Station for MAVLink Drones
Loading...
Searching...
No Matches
RTCMUdpInput.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#include <QtNetwork/QUdpSocket>
7
8Q_DECLARE_LOGGING_CATEGORY(RTCMUdpInputLog)
9
10
26class RTCMUdpInput : public QObject
27{
28 Q_OBJECT
29 Q_PROPERTY(bool running READ isRunning NOTIFY runningChanged)
30 Q_PROPERTY(quint16 port READ port NOTIFY portChanged)
31
32public:
33
34 explicit RTCMUdpInput(quint16 port, QObject *parent = nullptr);
35 ~RTCMUdpInput() override;
36
39 bool start();
40
42 void stop();
43
44 bool isRunning() const { return _running; }
45 quint16 port() const { return _port; }
46
48 void setPort(quint16 port);
49
50signals:
53 void rtcmDataReceived(const QByteArray &data);
54
57
58private slots:
59 void _readDatagrams();
60
61private:
62 QUdpSocket _socket;
63 quint16 _port;
64 bool _running = false;
65};
Listens on a UDP port for raw RTCM3 correction data and emits it for forwarding to connected vehicles...
void runningChanged()
void rtcmDataReceived(const QByteArray &data)
bool isRunning() const
void portChanged()
quint16 port() const