diff --git a/QGCCommon.pri b/QGCCommon.pri
index 21b88be8e3b96dd441257da490d81f12f18aba6d..517a55310a740a602a4ae497c7a721ec9521f41d 100644
--- a/QGCCommon.pri
+++ b/QGCCommon.pri
@@ -56,9 +56,10 @@ linux {
} else : macx {
macx-clang | macx-llvm {
message("Mac build")
- CONFIG += MacBuild
- CONFIG += x86_64
- CONFIG -= x86
+ CONFIG += MacBuild
+ CONFIG += x86_64
+ CONFIG -= x86
+ DEFINES += QGC_GST_TAISYNC_ENABLED
equals(QT_MAJOR_VERSION, 5) | greaterThan(QT_MINOR_VERSION, 5) {
QMAKE_MACOSX_DEPLOYMENT_TARGET = 10.7
} else {
@@ -83,6 +84,7 @@ linux {
DEFINES += QGC_NO_GOOGLE_MAPS
DEFINES += NO_SERIAL_LINK
DEFINES += QGC_DISABLE_UVC
+ DEFINES += QGC_GST_TAISYNC_ENABLED
QMAKE_IOS_DEPLOYMENT_TARGET = 8.0
QMAKE_APPLE_TARGETED_DEVICE_FAMILY = 1,2 # Universal
QMAKE_LFLAGS += -Wl,-no_pie
diff --git a/build_ios.sh b/build_ios.sh
index 3d3d8873aafae6fb061b8ba5192274c8673b4125..627a71477578bbf8677a7e4436e14214fa69697a 100755
--- a/build_ios.sh
+++ b/build_ios.sh
@@ -5,7 +5,7 @@ if [ ! -d /Volumes/RAMDisk ] ; then
exit 1
fi
#-- Set to my local installation
-QMAKE=/Users/gus/Applications/Qt/5.11.0/ios/bin/qmake
+QMAKE=/Users/gus/Applications/Qt/5.11.2/ios/bin/qmake
#-- Using Travis variables as this will eventually live there
SHADOW_BUILD_DIR=/Volumes/RAMDisk/build-qgroundcontrol-iOS-Release
TRAVIS_BUILD_DIR=/Users/gus/github/work/UpstreamQGC
diff --git a/qgroundcontrol.pro b/qgroundcontrol.pro
index c9331d6227753ba4efc692e965ef80b7cf85d1f0..f3d320104856d95c22c7254e0b1e1889c01e1d58 100644
--- a/qgroundcontrol.pro
+++ b/qgroundcontrol.pro
@@ -628,7 +628,7 @@ HEADERS += \
AndroidBuild {
HEADERS += \
- src/Joystick/JoystickAndroid.h \
+ src/Joystick/JoystickAndroid.h \
}
DebugBuild {
@@ -714,7 +714,7 @@ iOSBuild {
AndroidBuild {
SOURCES += src/MobileScreenMgr.cc \
- src/Joystick/JoystickAndroid.cc \
+ src/Joystick/JoystickAndroid.cc \
}
SOURCES += \
@@ -1106,6 +1106,27 @@ SOURCES += \
src/FactSystem/ParameterManager.cc \
src/FactSystem/SettingsFact.cc \
+#-------------------------------------------------------------------------------------
+# Taisync
+contains (DEFINES, QGC_GST_TAISYNC_ENABLED) {
+ INCLUDEPATH += \
+ src/Taisync
+
+ HEADERS += \
+ src/comm/TaisyncLink.h \
+ src/Taisync/TaisyncHandler.h \
+ src/Taisync/TaisyncSettings.h \
+ src/Taisync/TaisyncTelemetry.h \
+ src/Taisync/TaisyncVideoReceiver.h \
+
+ SOURCES += \
+ src/comm/TaisyncLink.cc \
+ src/Taisync/TaisyncHandler.cc \
+ src/Taisync/TaisyncSettings.cc \
+ src/Taisync/TaisyncTelemetry.cc \
+ src/Taisync/TaisyncVideoReceiver.cc \
+}
+
#-------------------------------------------------------------------------------------
# AirMap
diff --git a/qgroundcontrol.qrc b/qgroundcontrol.qrc
index bdea8a6b9c5ea3a213407188ba74e0b7719b6eb8..5143cec2e952cceb7b5d8772f88546b30d4a1a9d 100644
--- a/qgroundcontrol.qrc
+++ b/qgroundcontrol.qrc
@@ -199,6 +199,7 @@
src/PlanView/SurveyItemEditor.qml
src/AutoPilotPlugins/Common/SyslinkComponent.qml
src/ui/preferences/TcpSettings.qml
+ src/Taisync/TaisyncSettings.qml
src/test.qml
src/ui/preferences/UdpSettings.qml
src/FlightMap/Widgets/ValuePageWidget.qml
diff --git a/src/Settings/SettingsGroup.h b/src/Settings/SettingsGroup.h
index 4b854d7c6f0bc18e394bf9f07cef90ee5d182ac9..42920b40a1a01be9495e36cb561d56c1e0513456 100644
--- a/src/Settings/SettingsGroup.h
+++ b/src/Settings/SettingsGroup.h
@@ -54,13 +54,19 @@
class SettingsGroup : public QObject
{
Q_OBJECT
-
+
public:
/// @param name Name for this Settings group
/// @param settingsGroup Group to place settings in for QSettings::setGroup
SettingsGroup(const QString &name, const QString &settingsGroup, QObject* parent = nullptr);
- Q_PROPERTY(bool visible MEMBER _visible CONSTANT)
+ Q_PROPERTY(bool visible READ visible WRITE setVisible NOTIFY visibleChanged)
+
+ virtual bool visible () { return _visible; }
+ virtual void setVisible (bool vis) { _visible = vis; emit visibleChanged(); }
+
+signals:
+ void visibleChanged ();
protected:
SettingsFact* _createSettingsFact(const QString& factName);
diff --git a/src/Taisync/TaisyncHandler.cc b/src/Taisync/TaisyncHandler.cc
new file mode 100644
index 0000000000000000000000000000000000000000..d39cd3d67c9123235b2a459cfcacd63f88f05060
--- /dev/null
+++ b/src/Taisync/TaisyncHandler.cc
@@ -0,0 +1,75 @@
+/****************************************************************************
+ *
+ * (c) 2009-2016 QGROUNDCONTROL PROJECT
+ *
+ * QGroundControl is licensed according to the terms in the file
+ * COPYING.md in the root of the source code directory.
+ *
+ ****************************************************************************/
+
+#include "TaisyncHandler.h"
+#include "SettingsManager.h"
+#include "QGCApplication.h"
+#include "VideoManager.h"
+
+
+QGC_LOGGING_CATEGORY(TaisyncLog, "TaisyncLog")
+
+//-----------------------------------------------------------------------------
+TaisyncHandler::TaisyncHandler(QObject* parent)
+ : QObject (parent)
+{
+}
+
+//-----------------------------------------------------------------------------
+TaisyncHandler::~TaisyncHandler()
+{
+ close();
+}
+
+//-----------------------------------------------------------------------------
+void
+TaisyncHandler::close()
+{
+ qCDebug(TaisyncLog) << "Close Taisync TCP";
+ if(_tcpSocket) {
+ _tcpSocket->close();
+ _tcpSocket->deleteLater();
+ _tcpSocket = nullptr;
+ }
+}
+
+//-----------------------------------------------------------------------------
+void
+TaisyncHandler::_start(uint16_t port)
+{
+ qCDebug(TaisyncLog) << "Start Taisync TCP on port" << port;
+ _tcpServer = new QTcpServer(this);
+ QObject::connect(_tcpServer, &QTcpServer::newConnection, this, &TaisyncHandler::_newConnection);
+ _tcpServer->listen(QHostAddress::AnyIPv4, port);
+}
+
+//-----------------------------------------------------------------------------
+void
+TaisyncHandler::_newConnection()
+{
+ qCDebug(TaisyncLog) << "New Taisync TCP Connection";
+ if(_tcpSocket) {
+ _tcpSocket->close();
+ _tcpSocket->deleteLater();
+ }
+ _tcpSocket = _tcpServer->nextPendingConnection();
+ QObject::connect(_tcpSocket, &QIODevice::readyRead, this, &TaisyncHandler::_readBytes);
+}
+
+//-----------------------------------------------------------------------------
+void
+TaisyncHandler::_socketDisconnected()
+{
+ qCDebug(TaisyncLog) << "Taisync Telemetry Connection Closed";
+ if(_tcpSocket) {
+ _tcpSocket->close();
+ _tcpSocket->deleteLater();
+ _tcpSocket = nullptr;
+ }
+}
diff --git a/src/Taisync/TaisyncHandler.h b/src/Taisync/TaisyncHandler.h
new file mode 100644
index 0000000000000000000000000000000000000000..d1aea53a760fabdc22c6c08a92f415e617f13b92
--- /dev/null
+++ b/src/Taisync/TaisyncHandler.h
@@ -0,0 +1,45 @@
+/****************************************************************************
+ *
+ * (c) 2009-2016 QGROUNDCONTROL PROJECT
+ *
+ * QGroundControl is licensed according to the terms in the file
+ * COPYING.md in the root of the source code directory.
+ *
+ ****************************************************************************/
+
+#pragma once
+
+#include "QGCLoggingCategory.h"
+
+#include
+#include
+
+#define TAISYNC_VIDEO_UDP_PORT 5600
+#define TAISYNC_VIDEO_TCP_PORT 8000
+#define TAISYNC_SETTINGS_PORT 8200
+#define TAISYNC_TELEM_PORT 8400
+
+Q_DECLARE_LOGGING_CATEGORY(TaisyncLog)
+
+class TaisyncHandler : public QObject
+{
+ Q_OBJECT
+public:
+
+ explicit TaisyncHandler (QObject* parent = nullptr);
+ ~TaisyncHandler ();
+ virtual void start () = 0;
+ virtual void close ();
+
+protected:
+ virtual void _start (uint16_t port);
+
+protected slots:
+ virtual void _newConnection ();
+ virtual void _socketDisconnected ();
+ virtual void _readBytes () = 0;
+
+protected:
+ QTcpServer* _tcpServer = nullptr;
+ QTcpSocket* _tcpSocket = nullptr;
+};
diff --git a/src/Taisync/TaisyncSettings.cc b/src/Taisync/TaisyncSettings.cc
new file mode 100644
index 0000000000000000000000000000000000000000..3cd44db870cd6741d7735f807ad007c4a51c0929
--- /dev/null
+++ b/src/Taisync/TaisyncSettings.cc
@@ -0,0 +1,39 @@
+/****************************************************************************
+ *
+ * (c) 2009-2016 QGROUNDCONTROL PROJECT
+ *
+ * QGroundControl is licensed according to the terms in the file
+ * COPYING.md in the root of the source code directory.
+ *
+ ****************************************************************************/
+
+#include "TaisyncSettings.h"
+#include "SettingsManager.h"
+#include "QGCApplication.h"
+#include "VideoManager.h"
+
+
+QGC_LOGGING_CATEGORY(TaisyncSettingsLog, "TaisyncSettingsLog")
+
+//-----------------------------------------------------------------------------
+TaisyncSettings::TaisyncSettings(QObject* parent)
+ : TaisyncHandler(parent)
+{
+}
+
+//-----------------------------------------------------------------------------
+void
+TaisyncSettings::start()
+{
+ qCDebug(TaisyncSettingsLog) << "Start Taisync Settings";
+ _start(TAISYNC_SETTINGS_PORT);
+}
+
+//-----------------------------------------------------------------------------
+void
+TaisyncSettings::_readBytes()
+{
+ QByteArray bytesIn = _tcpSocket->read(_tcpSocket->bytesAvailable());
+ qCDebug(TaisyncSettingsLog) << "Taisync settings data:" << bytesIn.size();
+}
+
diff --git a/src/Taisync/TaisyncSettings.h b/src/Taisync/TaisyncSettings.h
new file mode 100644
index 0000000000000000000000000000000000000000..b33b8ac613e2d952d1fcd06637f38a558a7fd02c
--- /dev/null
+++ b/src/Taisync/TaisyncSettings.h
@@ -0,0 +1,27 @@
+/****************************************************************************
+ *
+ * (c) 2009-2016 QGROUNDCONTROL PROJECT
+ *
+ * QGroundControl is licensed according to the terms in the file
+ * COPYING.md in the root of the source code directory.
+ *
+ ****************************************************************************/
+
+#pragma once
+
+#include "TaisyncHandler.h"
+
+Q_DECLARE_LOGGING_CATEGORY(TaisyncSettingsLog)
+
+class TaisyncSettings : public TaisyncHandler
+{
+ Q_OBJECT
+public:
+
+ explicit TaisyncSettings (QObject* parent = nullptr);
+ void start () override;
+
+protected slots:
+ void _readBytes () override;
+
+};
diff --git a/src/Taisync/TaisyncSettings.qml b/src/Taisync/TaisyncSettings.qml
new file mode 100644
index 0000000000000000000000000000000000000000..692a84b67132a47574f31ebfdc3d47b2c6cf38c6
--- /dev/null
+++ b/src/Taisync/TaisyncSettings.qml
@@ -0,0 +1,36 @@
+/****************************************************************************
+ *
+ * (c) 2009-2016 QGROUNDCONTROL PROJECT
+ *
+ * QGroundControl is licensed according to the terms in the file
+ * COPYING.md in the root of the source code directory.
+ *
+ ****************************************************************************/
+
+
+import QtQuick 2.3
+import QtQuick.Controls 1.2
+import QtQuick.Dialogs 1.2
+
+import QGroundControl 1.0
+import QGroundControl.Controls 1.0
+import QGroundControl.ScreenTools 1.0
+import QGroundControl.Palette 1.0
+
+Column {
+ id: _taisyncSettings
+ spacing: ScreenTools.defaultFontPixelHeight * 0.5
+ anchors.margins: ScreenTools.defaultFontPixelWidth
+ function saveSettings() {
+ if(subEditConfig) {
+ subEditConfig.videoEnabled = videoEnableCheck.checked
+ }
+ }
+ QGCCheckBox {
+ id: videoEnableCheck
+ text: qsTr("Enable Taisync video link")
+ Component.onCompleted: {
+ checked = subEditConfig && subEditConfig.linkType === LinkConfiguration.TypeTaisync ? subEditConfig.videoEnabled : false
+ }
+ }
+}
diff --git a/src/Taisync/TaisyncTelemetry.cc b/src/Taisync/TaisyncTelemetry.cc
new file mode 100644
index 0000000000000000000000000000000000000000..9993cf2ffc730ce3edb34117c843d27c4b858e6c
--- /dev/null
+++ b/src/Taisync/TaisyncTelemetry.cc
@@ -0,0 +1,65 @@
+/****************************************************************************
+ *
+ * (c) 2009-2016 QGROUNDCONTROL PROJECT
+ *
+ * QGroundControl is licensed according to the terms in the file
+ * COPYING.md in the root of the source code directory.
+ *
+ ****************************************************************************/
+
+#include "TaisyncTelemetry.h"
+#include "SettingsManager.h"
+#include "QGCApplication.h"
+#include "VideoManager.h"
+
+
+QGC_LOGGING_CATEGORY(TaisyncTelemetryLog, "TaisyncTelemetryLog")
+
+//-----------------------------------------------------------------------------
+TaisyncTelemetry::TaisyncTelemetry(QObject* parent)
+ : TaisyncHandler(parent)
+{
+}
+
+//-----------------------------------------------------------------------------
+void
+TaisyncTelemetry::close()
+{
+ TaisyncHandler::close();
+ qCDebug(TaisyncTelemetryLog) << "Close Taisync Telemetry";
+}
+
+//-----------------------------------------------------------------------------
+void
+TaisyncTelemetry::start()
+{
+ qCDebug(TaisyncTelemetryLog) << "Start Taisync Telemetry";
+ _start(TAISYNC_TELEM_PORT);
+}
+
+//-----------------------------------------------------------------------------
+void
+TaisyncTelemetry::writeBytes(QByteArray bytes)
+{
+ if(_tcpSocket) {
+ _tcpSocket->write(bytes);
+ }
+}
+
+//-----------------------------------------------------------------------------
+void
+TaisyncTelemetry::_newConnection()
+{
+ TaisyncHandler::_newConnection();
+ qCDebug(TaisyncTelemetryLog) << "New Taisync Temeletry Connection";
+}
+
+//-----------------------------------------------------------------------------
+void
+TaisyncTelemetry::_readBytes()
+{
+ while(_tcpSocket->bytesAvailable()) {
+ QByteArray bytesIn = _tcpSocket->read(_tcpSocket->bytesAvailable());
+ emit bytesReady(bytesIn);
+ }
+}
diff --git a/src/Taisync/TaisyncTelemetry.h b/src/Taisync/TaisyncTelemetry.h
new file mode 100644
index 0000000000000000000000000000000000000000..fe70aec93fbcaffb799a28cc0683cedc22d29b25
--- /dev/null
+++ b/src/Taisync/TaisyncTelemetry.h
@@ -0,0 +1,35 @@
+/****************************************************************************
+ *
+ * (c) 2009-2016 QGROUNDCONTROL PROJECT
+ *
+ * QGroundControl is licensed according to the terms in the file
+ * COPYING.md in the root of the source code directory.
+ *
+ ****************************************************************************/
+
+#pragma once
+
+#include "TaisyncHandler.h"
+#include
+#include
+
+Q_DECLARE_LOGGING_CATEGORY(TaisyncTelemetryLog)
+
+class TaisyncTelemetry : public TaisyncHandler
+{
+ Q_OBJECT
+public:
+
+ explicit TaisyncTelemetry (QObject* parent = nullptr);
+ void close () override;
+ void start () override;
+ void writeBytes (QByteArray bytes);
+
+signals:
+ void bytesReady (QByteArray bytes);
+
+private slots:
+ void _newConnection () override;
+ void _readBytes () override;
+
+};
diff --git a/src/Taisync/TaisyncVideoReceiver.cc b/src/Taisync/TaisyncVideoReceiver.cc
new file mode 100644
index 0000000000000000000000000000000000000000..b4699cc68c7e7c1523aa1dac82ce4a25f7563e8e
--- /dev/null
+++ b/src/Taisync/TaisyncVideoReceiver.cc
@@ -0,0 +1,52 @@
+/****************************************************************************
+ *
+ * (c) 2009-2016 QGROUNDCONTROL PROJECT
+ *
+ * QGroundControl is licensed according to the terms in the file
+ * COPYING.md in the root of the source code directory.
+ *
+ ****************************************************************************/
+
+#include "TaisyncVideoReceiver.h"
+#include "SettingsManager.h"
+#include "QGCApplication.h"
+#include "VideoManager.h"
+
+
+QGC_LOGGING_CATEGORY(TaisyncVideoReceiverLog, "TaisyncVideoReceiverLog")
+
+//-----------------------------------------------------------------------------
+TaisyncVideoReceiver::TaisyncVideoReceiver(QObject* parent)
+ : TaisyncHandler(parent)
+{
+}
+
+//-----------------------------------------------------------------------------
+void
+TaisyncVideoReceiver::close()
+{
+ TaisyncHandler::close();
+ qCDebug(TaisyncVideoReceiverLog) << "Close Taisync Video Receiver";
+ if(_udpVideoSocket) {
+ _udpVideoSocket->close();
+ _udpVideoSocket->deleteLater();
+ _udpVideoSocket = nullptr;
+ }
+}
+
+//-----------------------------------------------------------------------------
+void
+TaisyncVideoReceiver::start()
+{
+ qCDebug(TaisyncVideoReceiverLog) << "Start Taisync Video Receiver";
+ _udpVideoSocket = new QUdpSocket(this);
+ _start(TAISYNC_VIDEO_TCP_PORT);
+}
+
+//-----------------------------------------------------------------------------
+void
+TaisyncVideoReceiver::_readBytes()
+{
+ QByteArray bytesIn = _tcpSocket->read(_tcpSocket->bytesAvailable());
+ _udpVideoSocket->writeDatagram(bytesIn, QHostAddress::LocalHost, TAISYNC_VIDEO_UDP_PORT);
+}
diff --git a/src/Taisync/TaisyncVideoReceiver.h b/src/Taisync/TaisyncVideoReceiver.h
new file mode 100644
index 0000000000000000000000000000000000000000..c7ad8bae06972a8e4bcfcd7c32e1f9c385cfee81
--- /dev/null
+++ b/src/Taisync/TaisyncVideoReceiver.h
@@ -0,0 +1,31 @@
+/****************************************************************************
+ *
+ * (c) 2009-2016 QGROUNDCONTROL PROJECT
+ *
+ * QGroundControl is licensed according to the terms in the file
+ * COPYING.md in the root of the source code directory.
+ *
+ ****************************************************************************/
+
+#pragma once
+
+#include "TaisyncHandler.h"
+#include
+
+Q_DECLARE_LOGGING_CATEGORY(TaisyncVideoReceiverLog)
+
+class TaisyncVideoReceiver : public TaisyncHandler
+{
+ Q_OBJECT
+public:
+
+ explicit TaisyncVideoReceiver (QObject* parent = nullptr);
+ void start () override;
+ void close () override;
+
+private slots:
+ void _readBytes () override;
+
+private:
+ QUdpSocket* _udpVideoSocket = nullptr;
+};
diff --git a/src/comm/LinkConfiguration.cc b/src/comm/LinkConfiguration.cc
index c27239517cea29e159682d3c78ba52c2d2fa3473..1fbdb0faed5aca5370a15ef9667b5b03eb5d88e5 100644
--- a/src/comm/LinkConfiguration.cc
+++ b/src/comm/LinkConfiguration.cc
@@ -29,11 +29,14 @@
#ifdef QT_DEBUG
#include "MockLink.h"
#endif
+#if defined(QGC_GST_TAISYNC_ENABLED)
+#include "TaisyncLink.h"
+#endif
#define LINK_SETTING_ROOT "LinkConfigurations"
LinkConfiguration::LinkConfiguration(const QString& name)
- : _link(NULL)
+ : _link(nullptr)
, _name(name)
, _dynamic(false)
, _autoConnect(false)
@@ -80,7 +83,7 @@ const QString LinkConfiguration::settingsRoot()
*/
LinkConfiguration* LinkConfiguration::createSettings(int type, const QString& name)
{
- LinkConfiguration* config = NULL;
+ LinkConfiguration* config = nullptr;
switch(type) {
#ifndef NO_SERIAL_LINK
case LinkConfiguration::TypeSerial:
@@ -107,6 +110,11 @@ LinkConfiguration* LinkConfiguration::createSettings(int type, const QString& na
case LinkConfiguration::TypeMock:
config = new MockConfiguration(name);
break;
+#endif
+#if defined(QGC_GST_TAISYNC_ENABLED)
+ case LinkConfiguration::TypeTaisync:
+ config = new TaisyncConfiguration(name);
+ break;
#endif
}
return config;
@@ -118,7 +126,7 @@ LinkConfiguration* LinkConfiguration::createSettings(int type, const QString& na
*/
LinkConfiguration* LinkConfiguration::duplicateSettings(LinkConfiguration* source)
{
- LinkConfiguration* dupe = NULL;
+ LinkConfiguration* dupe = nullptr;
switch(source->type()) {
#ifndef NO_SERIAL_LINK
case TypeSerial:
@@ -145,9 +153,13 @@ LinkConfiguration* LinkConfiguration::duplicateSettings(LinkConfiguration* sourc
case TypeMock:
dupe = new MockConfiguration(dynamic_cast(source));
break;
+#endif
+#if defined(QGC_GST_TAISYNC_ENABLED)
+ case TypeTaisync:
+ dupe = new TaisyncConfiguration(dynamic_cast(source));
+ break;
#endif
case TypeLast:
- default:
break;
}
return dupe;
diff --git a/src/comm/LinkConfiguration.h b/src/comm/LinkConfiguration.h
index a32e65f53e2caa0c0189315e43c3faf1a36adb30..11ba5bc37277a92b7e55c565817d8de41e43154a 100644
--- a/src/comm/LinkConfiguration.h
+++ b/src/comm/LinkConfiguration.h
@@ -51,6 +51,9 @@ public:
#endif
TypeUdp, ///< UDP Link
TypeTcp, ///< TCP Link
+#if defined(QGC_GST_TAISYNC_ENABLED)
+ TypeTaisync,
+#endif
#ifdef QGC_ENABLE_BLUETOOTH
TypeBluetooth, ///< Bluetooth Link
#endif
diff --git a/src/comm/LinkManager.cc b/src/comm/LinkManager.cc
index a0ba291f4c1f4a7e14b981e780784ac5d5dbd34e..9a210f16aa3ef00df398ec45fbdbee9f047d5af0 100644
--- a/src/comm/LinkManager.cc
+++ b/src/comm/LinkManager.cc
@@ -24,6 +24,9 @@
#ifdef QGC_ENABLE_BLUETOOTH
#include "BluetoothLink.h"
#endif
+#if defined(QGC_GST_TAISYNC_ENABLED)
+#include "TaisyncLink.h"
+#endif
#ifndef __mobile__
#include "GPSManager.h"
@@ -49,11 +52,11 @@ LinkManager::LinkManager(QGCApplication* app, QGCToolbox* toolbox)
, _configurationsLoaded(false)
, _connectionsSuspended(false)
, _mavlinkChannelsUsedBitMask(1) // We never use channel 0 to avoid sequence numbering problems
- , _autoConnectSettings(NULL)
- , _mavlinkProtocol(NULL)
+ , _autoConnectSettings(nullptr)
+ , _mavlinkProtocol(nullptr)
#ifndef __mobile__
#ifndef NO_SERIAL_LINK
- , _nmeaPort(NULL)
+ , _nmeaPort(nullptr)
#endif
#endif
{
@@ -104,11 +107,11 @@ void LinkManager::createConnectedLink(LinkConfiguration* config)
LinkInterface* LinkManager::createConnectedLink(SharedLinkConfigurationPointer& config, bool isPX4Flow)
{
if (!config) {
- qWarning() << "LinkManager::createConnectedLink called with NULL config";
- return NULL;
+ qWarning() << "LinkManager::createConnectedLink called with nullptr config";
+ return nullptr;
}
- LinkInterface* pLink = NULL;
+ LinkInterface* pLink = nullptr;
switch(config->type()) {
#ifndef NO_SERIAL_LINK
case LinkConfiguration::TypeSerial:
@@ -117,7 +120,7 @@ LinkInterface* LinkManager::createConnectedLink(SharedLinkConfigurationPointer&
if (serialConfig) {
pLink = new SerialLink(config, isPX4Flow);
if (serialConfig->usbDirect()) {
- _activeLinkCheckList.append((SerialLink*)pLink);
+ _activeLinkCheckList.append(dynamic_cast(pLink));
if (!_activeLinkCheckTimer.isActive()) {
_activeLinkCheckTimer.start();
}
@@ -148,17 +151,19 @@ LinkInterface* LinkManager::createConnectedLink(SharedLinkConfigurationPointer&
case LinkConfiguration::TypeMock:
pLink = new MockLink(config);
break;
+#endif
+#if defined(QGC_GST_TAISYNC_ENABLED)
+ case LinkConfiguration::TypeTaisync:
+ pLink = new TaisyncLink(config);
+ break;
#endif
case LinkConfiguration::TypeLast:
- default:
break;
}
-
if (pLink) {
_addLink(pLink);
connectLink(pLink);
}
-
return pLink;
}
@@ -174,7 +179,7 @@ LinkInterface* LinkManager::createConnectedLink(const QString& name)
}
}
}
- return NULL;
+ return nullptr;
}
void LinkManager::_addLink(LinkInterface* link)
@@ -289,8 +294,8 @@ SharedLinkInterfacePointer LinkManager::sharedLinkInterfacePointerForLink(LinkIn
}
}
- qWarning() << "LinkManager::sharedLinkInterfaceForLink returning NULL";
- return SharedLinkInterfacePointer(NULL);
+ qWarning() << "LinkManager::sharedLinkInterfaceForLink returning nullptr";
+ return SharedLinkInterfacePointer(nullptr);
}
/// @brief If all new connections should be suspended a message is displayed to the user and true
@@ -371,42 +376,46 @@ void LinkManager::loadLinkConfigurationList()
QString root(LinkConfiguration::settingsRoot());
root += QString("/Link%1").arg(i);
if(settings.contains(root + "/type")) {
- int type = settings.value(root + "/type").toInt();
- if((LinkConfiguration::LinkType)type < LinkConfiguration::TypeLast) {
+ LinkConfiguration::LinkType type = static_cast(settings.value(root + "/type").toInt());
+ if(type < LinkConfiguration::TypeLast) {
if(settings.contains(root + "/name")) {
QString name = settings.value(root + "/name").toString();
if(!name.isEmpty()) {
- LinkConfiguration* pLink = NULL;
+ LinkConfiguration* pLink = nullptr;
bool autoConnect = settings.value(root + "/auto").toBool();
bool highLatency = settings.value(root + "/high_latency").toBool();
- switch((LinkConfiguration::LinkType)type) {
+ switch(type) {
#ifndef NO_SERIAL_LINK
case LinkConfiguration::TypeSerial:
- pLink = (LinkConfiguration*)new SerialConfiguration(name);
+ pLink = dynamic_cast(new SerialConfiguration(name));
break;
#endif
case LinkConfiguration::TypeUdp:
- pLink = (LinkConfiguration*)new UDPConfiguration(name);
+ pLink = dynamic_cast(new UDPConfiguration(name));
break;
case LinkConfiguration::TypeTcp:
- pLink = (LinkConfiguration*)new TCPConfiguration(name);
+ pLink = dynamic_cast(new TCPConfiguration(name));
break;
#ifdef QGC_ENABLE_BLUETOOTH
case LinkConfiguration::TypeBluetooth:
- pLink = (LinkConfiguration*)new BluetoothConfiguration(name);
+ pLink = dynamic_cast(new BluetoothConfiguration(name));
break;
#endif
#ifndef __mobile__
case LinkConfiguration::TypeLogReplay:
- pLink = (LinkConfiguration*)new LogReplayLinkConfiguration(name);
+ pLink = dynamic_cast(new LogReplayLinkConfiguration(name));
break;
#endif
#ifdef QT_DEBUG
case LinkConfiguration::TypeMock:
- pLink = (LinkConfiguration*)new MockConfiguration(name);
+ pLink = dynamic_cast(new MockConfiguration(name));
+ break;
+#endif
+#if defined(QGC_GST_TAISYNC_ENABLED)
+ case LinkConfiguration::TypeTaisync:
+ pLink = dynamic_cast(new TaisyncConfiguration(name));
break;
#endif
- default:
case LinkConfiguration::TypeLast:
break;
}
@@ -456,7 +465,7 @@ SerialConfiguration* LinkManager::_autoconnectConfigurationsContainsPort(const Q
qWarning() << "Internal error";
}
}
- return NULL;
+ return nullptr;
}
#endif
@@ -465,10 +474,9 @@ void LinkManager::_updateAutoConnectLinks(void)
if (_connectionsSuspended || qgcApp()->runningUnitTests()) {
return;
}
-
// Re-add UDP if we need to
bool foundUDP = false;
- for (int i=0; i<_sharedLinks.count(); i++) {
+ for (int i = 0; i < _sharedLinks.count(); i++) {
LinkConfiguration* linkConfig = _sharedLinks[i]->getLinkConfiguration();
if (linkConfig->type() == LinkConfiguration::TypeUdp && linkConfig->name() == _defaultUPDLinkName) {
foundUDP = true;
@@ -477,7 +485,7 @@ void LinkManager::_updateAutoConnectLinks(void)
}
if (!foundUDP && _autoConnectSettings->autoConnectUDP()->rawValue().toBool()) {
qCDebug(LinkManagerLog) << "New auto-connect UDP port added";
- // Default UDPConfiguration is set up for autoconnect
+ //-- Default UDPConfiguration is set up for autoconnect
UDPConfiguration* udpConfig = new UDPConfiguration(_defaultUPDLinkName);
udpConfig->setDynamic(true);
SharedLinkConfigurationPointer config = addConfiguration(udpConfig);
@@ -488,7 +496,6 @@ void LinkManager::_updateAutoConnectLinks(void)
#ifndef NO_SERIAL_LINK
QStringList currentPorts;
QList portList;
-
#ifdef __android__
// Android builds only support a single serial connection. Repeatedly calling availablePorts after that one serial
// port is connected leaks file handles due to a bug somewhere in android serial code. In order to work around that
@@ -524,22 +531,18 @@ void LinkManager::_updateAutoConnectLinks(void)
_nmeaDeviceName = portInfo.systemLocation().trimmed();
qCDebug(LinkManagerLog) << "Configuring nmea port" << _nmeaDeviceName;
QSerialPort* newPort = new QSerialPort(portInfo);
-
_nmeaBaud = _autoConnectSettings->autoConnectNmeaBaud()->cookedValue().toUInt();
- newPort->setBaudRate(_nmeaBaud);
+ newPort->setBaudRate(static_cast(_nmeaBaud));
qCDebug(LinkManagerLog) << "Configuring nmea baudrate" << _nmeaBaud;
-
// This will stop polling old device if previously set
_toolbox->qgcPositionManager()->setNmeaSourceDevice(newPort);
-
if (_nmeaPort) {
delete _nmeaPort;
}
_nmeaPort = newPort;
-
} else if (_autoConnectSettings->autoConnectNmeaBaud()->cookedValue().toUInt() != _nmeaBaud) {
_nmeaBaud = _autoConnectSettings->autoConnectNmeaBaud()->cookedValue().toUInt();
- _nmeaPort->setBaudRate(_nmeaBaud);
+ _nmeaPort->setBaudRate(static_cast(_nmeaBaud));
qCDebug(LinkManagerLog) << "Configuring nmea baudrate" << _nmeaBaud;
}
} else
@@ -551,7 +554,6 @@ void LinkManager::_updateAutoConnectLinks(void)
qCDebug(LinkManagerLog) << "Waiting for bootloader to finish" << portInfo.systemLocation();
continue;
}
-
if (_autoconnectConfigurationsContainsPort(portInfo.systemLocation()) || _autoConnectRTKPort == portInfo.systemLocation()) {
qCDebug(LinkManagerVerboseLog) << "Skipping existing autoconnect" << portInfo.systemLocation();
} else if (!_autoconnectWaitList.contains(portInfo.systemLocation())) {
@@ -561,10 +563,8 @@ void LinkManager::_updateAutoConnectLinks(void)
qCDebug(LinkManagerLog) << "Waiting for next autoconnect pass" << portInfo.systemLocation();
_autoconnectWaitList[portInfo.systemLocation()] = 1;
} else if (++_autoconnectWaitList[portInfo.systemLocation()] * _autoconnectUpdateTimerMSecs > _autoconnectConnectDelayMSecs) {
- SerialConfiguration* pSerialConfig = NULL;
-
+ SerialConfiguration* pSerialConfig = nullptr;
_autoconnectWaitList.remove(portInfo.systemLocation());
-
switch (boardType) {
case QGCSerialPortInfo::BoardTypePixhawk:
if (_autoConnectSettings->autoConnectPixhawk()->rawValue().toBool()) {
@@ -600,7 +600,6 @@ void LinkManager::_updateAutoConnectLinks(void)
qWarning() << "Internal error";
continue;
}
-
if (pSerialConfig) {
qCDebug(LinkManagerLog) << "New auto-connect port added: " << pSerialConfig->name() << portInfo.systemLocation();
pSerialConfig->setBaud(boardType == QGCSerialPortInfo::BoardTypeSiKRadio ? 57600 : 115200);
@@ -616,7 +615,7 @@ void LinkManager::_updateAutoConnectLinks(void)
#ifndef __android__
// Android builds only support a single serial connection. Repeatedly calling availablePorts after that one serial
// port is connected leaks file handles due to a bug somewhere in android serial code. In order to work around that
- // bug after we connect the first serial port we stop probing for additional ports. The means we must rely on
+ // bug after we connect the first serial port we stop probing for additional ports. That means we must rely on
// the port disconnecting itself when the radio is pulled to signal communication list as opposed to automatically
// closing the Link.
@@ -683,20 +682,23 @@ QStringList LinkManager::linkTypeStrings(void) const
if(!list.size())
{
#ifndef NO_SERIAL_LINK
- list += "Serial";
+ list += tr("Serial");
+#endif
+ list += tr("UDP");
+ list += tr("TCP");
+#if defined(QGC_GST_TAISYNC_ENABLED)
+ list += tr("Taisync");
#endif
- list += "UDP";
- list += "TCP";
#ifdef QGC_ENABLE_BLUETOOTH
list += "Bluetooth";
#endif
#ifdef QT_DEBUG
- list += "Mock Link";
+ list += tr("Mock Link");
#endif
#ifndef __mobile__
- list += "Log Replay";
+ list += tr("Log Replay");
#endif
- if (list.size() != (int)LinkConfiguration::TypeLast) {
+ if (list.size() != static_cast(LinkConfiguration::TypeLast)) {
qWarning() << "Internal error";
}
}
@@ -777,7 +779,7 @@ bool LinkManager::endCreateConfiguration(LinkConfiguration* config)
LinkConfiguration* LinkManager::createConfiguration(int type, const QString& name)
{
#ifndef NO_SERIAL_LINK
- if((LinkConfiguration::LinkType)type == LinkConfiguration::TypeSerial)
+ if(static_cast(type) == LinkConfiguration::TypeSerial)
_updateSerialPorts();
#endif
return LinkConfiguration::createSettings(type, name);
@@ -793,11 +795,10 @@ LinkConfiguration* LinkManager::startConfigurationEditing(LinkConfiguration* con
return LinkConfiguration::duplicateSettings(config);
} else {
qWarning() << "Internal error";
- return NULL;
+ return nullptr;
}
}
-
void LinkManager::_fixUnnamed(LinkConfiguration* config)
{
if (config) {
@@ -819,16 +820,25 @@ void LinkManager::_fixUnnamed(LinkConfiguration* config)
#endif
case LinkConfiguration::TypeUdp:
config->setName(
- QString("UDP Link on Port %1").arg(dynamic_cast(config)->localPort()));
+ QString("UDP Link on Port %1").arg(dynamic_cast(config)->localPort()));
break;
case LinkConfiguration::TypeTcp: {
TCPConfiguration* tconfig = dynamic_cast(config);
if(tconfig) {
config->setName(
- QString("TCP Link %1:%2").arg(tconfig->address().toString()).arg((int)tconfig->port()));
+ QString("TCP Link %1:%2").arg(tconfig->address().toString()).arg(static_cast(tconfig->port())));
}
}
break;
+#if defined(QGC_GST_TAISYNC_ENABLED)
+ case LinkConfiguration::TypeTaisync: {
+ TaisyncConfiguration* tconfig = dynamic_cast(config);
+ if(tconfig) {
+ config->setName(QString("Taisync Link"));
+ }
+ }
+ break;
+#endif
#ifdef QGC_ENABLE_BLUETOOTH
case LinkConfiguration::TypeBluetooth: {
BluetoothConfiguration* tconfig = dynamic_cast(config);
@@ -849,12 +859,10 @@ void LinkManager::_fixUnnamed(LinkConfiguration* config)
#endif
#ifdef QT_DEBUG
case LinkConfiguration::TypeMock:
- config->setName(
- QString("Mock Link"));
+ config->setName(QString("Mock Link"));
break;
#endif
case LinkConfiguration::TypeLast:
- default:
break;
}
}
@@ -896,9 +904,8 @@ bool LinkManager::isBluetoothAvailable(void)
#ifndef NO_SERIAL_LINK
void LinkManager::_activeLinkCheck(void)
{
- SerialLink* link = NULL;
+ SerialLink* link = nullptr;
bool found = false;
-
if (_activeLinkCheckList.count() != 0) {
link = _activeLinkCheckList.takeFirst();
if (containsLink(link) && link->isConnected()) {
@@ -912,14 +919,12 @@ void LinkManager::_activeLinkCheck(void)
}
}
} else {
- link = NULL;
+ link = nullptr;
}
}
-
if (_activeLinkCheckList.count() == 0) {
_activeLinkCheckTimer.stop();
}
-
if (!found && link) {
// See if we can get an NSH prompt on this link
bool foundNSHPrompt = false;
@@ -931,10 +936,10 @@ void LinkManager::_activeLinkCheck(void)
foundNSHPrompt = true;
}
}
-
- qgcApp()->showMessage(foundNSHPrompt ?
- tr("Please check to make sure you have an SD Card inserted in your Vehicle and try again.") :
- tr("Your Vehicle is not responding. If this continues, shutdown %1, restart the Vehicle letting it boot completely, then start %1.").arg(qgcApp()->applicationName()));
+ qgcApp()->showMessage(
+ foundNSHPrompt ?
+ tr("Please check to make sure you have an SD Card inserted in your Vehicle and try again.") :
+ tr("Your Vehicle is not responding. If this continues, shutdown %1, restart the Vehicle letting it boot completely, then start %1.").arg(qgcApp()->applicationName()));
}
}
#endif
@@ -959,32 +964,27 @@ SharedLinkConfigurationPointer LinkManager::addConfiguration(LinkConfiguration*
void LinkManager::_removeConfiguration(LinkConfiguration* config)
{
_qmlConfigurations.removeOne(config);
-
for (int i=0; i<_sharedConfigurations.count(); i++) {
if (_sharedConfigurations[i].data() == config) {
_sharedConfigurations.removeAt(i);
return;
}
}
-
qWarning() << "LinkManager::_removeConfiguration called with unknown config";
}
QList LinkManager::links(void)
{
QList rawLinks;
-
for (int i=0; i<_sharedLinks.count(); i++) {
rawLinks.append(_sharedLinks[i].data());
}
-
return rawLinks;
}
void LinkManager::startAutoConnectedLinks(void)
{
SharedLinkConfigurationPointer conf;
-
for(int i = 0; i < _sharedConfigurations.count(); i++) {
conf = _sharedConfigurations[i];
if (conf->isAutoConnect())
@@ -995,7 +995,7 @@ void LinkManager::startAutoConnectedLinks(void)
int LinkManager::_reserveMavlinkChannel(void)
{
// Find a mavlink channel to use for this link, Channel 0 is reserved for internal use.
- for (int mavlinkChannel=1; mavlinkChannel<32; mavlinkChannel++) {
+ for (uint8_t mavlinkChannel = 1; mavlinkChannel < 32; mavlinkChannel++) {
if (!(_mavlinkChannelsUsedBitMask & 1 << mavlinkChannel)) {
mavlink_reset_channel_status(mavlinkChannel);
// Start the channel on Mav 1 protocol
@@ -1005,7 +1005,6 @@ int LinkManager::_reserveMavlinkChannel(void)
return mavlinkChannel;
}
}
-
return 0; // All channels reserved
}
diff --git a/src/comm/TaisyncLink.cc b/src/comm/TaisyncLink.cc
new file mode 100644
index 0000000000000000000000000000000000000000..c5544afb0b7373291fc471e3877d41a22ff7fbfe
--- /dev/null
+++ b/src/comm/TaisyncLink.cc
@@ -0,0 +1,286 @@
+/****************************************************************************
+ *
+ * (c) 2009-2016 QGROUNDCONTROL PROJECT
+ *
+ * QGroundControl is licensed according to the terms in the file
+ * COPYING.md in the root of the source code directory.
+ *
+ ****************************************************************************/
+
+#include
+#include
+
+#include "TaisyncLink.h"
+#include "QGC.h"
+#include "QGCApplication.h"
+#include "SettingsManager.h"
+#include "VideoSettings.h"
+
+#include "TaisyncTelemetry.h"
+#include "TaisyncSettings.h"
+#include "TaisyncVideoReceiver.h"
+
+static const char* kEnableVideo = "enableVideo";
+
+//-----------------------------------------------------------------------------
+TaisyncLink::TaisyncLink(SharedLinkConfigurationPointer& config)
+ : LinkInterface(config)
+ , _taiConfig(qobject_cast(config.data()))
+{
+ if (!_taiConfig) {
+ qWarning() << "Internal error";
+ }
+ moveToThread(this);
+}
+
+//-----------------------------------------------------------------------------
+TaisyncLink::~TaisyncLink()
+{
+ _disconnect();
+ // Tell the thread to exit
+ _running = false;
+ quit();
+ // Wait for it to exit
+ wait();
+ this->deleteLater();
+}
+
+//-----------------------------------------------------------------------------
+void
+TaisyncLink::run()
+{
+ if(_hardwareConnect()) {
+ exec();
+ }
+ _hardwareDisconnect();
+}
+
+//-----------------------------------------------------------------------------
+void
+TaisyncLink::_restartConnection()
+{
+ if(this->isConnected())
+ {
+ _disconnect();
+ _connect();
+ }
+}
+
+//-----------------------------------------------------------------------------
+QString
+TaisyncLink::getName() const
+{
+ return _taiConfig->name();
+}
+
+//-----------------------------------------------------------------------------
+void
+TaisyncLink::_writeBytes(const QByteArray data)
+{
+ if (_taiTelemetery) {
+ _taiTelemetery->writeBytes(data);
+ _logOutputDataRate(static_cast(data.size()), QDateTime::currentMSecsSinceEpoch());
+ }
+}
+
+//-----------------------------------------------------------------------------
+void
+TaisyncLink::_readBytes(QByteArray bytes)
+{
+ emit bytesReceived(this, bytes);
+ _logInputDataRate(static_cast(bytes.size()), QDateTime::currentMSecsSinceEpoch());
+}
+
+//-----------------------------------------------------------------------------
+void
+TaisyncLink::_disconnect()
+{
+ _running = false;
+ quit();
+ wait();
+ if (_taiTelemetery) {
+ _hardwareDisconnect();
+ emit disconnected();
+ }
+ //-- Restore video settings
+ if(!_savedVideoSource.isNull()) {
+ VideoSettings* pVSettings = qgcApp()->toolbox()->settingsManager()->videoSettings();
+ pVSettings->videoSource()->setRawValue(_savedVideoSource);
+ pVSettings->udpPort()->setRawValue(_savedVideoUDP);
+ pVSettings->aspectRatio()->setRawValue(_savedAR);
+ pVSettings->setVisible(_savedVideoState);
+ }
+}
+
+//-----------------------------------------------------------------------------
+bool
+TaisyncLink::_connect(void)
+{
+ if(this->isRunning() || _running) {
+ _running = false;
+ quit();
+ wait();
+ }
+ _running = true;
+ if(_taiConfig->videoEnabled()) {
+ //-- Hide video selection as we will be fixed to Taisync video and set the way we need it.
+ VideoSettings* pVSettings = qgcApp()->toolbox()->settingsManager()->videoSettings();
+ _savedVideoSource = pVSettings->videoSource()->rawValue();
+ _savedVideoUDP = pVSettings->udpPort()->rawValue();
+ _savedAR = pVSettings->aspectRatio()->rawValue();
+ _savedVideoState = pVSettings->visible();
+ pVSettings->setVisible(false);
+ pVSettings->udpPort()->setRawValue(5600);
+ pVSettings->aspectRatio()->setRawValue(1024.0 / 768.0);
+ pVSettings->videoSource()->setRawValue(QString(VideoSettings::videoSourceUDP));
+ }
+ start(NormalPriority);
+ return true;
+}
+
+//-----------------------------------------------------------------------------
+void
+TaisyncLink::_hardwareDisconnect()
+{
+ if (_taiTelemetery) {
+ _taiTelemetery->close();
+ _taiTelemetery->deleteLater();
+ _taiTelemetery = nullptr;
+ }
+ if (_taiSettings) {
+ _taiSettings->close();
+ _taiSettings->deleteLater();
+ _taiSettings = nullptr;
+ }
+#if defined(__ios__) || defined(__android__)
+ if (_taiVideo) {
+ _taiVideo->close();
+ _taiVideo->deleteLater();
+ _taiVideo = nullptr;
+ }
+#endif
+}
+
+//-----------------------------------------------------------------------------
+bool
+TaisyncLink::_hardwareConnect()
+{
+ _hardwareDisconnect();
+ _taiTelemetery = new TaisyncTelemetry(this);
+ QObject::connect(_taiTelemetery, &TaisyncTelemetry::bytesReady, this, &TaisyncLink::_readBytes);
+ _taiTelemetery->start();
+ _taiSettings = new TaisyncSettings(this);
+ _taiSettings->start();
+#if defined(__ios__) || defined(__android__)
+ if(_taiConfig->videoEnabled()) {
+ _taiVideo = new TaisyncVideoReceiver(this);
+ _taiVideo->start();
+ }
+#endif
+ return true;
+}
+
+//-----------------------------------------------------------------------------
+bool
+TaisyncLink::isConnected() const
+{
+ return _taiTelemetery != nullptr;
+}
+
+//-----------------------------------------------------------------------------
+qint64
+TaisyncLink::getConnectionSpeed() const
+{
+ return 57600; // 57.6 Kbit
+}
+
+//-----------------------------------------------------------------------------
+qint64
+TaisyncLink::getCurrentInDataRate() const
+{
+ return 0;
+}
+
+//-----------------------------------------------------------------------------
+qint64
+TaisyncLink::getCurrentOutDataRate() const
+{
+ return 0;
+}
+
+//--------------------------------------------------------------------------
+//-- TaisyncConfiguration
+
+//--------------------------------------------------------------------------
+TaisyncConfiguration::TaisyncConfiguration(const QString& name) : LinkConfiguration(name)
+{
+}
+
+//--------------------------------------------------------------------------
+TaisyncConfiguration::TaisyncConfiguration(TaisyncConfiguration* source) : LinkConfiguration(source)
+{
+ _copyFrom(source);
+}
+
+//--------------------------------------------------------------------------
+TaisyncConfiguration::~TaisyncConfiguration()
+{
+}
+
+//--------------------------------------------------------------------------
+void
+TaisyncConfiguration::copyFrom(LinkConfiguration *source)
+{
+ LinkConfiguration::copyFrom(source);
+ _copyFrom(source);
+}
+
+//--------------------------------------------------------------------------
+void
+TaisyncConfiguration::_copyFrom(LinkConfiguration *source)
+{
+ TaisyncConfiguration* usource = dynamic_cast(source);
+ if (usource) {
+ _enableVideo = usource->videoEnabled();
+ } else {
+ qWarning() << "Internal error";
+ }
+}
+
+//--------------------------------------------------------------------------
+void
+TaisyncConfiguration::setVideoEnabled(bool enable)
+{
+ _enableVideo = enable;
+ emit enableVideoChanged();
+}
+
+//--------------------------------------------------------------------------
+void
+TaisyncConfiguration::saveSettings(QSettings& settings, const QString& root)
+{
+ settings.beginGroup(root);
+ settings.setValue(kEnableVideo, _enableVideo);
+ settings.endGroup();
+}
+
+//--------------------------------------------------------------------------
+void
+TaisyncConfiguration::loadSettings(QSettings& settings, const QString& root)
+{
+ settings.beginGroup(root);
+ _enableVideo = settings.value(kEnableVideo, true).toBool();
+ settings.endGroup();
+}
+
+//--------------------------------------------------------------------------
+void
+TaisyncConfiguration::updateSettings()
+{
+ if(_link) {
+ TaisyncLink* ulink = dynamic_cast(_link);
+ if(ulink) {
+ ulink->_restartConnection();
+ }
+ }
+}
diff --git a/src/comm/TaisyncLink.h b/src/comm/TaisyncLink.h
new file mode 100644
index 0000000000000000000000000000000000000000..77b3471d32726a8f11bc135c3d99fc76f1e5a8e4
--- /dev/null
+++ b/src/comm/TaisyncLink.h
@@ -0,0 +1,128 @@
+/****************************************************************************
+ *
+ * (c) 2009-2018 QGROUNDCONTROL PROJECT
+ *
+ * QGroundControl is licensed according to the terms in the file
+ * COPYING.md in the root of the source code directory.
+ *
+ ****************************************************************************/
+
+
+#pragma once
+
+#include
+#include
+#include
+#include
+#include
+#include
+#include
+#include
+#include
+#include
+#include
+
+#include "QGCConfig.h"
+#include "LinkManager.h"
+
+class TaisyncTelemetry;
+class TaisyncSettings;
+#if defined(__ios__) || defined(__android__)
+class TaisyncVideoReceiver;
+#endif
+
+//-----------------------------------------------------------------------------
+class TaisyncConfiguration : public LinkConfiguration
+{
+ Q_OBJECT
+public:
+
+ Q_PROPERTY(bool videoEnabled READ videoEnabled WRITE setVideoEnabled NOTIFY enableVideoChanged)
+
+ TaisyncConfiguration (const QString& name);
+ TaisyncConfiguration (TaisyncConfiguration* source);
+ ~TaisyncConfiguration ();
+
+ bool videoEnabled () { return _enableVideo; }
+
+ void setVideoEnabled (bool enable);
+
+ /// From LinkConfiguration
+ LinkType type () { return LinkConfiguration::TypeTaisync; }
+ void copyFrom (LinkConfiguration* source);
+ void loadSettings (QSettings& settings, const QString& root);
+ void saveSettings (QSettings& settings, const QString& root);
+ void updateSettings ();
+ bool isAutoConnectAllowed() { return true; }
+ bool isHighLatencyAllowed() { return false; }
+ QString settingsURL () { return "TaisyncSettings.qml"; }
+ QString settingsTitle () { return tr("Taisync Link Settings"); }
+
+signals:
+ void enableVideoChanged ();
+
+private:
+ void _copyFrom (LinkConfiguration *source);
+
+private:
+ bool _enableVideo = true;
+};
+
+//-----------------------------------------------------------------------------
+class TaisyncLink : public LinkInterface
+{
+ Q_OBJECT
+
+ friend class TaisyncConfiguration;
+ friend class LinkManager;
+
+public:
+ void requestReset () override { }
+ bool isConnected () const override;
+ QString getName () const override;
+
+ // Extensive statistics for scientific purposes
+ qint64 getConnectionSpeed () const override;
+ qint64 getCurrentInDataRate () const;
+ qint64 getCurrentOutDataRate () const;
+
+ // Thread
+ void run () override;
+
+ // These are left unimplemented in order to cause linker errors which indicate incorrect usage of
+ // connect/disconnect on link directly. All connect/disconnect calls should be made through LinkManager.
+ bool connect (void);
+ bool disconnect (void);
+
+private slots:
+ void _writeBytes (const QByteArray data) override;
+ void _readBytes (QByteArray bytes);
+
+private:
+ // Links are only created/destroyed by LinkManager so constructor/destructor is not public
+ TaisyncLink (SharedLinkConfigurationPointer& config);
+ ~TaisyncLink () override;
+
+ // From LinkInterface
+ bool _connect () override;
+ void _disconnect () override;
+
+ bool _hardwareConnect ();
+ void _hardwareDisconnect ();
+ void _restartConnection ();
+ void _writeDataGram (const QByteArray data);
+
+private:
+ bool _running = false;
+ TaisyncConfiguration* _taiConfig = nullptr;
+ TaisyncTelemetry* _taiTelemetery = nullptr;
+ TaisyncSettings* _taiSettings = nullptr;
+#if defined(__ios__) || defined(__android__)
+ TaisyncVideoReceiver* _taiVideo = nullptr;
+#endif
+ bool _savedVideoState = true;
+ QVariant _savedVideoSource;
+ QVariant _savedVideoUDP;
+ QVariant _savedAR;
+};
+