3#include <QtQmlIntegration/QtQmlIntegration>
68 virtual void _writeBytes(
const QByteArray &bytes) = 0;
72 virtual bool _connect() = 0;
74 uint8_t _mavlinkChannel = std::numeric_limits<uint8_t>::max();
75 bool _decodedFirstMavlinkPacket =
false;
76 int _vehicleReferenceCount = 0;
77 bool _mavlinkV1TrafficReported =
false;
80 std::unique_ptr<SigningController> _signingController;
std::shared_ptr< LinkConfiguration > SharedLinkConfigurationPtr
std::shared_ptr< LinkInterface > SharedLinkInterfacePtr
std::weak_ptr< LinkInterface > WeakLinkInterfacePtr
The link interface defines the interface for all links used to communicate with the ground station ap...
void bytesReceived(LinkInterface *link, const QByteArray &data)
void setDecodedFirstMavlinkPacket(bool decodedFirstMavlinkPacket)
uint8_t mavlinkChannel() const
void addVehicleReference()
virtual void _freeMavlinkChannel()
virtual bool isLogReplay() const
bool decodedFirstMavlinkPacket() const
virtual Q_INVOKABLE void disconnect()=0
void reportMavlinkV1Traffic()
const SharedLinkConfigurationPtr linkConfiguration() const
void _connectionRemoved()
bool mavlinkChannelIsSet() const
virtual bool isConnected() const =0
virtual bool _allocateMavlinkChannel()
SigningController * signing()
Per-link signing state and confirmation state machine. Non-null after channel allocation.
void removeVehicleReference()
virtual bool isSecureConnection() const
Returns true if the connection is secure (e.g. USB, wired ethernet)
void communicationError(const QString &title, const QString &error)
const SigningController * signing() const
void bytesSent(LinkInterface *link, const QByteArray &data)
void writeBytesThreadSafe(const char *bytes, int length)
SharedLinkConfigurationPtr linkConfiguration()
SharedLinkConfigurationPtr _config
Manage communication links The Link Manager organizes the physical Links. It can manage arbitrary lin...
Owns MAVLink signing state and the deferred-confirmation state machine for one LinkInterface.