From 44d8027df967850784f8c0052ff5f6557ad06084 Mon Sep 17 00:00:00 2001 From: Jacob Dahl Date: Wed, 27 May 2020 10:25:21 -0600 Subject: [PATCH] Added a transmitOnly flag to UDP config. When enabled, the socket receive buffer is set to zero such that no data is ever received. Also updated the MavlinkSettings page such that new config settings respect the setting visibility. --- src/comm/LinkManager.cc | 1 + src/comm/UDPLink.cc | 20 ++++++++++++++++---- src/comm/UDPLink.h | 9 +++++++++ src/ui/preferences/MavlinkSettings.qml | 10 +++++++--- 4 files changed, 33 insertions(+), 7 deletions(-) diff --git a/src/comm/LinkManager.cc b/src/comm/LinkManager.cc index ab612a7f1..86bf1f322 100644 --- a/src/comm/LinkManager.cc +++ b/src/comm/LinkManager.cc @@ -512,6 +512,7 @@ void LinkManager::_updateAutoConnectLinks(void) UDPConfiguration* udpConfig = new UDPConfiguration(_mavlinkForwardingLinkName); udpConfig->setDynamic(true); + udpConfig->setTransmitOnly(true); QString hostName = _toolbox->settingsManager()->appSettings()->forwardMavlinkHostName()->rawValue().toString(); udpConfig->addHost(hostName); diff --git a/src/comm/UDPLink.cc b/src/comm/UDPLink.cc index f336424b6..b1316fae9 100644 --- a/src/comm/UDPLink.cc +++ b/src/comm/UDPLink.cc @@ -293,10 +293,18 @@ bool UDPLink::_hardwareConnect() //-- Make sure we have a large enough IO buffers #ifdef __mobile__ _socket->setSocketOption(QAbstractSocket::SendBufferSizeSocketOption, 64 * 1024); - _socket->setSocketOption(QAbstractSocket::ReceiveBufferSizeSocketOption, 128 * 1024); + if (_udpConfig->isTransmitOnly()) { + _socket->setSocketOption(QAbstractSocket::ReceiveBufferSizeSocketOption, 0); + } else { + _socket->setSocketOption(QAbstractSocket::ReceiveBufferSizeSocketOption, 128 * 1024); + } #else _socket->setSocketOption(QAbstractSocket::SendBufferSizeSocketOption, 256 * 1024); - _socket->setSocketOption(QAbstractSocket::ReceiveBufferSizeSocketOption, 512 * 1024); + if (_udpConfig->isTransmitOnly()) { + _socket->setSocketOption(QAbstractSocket::ReceiveBufferSizeSocketOption, 0);; + } else { + _socket->setSocketOption(QAbstractSocket::ReceiveBufferSizeSocketOption, 512 * 1024);; + } #endif _registerZeroconf(_udpConfig->localPort(), kZeroconfRegistration); QObject::connect(_socket, &QUdpSocket::readyRead, this, &UDPLink::readBytes); @@ -369,7 +377,9 @@ void UDPLink::_deregisterZeroconf() //-------------------------------------------------------------------------- //-- UDPConfiguration -UDPConfiguration::UDPConfiguration(const QString& name) : LinkConfiguration(name) +UDPConfiguration::UDPConfiguration(const QString& name) + : LinkConfiguration(name) + , _transmitOnly(false) { AutoConnectSettings* settings = qgcApp()->toolbox()->settingsManager()->autoConnectSettings(); _localPort = settings->udpListenPort()->rawValue().toInt(); @@ -379,7 +389,9 @@ UDPConfiguration::UDPConfiguration(const QString& name) : LinkConfiguration(name } } -UDPConfiguration::UDPConfiguration(UDPConfiguration* source) : LinkConfiguration(source) +UDPConfiguration::UDPConfiguration(UDPConfiguration* source) + : LinkConfiguration(source) + , _transmitOnly(false) { _copyFrom(source); } diff --git a/src/comm/UDPLink.h b/src/comm/UDPLink.h index de42986b5..2ff0a7ef1 100644 --- a/src/comm/UDPLink.h +++ b/src/comm/UDPLink.h @@ -111,6 +111,14 @@ public: */ void setLocalPort (quint16 port); + /*! + * @brief Set the UDP port to be transmit only. Receive buffer is set to zero. + * + */ + void setTransmitOnly (bool state) { _transmitOnly = state; } + + bool isTransmitOnly () { return _transmitOnly; } + /*! * @brief QML Interface */ @@ -142,6 +150,7 @@ private: QList _targetHosts; QStringList _hostList; ///< Exposed to QML quint16 _localPort; + bool _transmitOnly; }; class UDPLink : public LinkInterface diff --git a/src/ui/preferences/MavlinkSettings.qml b/src/ui/preferences/MavlinkSettings.qml index 869f120af..d8a62b3fb 100644 --- a/src/ui/preferences/MavlinkSettings.qml +++ b/src/ui/preferences/MavlinkSettings.qml @@ -158,6 +158,7 @@ Rectangle { id: mavlinkForwardingChecked text: qsTr("Enable MAVLink forwarding") fact: QGroundControl.settingsManager.appSettings.forwardMavlink + visible: QGroundControl.settingsManager.appSettings.forwardMavlink.visible } Row { @@ -165,21 +166,24 @@ Rectangle { QGCLabel { width: _labelWidth anchors.baseline: mavlinkForwardingHostNameField.baseline - visible: QGroundControl.settingsManager.appSettings.forwardMavlink.rawValue + visible: QGroundControl.settingsManager.appSettings.forwardMavlink.rawValue && + QGroundControl.settingsManager.appSettings.forwardMavlink.visible text: qsTr("Host name:") } FactTextField { id: mavlinkForwardingHostNameField fact: QGroundControl.settingsManager.appSettings.forwardMavlinkHostName width: _valueWidth - visible: QGroundControl.settingsManager.appSettings.forwardMavlink.rawValue + visible: QGroundControl.settingsManager.appSettings.forwardMavlink.rawValue && + QGroundControl.settingsManager.appSettings.forwardMavlink.visible anchors.verticalCenter: parent.verticalCenter } } QGCLabel { text: qsTr(" Changing the host name requires restart of application. ") - visible: QGroundControl.settingsManager.appSettings.forwardMavlink.rawValue + visible: QGroundControl.settingsManager.appSettings.forwardMavlink.rawValue && + QGroundControl.settingsManager.appSettings.forwardMavlink.visible } } } -- 2.22.0