diff --git a/qgroundcontrol.pro b/qgroundcontrol.pro index f3d320104856d95c22c7254e0b1e1889c01e1d58..05b6447f69eb40a1a7dd2d63068ba470483fb72a 100644 --- a/qgroundcontrol.pro +++ b/qgroundcontrol.pro @@ -1113,18 +1113,24 @@ contains (DEFINES, QGC_GST_TAISYNC_ENABLED) { src/Taisync HEADERS += \ - src/comm/TaisyncLink.h \ + src/Taisync/TaisyncManager.h \ src/Taisync/TaisyncHandler.h \ src/Taisync/TaisyncSettings.h \ - src/Taisync/TaisyncTelemetry.h \ - src/Taisync/TaisyncVideoReceiver.h \ SOURCES += \ - src/comm/TaisyncLink.cc \ + src/Taisync/TaisyncManager.cc \ src/Taisync/TaisyncHandler.cc \ src/Taisync/TaisyncSettings.cc \ - src/Taisync/TaisyncTelemetry.cc \ - src/Taisync/TaisyncVideoReceiver.cc \ + + iOSBuild | AndroidBuild { + HEADERS += \ + src/Taisync/TaisyncTelemetry.h \ + src/Taisync/TaisyncVideoReceiver.h \ + + SOURCES += \ + src/Taisync/TaisyncTelemetry.cc \ + src/Taisync/TaisyncVideoReceiver.cc \ + } } #------------------------------------------------------------------------------------- diff --git a/src/QGCToolbox.cc b/src/QGCToolbox.cc index 386b8139f6d08ece4c7c5f3e48556e17836ac9da..4ccde180dfb2b1106f1f1ea5f4424c37cb5a4ca0 100644 --- a/src/QGCToolbox.cc +++ b/src/QGCToolbox.cc @@ -35,64 +35,48 @@ #else #include "AirspaceManager.h" #endif +#if defined(QGC_GST_TAISYNC_ENABLED) +#include "TaisyncManager.h" +#endif #if defined(QGC_CUSTOM_BUILD) #include CUSTOMHEADER #endif QGCToolbox::QGCToolbox(QGCApplication* app) - : _audioOutput (NULL) - , _factSystem (NULL) - , _firmwarePluginManager(NULL) -#ifndef __mobile__ - , _gpsManager (NULL) -#endif - , _imageProvider (NULL) - , _joystickManager (NULL) - , _linkManager (NULL) - , _mavlinkProtocol (NULL) - , _missionCommandTree (NULL) - , _multiVehicleManager (NULL) - , _mapEngineManager (NULL) - , _uasMessageHandler (NULL) - , _followMe (NULL) - , _qgcPositionManager (NULL) - , _videoManager (NULL) - , _mavlinkLogManager (NULL) - , _corePlugin (NULL) - , _settingsManager (NULL) - , _airspaceManager (NULL) { // SettingsManager must be first so settings are available to any subsequent tools - _settingsManager = new SettingsManager(app, this); - + _settingsManager = new SettingsManager (app, this); //-- Scan and load plugins _scanAndLoadPlugins(app); - _audioOutput = new AudioOutput (app, this); - _factSystem = new FactSystem (app, this); - _firmwarePluginManager = new FirmwarePluginManager (app, this); + _audioOutput = new AudioOutput (app, this); + _factSystem = new FactSystem (app, this); + _firmwarePluginManager = new FirmwarePluginManager (app, this); #ifndef __mobile__ - _gpsManager = new GPSManager (app, this); + _gpsManager = new GPSManager (app, this); #endif - _imageProvider = new QGCImageProvider (app, this); - _joystickManager = new JoystickManager (app, this); - _linkManager = new LinkManager (app, this); - _mavlinkProtocol = new MAVLinkProtocol (app, this); - _missionCommandTree = new MissionCommandTree (app, this); - _multiVehicleManager = new MultiVehicleManager (app, this); - _mapEngineManager = new QGCMapEngineManager (app, this); - _uasMessageHandler = new UASMessageHandler (app, this); - _qgcPositionManager = new QGCPositionManager (app, this); - _followMe = new FollowMe (app, this); - _videoManager = new VideoManager (app, this); - _mavlinkLogManager = new MAVLinkLogManager (app, this); + _imageProvider = new QGCImageProvider (app, this); + _joystickManager = new JoystickManager (app, this); + _linkManager = new LinkManager (app, this); + _mavlinkProtocol = new MAVLinkProtocol (app, this); + _missionCommandTree = new MissionCommandTree (app, this); + _multiVehicleManager = new MultiVehicleManager (app, this); + _mapEngineManager = new QGCMapEngineManager (app, this); + _uasMessageHandler = new UASMessageHandler (app, this); + _qgcPositionManager = new QGCPositionManager (app, this); + _followMe = new FollowMe (app, this); + _videoManager = new VideoManager (app, this); + _mavlinkLogManager = new MAVLinkLogManager (app, this); //-- Airmap Manager //-- This should be "pluggable" so an arbitrary AirSpace manager can be used //-- For now, we instantiate the one and only AirMap provider #if defined(QGC_AIRMAP_ENABLED) - _airspaceManager = new AirMapManager (app, this); + _airspaceManager = new AirMapManager (app, this); #else - _airspaceManager = new AirspaceManager (app, this); + _airspaceManager = new AirspaceManager (app, this); +#endif +#if defined(QGC_GST_TAISYNC_ENABLED) + _taisyncManager = new TaisyncManager (app, this); #endif } @@ -100,7 +84,6 @@ void QGCToolbox::setChildToolboxes(void) { // SettingsManager must be first so settings are available to any subsequent tools _settingsManager->setToolbox(this); - _corePlugin->setToolbox(this); _audioOutput->setToolbox(this); _factSystem->setToolbox(this); @@ -121,6 +104,9 @@ void QGCToolbox::setChildToolboxes(void) _videoManager->setToolbox(this); _mavlinkLogManager->setToolbox(this); _airspaceManager->setToolbox(this); +#if defined(QGC_GST_TAISYNC_ENABLED) + _taisyncManager->setToolbox(this); +#endif } void QGCToolbox::_scanAndLoadPlugins(QGCApplication* app) @@ -139,7 +125,7 @@ void QGCToolbox::_scanAndLoadPlugins(QGCApplication* app) QGCTool::QGCTool(QGCApplication* app, QGCToolbox* toolbox) : QObject(toolbox) , _app(app) - , _toolbox(NULL) + , _toolbox(nullptr) { } diff --git a/src/QGCToolbox.h b/src/QGCToolbox.h index 3c5476fbcdd073006c78ae7f277f8a5dbb876aba..8df56423ea3e283c7e153b233a968ef99a94c2e6 100644 --- a/src/QGCToolbox.h +++ b/src/QGCToolbox.h @@ -33,6 +33,9 @@ class MAVLinkLogManager; class QGCCorePlugin; class SettingsManager; class AirspaceManager; +#if defined(QGC_GST_TAISYNC_ENABLED) +class TaisyncManager; +#endif /// This is used to manage all of our top level services/tools class QGCToolbox : public QObject { @@ -41,25 +44,28 @@ class QGCToolbox : public QObject { public: QGCToolbox(QGCApplication* app); - FirmwarePluginManager* firmwarePluginManager(void) { return _firmwarePluginManager; } - AudioOutput* audioOutput(void) { return _audioOutput; } - JoystickManager* joystickManager(void) { return _joystickManager; } - LinkManager* linkManager(void) { return _linkManager; } - MAVLinkProtocol* mavlinkProtocol(void) { return _mavlinkProtocol; } - MissionCommandTree* missionCommandTree(void) { return _missionCommandTree; } - MultiVehicleManager* multiVehicleManager(void) { return _multiVehicleManager; } - QGCMapEngineManager* mapEngineManager(void) { return _mapEngineManager; } - QGCImageProvider* imageProvider() { return _imageProvider; } - UASMessageHandler* uasMessageHandler(void) { return _uasMessageHandler; } - FollowMe* followMe(void) { return _followMe; } - QGCPositionManager* qgcPositionManager(void) { return _qgcPositionManager; } - VideoManager* videoManager(void) { return _videoManager; } - MAVLinkLogManager* mavlinkLogManager(void) { return _mavlinkLogManager; } - QGCCorePlugin* corePlugin(void) { return _corePlugin; } - SettingsManager* settingsManager(void) { return _settingsManager; } - AirspaceManager* airspaceManager(void) { return _airspaceManager; } + FirmwarePluginManager* firmwarePluginManager () { return _firmwarePluginManager; } + AudioOutput* audioOutput () { return _audioOutput; } + JoystickManager* joystickManager () { return _joystickManager; } + LinkManager* linkManager () { return _linkManager; } + MAVLinkProtocol* mavlinkProtocol () { return _mavlinkProtocol; } + MissionCommandTree* missionCommandTree () { return _missionCommandTree; } + MultiVehicleManager* multiVehicleManager () { return _multiVehicleManager; } + QGCMapEngineManager* mapEngineManager () { return _mapEngineManager; } + QGCImageProvider* imageProvider () { return _imageProvider; } + UASMessageHandler* uasMessageHandler () { return _uasMessageHandler; } + FollowMe* followMe () { return _followMe; } + QGCPositionManager* qgcPositionManager () { return _qgcPositionManager; } + VideoManager* videoManager () { return _videoManager; } + MAVLinkLogManager* mavlinkLogManager () { return _mavlinkLogManager; } + QGCCorePlugin* corePlugin () { return _corePlugin; } + SettingsManager* settingsManager () { return _settingsManager; } + AirspaceManager* airspaceManager () { return _airspaceManager; } #ifndef __mobile__ - GPSManager* gpsManager(void) { return _gpsManager; } + GPSManager* gpsManager () { return _gpsManager; } +#endif +#if defined(QGC_GST_TAISYNC_ENABLED) + TaisyncManager* taisyncManager () { return _taisyncManager; } #endif private: @@ -67,27 +73,30 @@ private: void _scanAndLoadPlugins(QGCApplication *app); - AudioOutput* _audioOutput; - FactSystem* _factSystem; - FirmwarePluginManager* _firmwarePluginManager; + AudioOutput* _audioOutput = nullptr; + FactSystem* _factSystem = nullptr; + FirmwarePluginManager* _firmwarePluginManager = nullptr; #ifndef __mobile__ - GPSManager* _gpsManager; + GPSManager* _gpsManager = nullptr; +#endif + QGCImageProvider* _imageProvider = nullptr; + JoystickManager* _joystickManager = nullptr; + LinkManager* _linkManager = nullptr; + MAVLinkProtocol* _mavlinkProtocol = nullptr; + MissionCommandTree* _missionCommandTree = nullptr; + MultiVehicleManager* _multiVehicleManager = nullptr; + QGCMapEngineManager* _mapEngineManager = nullptr; + UASMessageHandler* _uasMessageHandler = nullptr; + FollowMe* _followMe = nullptr; + QGCPositionManager* _qgcPositionManager = nullptr; + VideoManager* _videoManager = nullptr; + MAVLinkLogManager* _mavlinkLogManager = nullptr; + QGCCorePlugin* _corePlugin = nullptr; + SettingsManager* _settingsManager = nullptr; + AirspaceManager* _airspaceManager = nullptr; +#if defined(QGC_GST_TAISYNC_ENABLED) + TaisyncManager* _taisyncManager = nullptr; #endif - QGCImageProvider* _imageProvider; - JoystickManager* _joystickManager; - LinkManager* _linkManager; - MAVLinkProtocol* _mavlinkProtocol; - MissionCommandTree* _missionCommandTree; - MultiVehicleManager* _multiVehicleManager; - QGCMapEngineManager* _mapEngineManager; - UASMessageHandler* _uasMessageHandler; - FollowMe* _followMe; - QGCPositionManager* _qgcPositionManager; - VideoManager* _videoManager; - MAVLinkLogManager* _mavlinkLogManager; - QGCCorePlugin* _corePlugin; - SettingsManager* _settingsManager; - AirspaceManager* _airspaceManager; friend class QGCApplication; }; diff --git a/src/QmlControls/QGroundControlQmlGlobal.cc b/src/QmlControls/QGroundControlQmlGlobal.cc index 25f13569a52ddb835d035791accbad1a46b90dbb..4d4638680e9ecc71c79774bf59189e1eccb2a59c 100644 --- a/src/QmlControls/QGroundControlQmlGlobal.cc +++ b/src/QmlControls/QGroundControlQmlGlobal.cc @@ -29,23 +29,9 @@ double QGroundControlQmlGlobal::_zoom = 2; QGroundControlQmlGlobal::QGroundControlQmlGlobal(QGCApplication* app, QGCToolbox* toolbox) : QGCTool (app, toolbox) - , _flightMapInitialZoom (17.0) - , _linkManager (NULL) - , _multiVehicleManager (NULL) - , _mapEngineManager (NULL) - , _qgcPositionManager (NULL) - , _missionCommandTree (NULL) - , _videoManager (NULL) - , _mavlinkLogManager (NULL) - , _corePlugin (NULL) - , _firmwarePluginManager(NULL) - , _settingsManager (NULL) - , _gpsRtkFactGroup (nullptr) - , _airspaceManager (NULL) - , _skipSetupPage (false) { // We clear the parent on this object since we run into shutdown problems caused by hybrid qml app. Instead we let it leak on shutdown. - setParent(NULL); + setParent(nullptr); // Load last coordinates and zoom from config file QSettings settings; settings.beginGroup(_flightMapPositionSettingsGroup); @@ -80,6 +66,9 @@ void QGroundControlQmlGlobal::setToolbox(QGCToolbox* toolbox) _settingsManager = toolbox->settingsManager(); _gpsRtkFactGroup = qgcApp()->gpsRtkFactGroup(); _airspaceManager = toolbox->airspaceManager(); +#if defined(QGC_AIRMAP_ENABLED) + _taisyncManager = toolbox->taisyncManager(); +#endif } void QGroundControlQmlGlobal::saveGlobalSetting (const QString& key, const QString& value) diff --git a/src/QmlControls/QGroundControlQmlGlobal.h b/src/QmlControls/QGroundControlQmlGlobal.h index 22a64110fd48af2a4062d5155ad3889289658839..c4b29999833128ec9ee53908083d480221281675 100644 --- a/src/QmlControls/QGroundControlQmlGlobal.h +++ b/src/QmlControls/QGroundControlQmlGlobal.h @@ -23,6 +23,11 @@ #include "QGCLoggingCategory.h" #include "AppSettings.h" #include "AirspaceManager.h" +#if defined(QGC_GST_TAISYNC_ENABLED) +#include "TaisyncManager.h" +#else +class TaisyncManager; +#endif #ifdef QT_DEBUG #include "MockLink.h" @@ -52,6 +57,8 @@ public: Q_PROPERTY(FactGroup* gpsRtk READ gpsRtkFactGroup CONSTANT) Q_PROPERTY(AirspaceManager* airspaceManager READ airspaceManager CONSTANT) Q_PROPERTY(bool airmapSupported READ airmapSupported CONSTANT) + Q_PROPERTY(TaisyncManager* taisyncManager READ taisyncManager CONSTANT) + Q_PROPERTY(bool taisyncSupported READ taisyncSupported CONSTANT) Q_PROPERTY(int supportedFirmwareCount READ supportedFirmwareCount CONSTANT) @@ -145,6 +152,13 @@ public: static QGeoCoordinate flightMapPosition () { return _coord; } static double flightMapZoom () { return _zoom; } + TaisyncManager* taisyncManager () { return _taisyncManager; } +#if defined(QGC_GST_TAISYNC_ENABLED) + bool taisyncSupported () { return true; } +#else + bool taisyncSupported () { return false; } +#endif + qreal zOrderTopMost () { return 1000; } qreal zOrderWidgets () { return 100; } qreal zOrderMapItems () { return 50; } @@ -189,21 +203,22 @@ signals: void skipSetupPageChanged (); private: - double _flightMapInitialZoom; - LinkManager* _linkManager; - MultiVehicleManager* _multiVehicleManager; - QGCMapEngineManager* _mapEngineManager; - QGCPositionManager* _qgcPositionManager; - MissionCommandTree* _missionCommandTree; - VideoManager* _videoManager; - MAVLinkLogManager* _mavlinkLogManager; - QGCCorePlugin* _corePlugin; - FirmwarePluginManager* _firmwarePluginManager; - SettingsManager* _settingsManager; - FactGroup* _gpsRtkFactGroup; - AirspaceManager* _airspaceManager; - - bool _skipSetupPage; + double _flightMapInitialZoom = 17.0; + LinkManager* _linkManager = nullptr; + MultiVehicleManager* _multiVehicleManager = nullptr; + QGCMapEngineManager* _mapEngineManager = nullptr; + QGCPositionManager* _qgcPositionManager = nullptr; + MissionCommandTree* _missionCommandTree = nullptr; + VideoManager* _videoManager = nullptr; + MAVLinkLogManager* _mavlinkLogManager = nullptr; + QGCCorePlugin* _corePlugin = nullptr; + FirmwarePluginManager* _firmwarePluginManager = nullptr; + SettingsManager* _settingsManager = nullptr; + FactGroup* _gpsRtkFactGroup = nullptr; + AirspaceManager* _airspaceManager = nullptr; + TaisyncManager* _taisyncManager = nullptr; + + bool _skipSetupPage = false; static const char* _flightMapPositionSettingsGroup; static const char* _flightMapPositionLatitudeSettingsKey; diff --git a/src/Settings/App.SettingsGroup.json b/src/Settings/App.SettingsGroup.json index 928ca916813562c9230d61cd724948418a88bccf..780618082daf7bfd59e4c5ad4c16405013ccc69b 100644 --- a/src/Settings/App.SettingsGroup.json +++ b/src/Settings/App.SettingsGroup.json @@ -205,5 +205,19 @@ "shortDescription": "Request start of MAVLink telemetry streams (ArduPilot only)", "type": "bool", "defaultValue": true +}, +{ + "name": "enableTaisync", + "shortDescription": "Enable Taisync Module Support", + "longDescription": "Enable Taisync Module Support", + "type": "bool", + "defaultValue": true +}, +{ + "name": "enableTaisyncVideo", + "shortDescription": "Enable Taisync Video Support", + "longDescription": "Enable Taisync Video Support", + "type": "bool", + "defaultValue": true } ] diff --git a/src/Settings/AppSettings.cc b/src/Settings/AppSettings.cc index f8d0057382d79232b6a3712feac9c092f014fd1b..abfdfb4a6196939422ebb0797653fcfc43606112 100644 --- a/src/Settings/AppSettings.cc +++ b/src/Settings/AppSettings.cc @@ -85,6 +85,8 @@ DECLARE_SETTINGSFACT(AppSettings, defaultFirmwareType) DECLARE_SETTINGSFACT(AppSettings, gstDebugLevel) DECLARE_SETTINGSFACT(AppSettings, followTarget) DECLARE_SETTINGSFACT(AppSettings, apmStartMavlinkStreams) +DECLARE_SETTINGSFACT(AppSettings, enableTaisync) +DECLARE_SETTINGSFACT(AppSettings, enableTaisyncVideo) DECLARE_SETTINGSFACT_NO_FUNC(AppSettings, indoorPalette) { diff --git a/src/Settings/AppSettings.h b/src/Settings/AppSettings.h index 46e9a61e3bac4281c411240e7a3edb3c27ee63ae..37784b9be964c3a7e81a1363490620405c4bcede 100644 --- a/src/Settings/AppSettings.h +++ b/src/Settings/AppSettings.h @@ -14,7 +14,7 @@ class AppSettings : public SettingsGroup { Q_OBJECT - + public: AppSettings(QObject* parent = nullptr); @@ -43,6 +43,8 @@ public: DEFINE_SETTINGFACT(defaultFirmwareType) DEFINE_SETTINGFACT(gstDebugLevel) DEFINE_SETTINGFACT(followTarget) + DEFINE_SETTINGFACT(enableTaisync) + DEFINE_SETTINGFACT(enableTaisyncVideo) // Although this is a global setting it only affects ArduPilot vehicle since PX4 automatically starts the stream from the vehicle side DEFINE_SETTINGFACT(apmStartMavlinkStreams) diff --git a/src/Settings/AutoConnect.SettingsGroup.json b/src/Settings/AutoConnect.SettingsGroup.json index 7dfdf23807aab92658c0a438d3a796369fa2ff8e..ce5c7ca154454be9dd39e9f8bdc2e3a8d450f260 100644 --- a/src/Settings/AutoConnect.SettingsGroup.json +++ b/src/Settings/AutoConnect.SettingsGroup.json @@ -72,12 +72,5 @@ "shortDescription": "UDP target host port for autoconnect", "type": "uint32", "defaultValue": 14550 -}, -{ - "name": "autoConnectTaisyncUSB", - "shortDescription": "Automatically connect to a Taisync Ground Module", - "longDescription": "If this option is enabled GroundControl will automatically connect to a Taisync Ground Module which is connected via USB.", - "type": "bool", - "defaultValue": false } ] diff --git a/src/Settings/AutoConnectSettings.cc b/src/Settings/AutoConnectSettings.cc index 39dfe481624a993db2fa6705fdc17441a96371d3..23c576acacf4bbd9b1b18db9917144ac10ad66f1 100644 --- a/src/Settings/AutoConnectSettings.cc +++ b/src/Settings/AutoConnectSettings.cc @@ -23,7 +23,6 @@ DECLARE_SETTINGSFACT(AutoConnectSettings, autoConnectUDP) DECLARE_SETTINGSFACT(AutoConnectSettings, udpListenPort) DECLARE_SETTINGSFACT(AutoConnectSettings, udpTargetHostIP) DECLARE_SETTINGSFACT(AutoConnectSettings, udpTargetHostPort) -DECLARE_SETTINGSFACT(AutoConnectSettings, autoconnectTaisyncUSB) DECLARE_SETTINGSFACT_NO_FUNC(AutoConnectSettings, autoConnectPixhawk) { diff --git a/src/Settings/AutoConnectSettings.h b/src/Settings/AutoConnectSettings.h index 24fa0efd0e9e82ee71dc11da17ad15ead9c85a24..9f96d38ff0fb10db1ac78f5e1370c0832a623f5a 100644 --- a/src/Settings/AutoConnectSettings.h +++ b/src/Settings/AutoConnectSettings.h @@ -14,7 +14,7 @@ class AutoConnectSettings : public SettingsGroup { Q_OBJECT - + public: AutoConnectSettings(QObject* parent = nullptr); @@ -31,6 +31,5 @@ public: DEFINE_SETTINGFACT(udpListenPort) DEFINE_SETTINGFACT(udpTargetHostIP) DEFINE_SETTINGFACT(udpTargetHostPort) - DEFINE_SETTINGFACT(autoconnectTaisyncUSB) }; diff --git a/src/Taisync/TaisyncHandler.cc b/src/Taisync/TaisyncHandler.cc index e161215e1642f9943aed76a2743e1d4636c37fe0..d5587beecc6e9f91f7afb01234ee6bee4309bc81 100644 --- a/src/Taisync/TaisyncHandler.cc +++ b/src/Taisync/TaisyncHandler.cc @@ -13,7 +13,8 @@ #include "VideoManager.h" -QGC_LOGGING_CATEGORY(TaisyncLog, "TaisyncLog") +QGC_LOGGING_CATEGORY(TaisyncLog, "TaisyncLog") +QGC_LOGGING_CATEGORY(TaisyncVerbose, "TaisyncVerbose") //----------------------------------------------------------------------------- TaisyncHandler::TaisyncHandler(QObject* parent) @@ -31,8 +32,8 @@ TaisyncHandler::~TaisyncHandler() void TaisyncHandler::close() { - qCDebug(TaisyncLog) << "Close Taisync TCP"; if(_tcpSocket) { + qCDebug(TaisyncLog) << "Close Taisync TCP"; _tcpSocket->close(); _tcpSocket->deleteLater(); _tcpSocket = nullptr; @@ -40,13 +41,28 @@ TaisyncHandler::close() } //----------------------------------------------------------------------------- -void -TaisyncHandler::_start(uint16_t port) +bool +TaisyncHandler::_start(uint16_t port, QHostAddress addr) { - 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); + close(); + _serverMode = addr == QHostAddress::AnyIPv4; + if(_serverMode) { + qCDebug(TaisyncLog) << "Listen for Taisync TCP on port" << port; + _tcpServer = new QTcpServer(this); + QObject::connect(_tcpServer, &QTcpServer::newConnection, this, &TaisyncHandler::_newConnection); + _tcpServer->listen(QHostAddress::AnyIPv4, port); + } else { + _tcpSocket = new QTcpSocket(); + QObject::connect(_tcpSocket, &QIODevice::readyRead, this, &TaisyncHandler::_readBytes); + qCDebug(TaisyncLog) << "Connecting to" << addr; + _tcpSocket->connectToHost(addr, port); + if (!_tcpSocket->waitForConnected(1000)) { + close(); + return false; + } + emit connected(); + } + return true; } //----------------------------------------------------------------------------- diff --git a/src/Taisync/TaisyncHandler.h b/src/Taisync/TaisyncHandler.h index 5c090681d0fef00419a4d5153df2efdedfe97b13..08aaa2df3d7e0fd2e202f21e97cd5f96d3ce792c 100644 --- a/src/Taisync/TaisyncHandler.h +++ b/src/Taisync/TaisyncHandler.h @@ -14,12 +14,18 @@ #include #include +#if defined(__ios__) || defined(__android__) #define TAISYNC_VIDEO_UDP_PORT 5600 #define TAISYNC_VIDEO_TCP_PORT 8000 #define TAISYNC_SETTINGS_PORT 8200 #define TAISYNC_TELEM_PORT 8400 +#else +#define TAISYNC_SETTINGS_PORT 80 +#define TAISYNC_SETTINGS_TARGET "192.168.1.99" +#endif Q_DECLARE_LOGGING_CATEGORY(TaisyncLog) +Q_DECLARE_LOGGING_CATEGORY(TaisyncVerbose) class TaisyncHandler : public QObject { @@ -28,11 +34,11 @@ public: explicit TaisyncHandler (QObject* parent = nullptr); ~TaisyncHandler (); - virtual void start () = 0; + virtual bool start () = 0; virtual void close (); protected: - virtual void _start (uint16_t port); + virtual bool _start (uint16_t port, QHostAddress addr = QHostAddress::AnyIPv4); protected slots: virtual void _newConnection (); @@ -43,6 +49,7 @@ signals: void connected (); protected: - QTcpServer* _tcpServer = nullptr; - QTcpSocket* _tcpSocket = nullptr; + bool _serverMode = true; + QTcpServer* _tcpServer = nullptr; + QTcpSocket* _tcpSocket = nullptr; }; diff --git a/src/Taisync/TaisyncManager.cc b/src/Taisync/TaisyncManager.cc new file mode 100644 index 0000000000000000000000000000000000000000..35121b46eb0a207d32fe77480475ed055f122d12 --- /dev/null +++ b/src/Taisync/TaisyncManager.cc @@ -0,0 +1,193 @@ +/**************************************************************************** + * + * (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 "TaisyncManager.h" +#include "TaisyncHandler.h" +#include "SettingsManager.h" +#include "QGCApplication.h" +#include "VideoManager.h" + +//----------------------------------------------------------------------------- +TaisyncManager::TaisyncManager(QGCApplication* app, QGCToolbox* toolbox) + : QGCTool(app, toolbox) +{ + connect(&_workTimer, &QTimer::timeout, this, &TaisyncManager::_checkTaisync); + _workTimer.setSingleShot(true); +} + +//----------------------------------------------------------------------------- +TaisyncManager::~TaisyncManager() +{ + if(_taiSettings) { + _taiSettings->close(); + _taiSettings->deleteLater(); + _taiSettings = nullptr; + } +#if defined(__ios__) || defined(__android__) + if (_taiTelemetery) { + _taiTelemetery->close(); + _taiTelemetery->deleteLater(); + _taiTelemetery = nullptr; + } + if (_taiVideo) { + _taiVideo->close(); + _taiVideo->deleteLater(); + _taiVideo = nullptr; + } +#endif +} + +//----------------------------------------------------------------------------- +void +TaisyncManager::setToolbox(QGCToolbox* toolbox) +{ + QGCTool::setToolbox(toolbox); + _taiSettings = new TaisyncSettings(this); + connect(_taiSettings, &TaisyncSettings::updateSettings, this, &TaisyncManager::_updateSettings); + connect(_taiSettings, &TaisyncSettings::connected, this, &TaisyncManager::_connected); + _appSettings = toolbox->settingsManager()->appSettings(); + connect(_appSettings->enableTaisync(), &Fact::rawValueChanged, this, &TaisyncManager::_setEnabled); + connect(_appSettings->enableTaisyncVideo(), &Fact::rawValueChanged, this, &TaisyncManager::_setVideoEnabled); + _setEnabled(); + if(_enabled) { + _setVideoEnabled(); + } +} + +//----------------------------------------------------------------------------- +void +TaisyncManager::_setEnabled() +{ + bool enable = _appSettings->enableTaisync()->rawValue().toBool(); + if(enable) { +#if defined(__ios__) || defined(__android__) + _taiTelemetery = new TaisyncTelemetry(this); + QObject::connect(_taiTelemetery, &TaisyncTelemetry::bytesReady, this, &TaisyncManager::_readTelemBytes); +#endif + _workTimer.start(1000); + } else { +#if defined(__ios__) || defined(__android__) + if (_taiTelemetery) { + _taiTelemetery->close(); + _taiTelemetery->deleteLater(); + _taiTelemetery = nullptr; + } +#endif + _workTimer.stop(); + } + _enabled = enable; +} + +//----------------------------------------------------------------------------- +void +TaisyncManager::_setVideoEnabled() +{ + bool enable = _appSettings->enableTaisyncVideo()->rawValue().toBool(); + if(enable) { + //-- Hide video selection as we will be fixed to Taisync video and set the way we need it. + VideoSettings* pVSettings = qgcApp()->toolbox()->settingsManager()->videoSettings(); + //-- First save current state + _savedVideoSource = pVSettings->videoSource()->rawValue(); + _savedVideoUDP = pVSettings->udpPort()->rawValue(); + _savedAR = pVSettings->aspectRatio()->rawValue(); + _savedVideoState = pVSettings->visible(); + //-- Now set it up the way we need it do be + pVSettings->setVisible(false); + pVSettings->udpPort()->setRawValue(5600); + pVSettings->aspectRatio()->setRawValue(1024.0 / 768.0); + pVSettings->videoSource()->setRawValue(QString(VideoSettings::videoSourceUDP)); +#if defined(__ios__) || defined(__android__) + //-- iOS and Android receive raw h.264 and need a different pipeline + qgcApp()->toolbox()->videoManager()->setIsTaisync(true); + _taiVideo = new TaisyncVideoReceiver(this); + _taiVideo->start(); +#endif + } else { + //-- Restore video settings +#if defined(__ios__) || defined(__android__) + qgcApp()->toolbox()->videoManager()->setIsTaisync(false); + if (_taiVideo) { + _taiVideo->close(); + _taiVideo->deleteLater(); + _taiVideo = nullptr; + } +#endif + if(!_savedVideoSource.isValid()) { + VideoSettings* pVSettings = qgcApp()->toolbox()->settingsManager()->videoSettings(); + pVSettings->videoSource()->setRawValue(_savedVideoSource); + pVSettings->udpPort()->setRawValue(_savedVideoUDP); + pVSettings->aspectRatio()->setRawValue(_savedAR); + pVSettings->setVisible(_savedVideoState); + _savedVideoSource.clear(); + } + } + _enableVideo = enable; +} + +//----------------------------------------------------------------------------- +void +TaisyncManager::_connected() +{ + qCDebug(TaisyncLog) << "Taisync Settings Connected"; + _isConnected = true; + emit connectedChanged(); +} + +//----------------------------------------------------------------------------- +void +TaisyncManager::_checkTaisync() +{ + if(_enabled) { + if(!_isConnected) { + _taiSettings->start(); + } else { + if(++_currReq >= REQ_LAST) { + _currReq = REQ_LINK_STATUS; + } + switch(_currReq) { + case REQ_LINK_STATUS: + _taiSettings->requestLinkStatus(); + break; + case REQ_DEV_INFO: + _taiSettings->requestDevInfo(); + break; + case REQ_FREQ_SCAN: + _taiSettings->requestFreqScan(); + break; + } + } + _workTimer.start(1000); + } +} + +//----------------------------------------------------------------------------- +void +TaisyncManager::_updateSettings(QByteArray jSonData) +{ + qDebug() << jSonData; + QJsonParseError jsonParseError; + QJsonDocument doc = QJsonDocument::fromJson(jSonData, &jsonParseError); + if (jsonParseError.error != QJsonParseError::NoError) { + qWarning() << "Unable to parse Taisync response:" << jsonParseError.errorString() << jsonParseError.offset; + return; + } + QJsonObject jObj = doc.object(); + //-- Link Status? + if(jSonData.contains("\"flight\":")) { + _linkConnected = jObj["flight"].toString("") == "online"; + _linkVidFormat = jObj["videoformat"].toString(_linkVidFormat); + _downlinkRSSI = jObj["radiorssi"].toInt(_downlinkRSSI); + _uplinkRSSI = jObj["hdrssi"].toInt(_uplinkRSSI); + emit linkChanged(); + //-- Device Info? + } else if(jSonData.contains("\"firmwareversion\":")) { + _fwVersion = jObj["firmwareversion"].toString(_fwVersion); + _serialNumber = jObj["sn"].toString(_serialNumber); + } +} diff --git a/src/Taisync/TaisyncManager.h b/src/Taisync/TaisyncManager.h new file mode 100644 index 0000000000000000000000000000000000000000..16066e59856c63f5698212f32e9ade00e976cb88 --- /dev/null +++ b/src/Taisync/TaisyncManager.h @@ -0,0 +1,95 @@ +/**************************************************************************** + * + * (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 "QGCToolbox.h" +#include "QGCLoggingCategory.h" +#include "TaisyncSettings.h" +#if defined(__ios__) || defined(__android__) +#include "TaisyncTelemetry.h" +#include "TaisyncVideoReceiver.h" +#endif + +#include + +class AppSettings; +class QGCApplication; + +//----------------------------------------------------------------------------- +class TaisyncManager : public QGCTool +{ + Q_OBJECT +public: + + Q_PROPERTY(bool connected READ connected NOTIFY connectedChanged) + Q_PROPERTY(bool linkConnected READ linkConnected NOTIFY linkChanged) + Q_PROPERTY(QString linkVidFormat READ linkVidFormat NOTIFY linkChanged) + Q_PROPERTY(int uplinkRSSI READ uplinkRSSI NOTIFY linkChanged) + Q_PROPERTY(int downlinkRSSI READ downlinkRSSI NOTIFY linkChanged) + Q_PROPERTY(QString serialNumber READ serialNumber NOTIFY linkChanged) + Q_PROPERTY(QString fwVersion READ fwVersion NOTIFY linkChanged) + + explicit TaisyncManager (QGCApplication* app, QGCToolbox* toolbox); + ~TaisyncManager () override; + + void setToolbox (QGCToolbox* toolbox) override; + + bool connected () { return _isConnected; } + bool linkConnected () { return _linkConnected; } + QString linkVidFormat () { return _linkVidFormat; } + int uplinkRSSI () { return _downlinkRSSI; } + int downlinkRSSI () { return _uplinkRSSI; } + QString serialNumber () { return _serialNumber; } + QString fwVersion () { return _fwVersion; } + +signals: + void linkChanged (); + void connectedChanged (); + +private slots: + void _connected (); + void _checkTaisync (); + void _updateSettings (QByteArray jSonData); + void _setEnabled (); + void _setVideoEnabled (); + +private: + + enum { + REQ_LINK_STATUS, + REQ_DEV_INFO, + REQ_FREQ_SCAN, + REQ_LAST + }; + + int _currReq = REQ_LAST; + bool _running = false; + bool _isConnected = false; + AppSettings* _appSettings = nullptr; + TaisyncManager* _taiManager = nullptr; + TaisyncSettings* _taiSettings = nullptr; +#if defined(__ios__) || defined(__android__) + TaisyncTelemetry* _taiTelemetery = nullptr; + TaisyncVideoReceiver* _taiVideo = nullptr; +#endif + bool _enableVideo = true; + bool _enabled = true; + bool _linkConnected = false; + QTimer _workTimer; + QString _linkVidFormat; + int _downlinkRSSI = 0; + int _uplinkRSSI = 0; + bool _savedVideoState = true; + QVariant _savedVideoSource; + QVariant _savedVideoUDP; + QVariant _savedAR; + QString _serialNumber; + QString _fwVersion; +}; diff --git a/src/Taisync/TaisyncSettings.cc b/src/Taisync/TaisyncSettings.cc index e9b98e3e67bed99816d72128fe956d6a04d1a913..b19c017fa1dd6dfe85126c9e63e5f6bef03de089 100644 --- a/src/Taisync/TaisyncSettings.cc +++ b/src/Taisync/TaisyncSettings.cc @@ -7,14 +7,13 @@ * ****************************************************************************/ +#include "TaisyncManager.h" #include "TaisyncSettings.h" #include "SettingsManager.h" #include "QGCApplication.h" #include "VideoManager.h" -QGC_LOGGING_CATEGORY(TaisyncSettingsLog, "TaisyncSettingsLog") - static const char* kPostReq = "POST %1 HTTP/1.1\r\n" "Content-Type: application/json\r\n" @@ -30,19 +29,36 @@ TaisyncSettings::TaisyncSettings(QObject* parent) } //----------------------------------------------------------------------------- -void -TaisyncSettings::start() +bool TaisyncSettings::start() { - qCDebug(TaisyncSettingsLog) << "Start Taisync Settings"; - _start(TAISYNC_SETTINGS_PORT); + qCDebug(TaisyncLog) << "Start Taisync Settings"; +#if defined(__ios__) || defined(__android__) + return _start(TAISYNC_SETTINGS_PORT); +#else + return _start(80, QHostAddress(TAISYNC_SETTINGS_TARGET)); +#endif } //----------------------------------------------------------------------------- bool -TaisyncSettings::requestSettings() +TaisyncSettings::requestLinkStatus() { if(_tcpSocket) { QString req = QString(kGetReq).arg("/v1/baseband.json"); + //qCDebug(TaisyncVerbose) << "Request" << req; + _tcpSocket->write(req.toUtf8()); + return true; + } + return false; +} + +//----------------------------------------------------------------------------- +bool +TaisyncSettings::requestDevInfo() +{ + if(_tcpSocket) { + QString req = QString(kGetReq).arg("/v1/device.json"); + //qCDebug(TaisyncVerbose) << "Request" << req; _tcpSocket->write(req.toUtf8()); return true; } @@ -55,6 +71,7 @@ TaisyncSettings::requestFreqScan() { if(_tcpSocket) { QString req = QString(kGetReq).arg("/v1/freqscan.json"); + //qCDebug(TaisyncVerbose) << "Request" << req; _tcpSocket->write(req.toUtf8()); return true; } @@ -66,26 +83,12 @@ void TaisyncSettings::_readBytes() { QByteArray bytesIn = _tcpSocket->read(_tcpSocket->bytesAvailable()); - qCDebug(TaisyncSettingsLog) << "Taisync settings data:" << bytesIn.size(); - qCDebug(TaisyncSettingsLog) << QString(bytesIn); - if(bytesIn.contains("200 OK")) { - //-- Link Status? - int idx = bytesIn.indexOf('{'); - QJsonParseError jsonParseError; - QJsonDocument doc = QJsonDocument::fromJson(bytesIn.mid(idx), &jsonParseError); - if (jsonParseError.error != QJsonParseError::NoError) { - qWarning() << "Unable to parse Taisync response:" << jsonParseError.errorString() << jsonParseError.offset; - return; - } - QJsonObject jObj = doc.object(); - //-- Link Status? - if(bytesIn.contains("\"flight\":")) { - _linkConnected = jObj["flight"].toBool(_linkConnected); - _linkVidFormat = jObj["videoformat"].toString(_linkVidFormat); - _downlinkRSSI = jObj["radiorssi"].toInt(_downlinkRSSI); - _uplinkRSSI = jObj["hdrssi"].toInt(_uplinkRSSI); - emit linkChanged(); - } + //qCDebug(TaisyncVerbose) << "Taisync settings data:" << bytesIn.size(); + //qCDebug(TaisyncVerbose) << QString(bytesIn); + //-- Go straight to Json payload + int idx = bytesIn.indexOf('{'); + if(idx > 0) { + emit updateSettings(bytesIn.mid(idx)); } } diff --git a/src/Taisync/TaisyncSettings.h b/src/Taisync/TaisyncSettings.h index a28406100578335cfb4cd860bc2ef3d8ec36e668..78edcac0e501764d73e57e7758cb0d210b64ba5d 100644 --- a/src/Taisync/TaisyncSettings.h +++ b/src/Taisync/TaisyncSettings.h @@ -11,37 +11,20 @@ #include "TaisyncHandler.h" -Q_DECLARE_LOGGING_CATEGORY(TaisyncSettingsLog) - class TaisyncSettings : public TaisyncHandler { Q_OBJECT public: - - Q_PROPERTY(bool linkConnected READ linkConnected NOTIFY linkChanged) - Q_PROPERTY(QString linkVidFormat READ linkVidFormat NOTIFY linkChanged) - Q_PROPERTY(int uplinkRSSI READ uplinkRSSI NOTIFY linkChanged) - Q_PROPERTY(int downlinkRSSI READ downlinkRSSI NOTIFY linkChanged) - explicit TaisyncSettings (QObject* parent = nullptr); - void start () override; - bool requestSettings (); + bool start () override; + bool requestLinkStatus (); + bool requestDevInfo (); bool requestFreqScan (); - bool linkConnected () { return _linkConnected; } - QString linkVidFormat () { return _linkVidFormat; } - int uplinkRSSI () { return _downlinkRSSI; } - int downlinkRSSI () { return _uplinkRSSI; } - signals: - void linkChanged (); + void updateSettings (QByteArray jSonData); protected slots: void _readBytes () override; -private: - bool _linkConnected = false; - QString _linkVidFormat; - int _downlinkRSSI = 0; - int _uplinkRSSI = 0; }; diff --git a/src/Taisync/TaisyncSettings.qml b/src/Taisync/TaisyncSettings.qml index 692a84b67132a47574f31ebfdc3d47b2c6cf38c6..3814b0d8e35d621f6c9edc701acd2ae6de1d6dfc 100644 --- a/src/Taisync/TaisyncSettings.qml +++ b/src/Taisync/TaisyncSettings.qml @@ -8,29 +8,206 @@ ****************************************************************************/ -import QtQuick 2.3 -import QtQuick.Controls 1.2 -import QtQuick.Dialogs 1.2 +import QtGraphicalEffects 1.0 +import QtMultimedia 5.5 +import QtQuick 2.3 +import QtQuick.Controls 1.2 +import QtQuick.Controls.Styles 1.4 +import QtQuick.Dialogs 1.2 +import QtQuick.Layouts 1.2 +import QtLocation 5.3 +import QtPositioning 5.3 import QGroundControl 1.0 +import QGroundControl.Controllers 1.0 import QGroundControl.Controls 1.0 -import QGroundControl.ScreenTools 1.0 +import QGroundControl.FactControls 1.0 +import QGroundControl.FactSystem 1.0 import QGroundControl.Palette 1.0 +import QGroundControl.ScreenTools 1.0 +import QGroundControl.SettingsManager 1.0 -Column { - id: _taisyncSettings - spacing: ScreenTools.defaultFontPixelHeight * 0.5 +QGCView { + id: _qgcView + viewPanel: panel + color: qgcPal.window + anchors.fill: parent 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 + + property real _labelWidth: ScreenTools.defaultFontPixelWidth * 26 + property real _valueWidth: ScreenTools.defaultFontPixelWidth * 20 + property real _panelWidth: _qgcView.width * _internalWidthRatio + property Fact _taisyncEnabledFact: QGroundControl.settingsManager.appSettings.enableTaisync + property Fact _taisyncVideoEnabledFact: QGroundControl.settingsManager.appSettings.enableTaisyncVideo + property bool _taisyncEnabled: _taisyncVideoEnabledFact.rawValue + + readonly property real _internalWidthRatio: 0.8 + + QGCPalette { id: qgcPal } + + QGCViewPanel { + id: panel + anchors.fill: parent + QGCFlickable { + clip: true + anchors.fill: parent + contentHeight: settingsColumn.height + contentWidth: settingsColumn.width + Column { + id: settingsColumn + width: _qgcView.width + spacing: ScreenTools.defaultFontPixelHeight * 0.5 + anchors.margins: ScreenTools.defaultFontPixelWidth + //----------------------------------------------------------------- + //-- General + Item { + width: _panelWidth + height: generalLabel.height + anchors.margins: ScreenTools.defaultFontPixelWidth + anchors.horizontalCenter: parent.horizontalCenter + QGCLabel { + id: generalLabel + text: qsTr("General") + font.family: ScreenTools.demiboldFontFamily + } + } + Rectangle { + height: generalRow.height + (ScreenTools.defaultFontPixelHeight * 2) + width: _panelWidth + color: qgcPal.windowShade + anchors.margins: ScreenTools.defaultFontPixelWidth + anchors.horizontalCenter: parent.horizontalCenter + Row { + id: generalRow + spacing: ScreenTools.defaultFontPixelWidth * 4 + anchors.centerIn: parent + Column { + spacing: ScreenTools.defaultFontPixelWidth + FactCheckBox { + text: qsTr("Enable Taisync") + fact: _taisyncEnabledFact + visible: _taisyncEnabledFact.visible + } + FactCheckBox { + text: qsTr("Enable Taisync Video") + fact: _taisyncVideoEnabledFact + visible: _taisyncVideoEnabledFact.visible + enabled: _taisyncEnabled + } + } + } + } + //----------------------------------------------------------------- + //-- Connection Status + Item { + width: _panelWidth + height: statusLabel.height + anchors.margins: ScreenTools.defaultFontPixelWidth + anchors.horizontalCenter: parent.horizontalCenter + visible: _taisyncEnabled + QGCLabel { + id: statusLabel + text: qsTr("Connection Status") + font.family: ScreenTools.demiboldFontFamily + } + } + Rectangle { + height: statusCol.height + (ScreenTools.defaultFontPixelHeight * 2) + width: _panelWidth + color: qgcPal.windowShade + visible: _taisyncEnabled + anchors.margins: ScreenTools.defaultFontPixelWidth + anchors.horizontalCenter: parent.horizontalCenter + Column { + id: statusCol + spacing: ScreenTools.defaultFontPixelHeight * 0.5 + width: parent.width + anchors.centerIn: parent + GridLayout { + anchors.margins: ScreenTools.defaultFontPixelHeight + columnSpacing: ScreenTools.defaultFontPixelWidth * 2 + anchors.horizontalCenter: parent.horizontalCenter + columns: 2 + QGCLabel { + text: qsTr("Ground Unit:") + Layout.minimumWidth: _labelWidth + } + QGCLabel { + text: QGroundControl.taisyncManager.connected ? qsTr("Connected") : qsTr("Not Connected") + color: QGroundControl.taisyncManager.connected ? qgcPal.colorGreen : qgcPal.colorRed + Layout.minimumWidth: _valueWidth + } + QGCLabel { + text: qsTr("Air Unit:") + } + QGCLabel { + text: QGroundControl.taisyncManager.linkConnected ? qsTr("Connected") : qsTr("Not Connected") + color: QGroundControl.taisyncManager.linkConnected ? qgcPal.colorGreen : qgcPal.colorRed + } + QGCLabel { + text: qsTr("Uplink RSSI:") + } + QGCLabel { + text: QGroundControl.taisyncManager.linkConnected ? QGroundControl.taisyncManager.uplinkRSSI : "" + } + QGCLabel { + text: qsTr("Downlink RSSI:") + } + QGCLabel { + text: QGroundControl.taisyncManager.linkConnected ? QGroundControl.taisyncManager.downlinkRSSI : "" + } + } + } + } + //----------------------------------------------------------------- + //-- Device Info + Item { + width: _panelWidth + height: devInfoLabel.height + anchors.margins: ScreenTools.defaultFontPixelWidth + anchors.horizontalCenter: parent.horizontalCenter + visible: _taisyncEnabled + QGCLabel { + id: devInfoLabel + text: qsTr("Device Info") + font.family: ScreenTools.demiboldFontFamily + } + } + Rectangle { + height: devInfoCol.height + (ScreenTools.defaultFontPixelHeight * 2) + width: _panelWidth + color: qgcPal.windowShade + visible: _taisyncEnabled + anchors.margins: ScreenTools.defaultFontPixelWidth + anchors.horizontalCenter: parent.horizontalCenter + Column { + id: devInfoCol + spacing: ScreenTools.defaultFontPixelHeight * 0.5 + width: parent.width + anchors.centerIn: parent + GridLayout { + anchors.margins: ScreenTools.defaultFontPixelHeight + columnSpacing: ScreenTools.defaultFontPixelWidth * 2 + anchors.horizontalCenter: parent.horizontalCenter + columns: 2 + QGCLabel { + text: qsTr("Serial Number:") + Layout.minimumWidth: _labelWidth + } + QGCLabel { + text: QGroundControl.taisyncManager.linkConnected ? QGroundControl.taisyncManager.serialNumber : qsTr("") + Layout.minimumWidth: _valueWidth + } + QGCLabel { + text: qsTr("Firmware Version:") + } + QGCLabel { + text: QGroundControl.taisyncManager.linkConnected ? QGroundControl.taisyncManager.fwVersion : qsTr("") + } + } + } + } + } } } } diff --git a/src/Taisync/TaisyncTelemetry.cc b/src/Taisync/TaisyncTelemetry.cc index 9993cf2ffc730ce3edb34117c843d27c4b858e6c..56ef972d0373d0fd51344af0046c89d64232814d 100644 --- a/src/Taisync/TaisyncTelemetry.cc +++ b/src/Taisync/TaisyncTelemetry.cc @@ -30,11 +30,10 @@ TaisyncTelemetry::close() } //----------------------------------------------------------------------------- -void -TaisyncTelemetry::start() +bool TaisyncTelemetry::start() { qCDebug(TaisyncTelemetryLog) << "Start Taisync Telemetry"; - _start(TAISYNC_TELEM_PORT); + return _start(TAISYNC_TELEM_PORT); } //----------------------------------------------------------------------------- diff --git a/src/Taisync/TaisyncTelemetry.h b/src/Taisync/TaisyncTelemetry.h index fe70aec93fbcaffb799a28cc0683cedc22d29b25..1da53045e977b746ff8709fe5d781d2dddbd7e42 100644 --- a/src/Taisync/TaisyncTelemetry.h +++ b/src/Taisync/TaisyncTelemetry.h @@ -22,7 +22,7 @@ public: explicit TaisyncTelemetry (QObject* parent = nullptr); void close () override; - void start () override; + bool start () override; void writeBytes (QByteArray bytes); signals: diff --git a/src/Taisync/TaisyncVideoReceiver.cc b/src/Taisync/TaisyncVideoReceiver.cc index b4699cc68c7e7c1523aa1dac82ce4a25f7563e8e..033c748b75f915a10976d3fe096f7c97a6342b19 100644 --- a/src/Taisync/TaisyncVideoReceiver.cc +++ b/src/Taisync/TaisyncVideoReceiver.cc @@ -35,12 +35,12 @@ TaisyncVideoReceiver::close() } //----------------------------------------------------------------------------- -void +bool TaisyncVideoReceiver::start() { qCDebug(TaisyncVideoReceiverLog) << "Start Taisync Video Receiver"; _udpVideoSocket = new QUdpSocket(this); - _start(TAISYNC_VIDEO_TCP_PORT); + return _start(TAISYNC_VIDEO_TCP_PORT); } //----------------------------------------------------------------------------- diff --git a/src/Taisync/TaisyncVideoReceiver.h b/src/Taisync/TaisyncVideoReceiver.h index c7ad8bae06972a8e4bcfcd7c32e1f9c385cfee81..26c36da395369703154b2b0a418dd29b5fd62e60 100644 --- a/src/Taisync/TaisyncVideoReceiver.h +++ b/src/Taisync/TaisyncVideoReceiver.h @@ -20,7 +20,7 @@ class TaisyncVideoReceiver : public TaisyncHandler public: explicit TaisyncVideoReceiver (QObject* parent = nullptr); - void start () override; + bool start () override; void close () override; private slots: diff --git a/src/VideoStreaming/VideoReceiver.cc b/src/VideoStreaming/VideoReceiver.cc index 4318b561766014b7c60b8f904b2e00f143dd8c38..e67bbbfcc5781a799d61dc15735d218288028929 100644 --- a/src/VideoStreaming/VideoReceiver.cc +++ b/src/VideoStreaming/VideoReceiver.cc @@ -229,7 +229,8 @@ VideoReceiver::start() _stop = false; qCDebug(VideoReceiverLog) << "start()"; -#ifdef QGC_GST_TAISYNC_ENABLED +#if defined(QGC_GST_TAISYNC_ENABLED) && (defined(__android__) || defined(__ios__)) + //-- Taisync on iOS or Android sends a raw h.264 stream bool isTaisyncUSB = qgcApp()->toolbox()->videoManager()->isTaisync(); #else bool isTaisyncUSB = false; @@ -295,7 +296,7 @@ VideoReceiver::start() break; } g_object_set(static_cast(dataSource), "uri", qPrintable(_uri), "caps", caps, nullptr); -#ifdef QGC_GST_TAISYNC_ENABLED +#if defined(QGC_GST_TAISYNC_ENABLED) && (defined(__android__) || defined(__ios__)) } else if(isTaisyncUSB) { QString uri = QString("0.0.0.0:%1").arg(TAISYNC_VIDEO_UDP_PORT); qCDebug(VideoReceiverLog) << "Taisync URI:" << uri; diff --git a/src/api/QGCCorePlugin.cc b/src/api/QGCCorePlugin.cc index 4cab3169c08e00acbe244f3c3fae61ab93a891c7..eebaf95401cf429422a57a1113f4d008557e80f2 100644 --- a/src/api/QGCCorePlugin.cc +++ b/src/api/QGCCorePlugin.cc @@ -29,25 +29,6 @@ class QGCCorePlugin_p { public: QGCCorePlugin_p() - : pGeneral (nullptr) - , pCommLinks (nullptr) - , pOfflineMaps (nullptr) - #if defined(QGC_AIRMAP_ENABLED) - , pAirmap (nullptr) - #endif - , pMAVLink (nullptr) - , pConsole (nullptr) - , pHelp (nullptr) - #if defined(QT_DEBUG) - , pMockLink (nullptr) - , pDebug (nullptr) - #endif - , defaultOptions (nullptr) - , valuesPageWidgetInfo (nullptr) - , cameraPageWidgetInfo (nullptr) - , videoPageWidgetInfo (nullptr) - , healthPageWidgetInfo (nullptr) - , vibrationPageWidgetInfo (nullptr) { } @@ -59,6 +40,10 @@ public: delete pCommLinks; if(pOfflineMaps) delete pOfflineMaps; +#if defined(QGC_GST_TAISYNC_ENABLED) + if(pTaisync) + delete pTaisync; +#endif #if defined(QGC_AIRMAP_ENABLED) if(pAirmap) delete pAirmap; @@ -77,27 +62,31 @@ public: delete defaultOptions; } - QmlComponentInfo* pGeneral; - QmlComponentInfo* pCommLinks; - QmlComponentInfo* pOfflineMaps; + QmlComponentInfo* pGeneral = nullptr; + QmlComponentInfo* pCommLinks = nullptr; + QmlComponentInfo* pOfflineMaps = nullptr; +#if defined(QGC_GST_TAISYNC_ENABLED) + QmlComponentInfo* pTaisync = nullptr; +#endif #if defined(QGC_AIRMAP_ENABLED) - QmlComponentInfo* pAirmap; + QmlComponentInfo* pAirmap = nullptr; #endif - QmlComponentInfo* pMAVLink; - QmlComponentInfo* pConsole; - QmlComponentInfo* pHelp; + QmlComponentInfo* pMAVLink = nullptr; + QmlComponentInfo* pConsole = nullptr; + QmlComponentInfo* pHelp = nullptr; #if defined(QT_DEBUG) - QmlComponentInfo* pMockLink; - QmlComponentInfo* pDebug; + QmlComponentInfo* pMockLink = nullptr; + QmlComponentInfo* pDebug = nullptr; #endif - QVariantList settingsList; - QGCOptions* defaultOptions; - - QmlComponentInfo* valuesPageWidgetInfo; - QmlComponentInfo* cameraPageWidgetInfo; - QmlComponentInfo* videoPageWidgetInfo; - QmlComponentInfo* healthPageWidgetInfo; - QmlComponentInfo* vibrationPageWidgetInfo; + + QmlComponentInfo* valuesPageWidgetInfo = nullptr; + QmlComponentInfo* cameraPageWidgetInfo = nullptr; + QmlComponentInfo* videoPageWidgetInfo = nullptr; + QmlComponentInfo* healthPageWidgetInfo = nullptr; + QmlComponentInfo* vibrationPageWidgetInfo = nullptr; + + QGCOptions* defaultOptions = nullptr; + QVariantList settingsList; QVariantList instrumentPageWidgetList; QmlObjectListModel _emptyCustomMapItems; @@ -141,6 +130,12 @@ QVariantList &QGCCorePlugin::settingsPages() QUrl::fromUserInput("qrc:/qml/OfflineMap.qml"), QUrl::fromUserInput("qrc:/res/waves.svg")); _p->settingsList.append(QVariant::fromValue(reinterpret_cast(_p->pOfflineMaps))); +#if defined(QGC_GST_TAISYNC_ENABLED) + _p->pTaisync = new QmlComponentInfo(tr("Taisync"), + QUrl::fromUserInput("qrc:/qml/TaisyncSettings.qml"), + QUrl::fromUserInput("")); + _p->settingsList.append(QVariant::fromValue(reinterpret_cast(_p->pTaisync))); +#endif #if defined(QGC_AIRMAP_ENABLED) _p->pAirmap = new QmlComponentInfo(tr("AirMap"), QUrl::fromUserInput("qrc:/qml/AirmapSettings.qml"), diff --git a/src/comm/LinkConfiguration.cc b/src/comm/LinkConfiguration.cc index 1fbdb0faed5aca5370a15ef9667b5b03eb5d88e5..e6a61144de8f36318c0e14b0580a800ebe95e2d8 100644 --- a/src/comm/LinkConfiguration.cc +++ b/src/comm/LinkConfiguration.cc @@ -29,9 +29,6 @@ #ifdef QT_DEBUG #include "MockLink.h" #endif -#if defined(QGC_GST_TAISYNC_ENABLED) -#include "TaisyncLink.h" -#endif #define LINK_SETTING_ROOT "LinkConfigurations" @@ -110,11 +107,6 @@ 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; @@ -153,11 +145,6 @@ 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: break; diff --git a/src/comm/LinkConfiguration.h b/src/comm/LinkConfiguration.h index 11ba5bc37277a92b7e55c565817d8de41e43154a..a32e65f53e2caa0c0189315e43c3faf1a36adb30 100644 --- a/src/comm/LinkConfiguration.h +++ b/src/comm/LinkConfiguration.h @@ -51,9 +51,6 @@ 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 9a210f16aa3ef00df398ec45fbdbee9f047d5af0..036441a4b5514a54a54ed14ae5e766aaa1e7719c 100644 --- a/src/comm/LinkManager.cc +++ b/src/comm/LinkManager.cc @@ -24,9 +24,6 @@ #ifdef QGC_ENABLE_BLUETOOTH #include "BluetoothLink.h" #endif -#if defined(QGC_GST_TAISYNC_ENABLED) -#include "TaisyncLink.h" -#endif #ifndef __mobile__ #include "GPSManager.h" @@ -151,11 +148,6 @@ 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: break; @@ -410,11 +402,6 @@ void LinkManager::loadLinkConfigurationList() case LinkConfiguration::TypeMock: 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 case LinkConfiguration::TypeLast: break; @@ -686,9 +673,6 @@ QStringList LinkManager::linkTypeStrings(void) const #endif list += tr("UDP"); list += tr("TCP"); -#if defined(QGC_GST_TAISYNC_ENABLED) - list += tr("Taisync"); -#endif #ifdef QGC_ENABLE_BLUETOOTH list += "Bluetooth"; #endif @@ -830,15 +814,6 @@ void LinkManager::_fixUnnamed(LinkConfiguration* config) } } 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); diff --git a/src/comm/TaisyncLink.cc b/src/comm/TaisyncLink.cc deleted file mode 100644 index f57d3036af32bd708e7ca3c4792b3e7d4744a919..0000000000000000000000000000000000000000 --- a/src/comm/TaisyncLink.cc +++ /dev/null @@ -1,321 +0,0 @@ -/**************************************************************************** - * - * (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 "VideoManager.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() -{ - // Thread - 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() -{ - //-- Stop thread - _running = false; - quit(); - wait(); - //-- Kill Taisync handlers - if (_taiTelemetery) { - _hardwareDisconnect(); - emit disconnected(); - } -#if defined(__ios__) || defined(__android__) - qgcApp()->toolbox()->videoManager()->setIsTaisync(false); -#endif - //-- 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(); - //-- First save current state - _savedVideoSource = pVSettings->videoSource()->rawValue(); - _savedVideoUDP = pVSettings->udpPort()->rawValue(); - _savedAR = pVSettings->aspectRatio()->rawValue(); - _savedVideoState = pVSettings->visible(); -#if defined(__ios__) || defined(__android__) - //-- iOS and Android receive raw h.264 and need a different pipeline - qgcApp()->toolbox()->videoManager()->setIsTaisync(true); -#endif - //-- Now set it up the way we need it do be - 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 - _connected = false; -} - -//----------------------------------------------------------------------------- -bool -TaisyncLink::_hardwareConnect() -{ - _hardwareDisconnect(); - _taiTelemetery = new TaisyncTelemetry(this); - QObject::connect(_taiTelemetery, &TaisyncTelemetry::bytesReady, this, &TaisyncLink::_readBytes); - QObject::connect(_taiTelemetery, &TaisyncTelemetry::connected, this, &TaisyncLink::_telemetryReady); - _taiTelemetery->start(); - _taiSettings = new TaisyncSettings(this); - _taiSettings->start(); - QObject::connect(_taiSettings, &TaisyncSettings::connected, this, &TaisyncLink::_settingsReady); -#if defined(__ios__) || defined(__android__) - if(_taiConfig->videoEnabled()) { - _taiVideo = new TaisyncVideoReceiver(this); - _taiVideo->start(); - } -#endif - return true; -} - -//----------------------------------------------------------------------------- -bool -TaisyncLink::isConnected() const -{ - return _connected; -} - -//----------------------------------------------------------------------------- -qint64 -TaisyncLink::getConnectionSpeed() const -{ - return 57600; // 57.6 Kbit -} - -//----------------------------------------------------------------------------- -qint64 -TaisyncLink::getCurrentInDataRate() const -{ - return 0; -} - -//----------------------------------------------------------------------------- -qint64 -TaisyncLink::getCurrentOutDataRate() const -{ - return 0; -} - -//----------------------------------------------------------------------------- -void -TaisyncLink::_telemetryReady() -{ - qCDebug(TaisyncLog) << "Taisync telemetry ready"; - if(!_connected) { - _connected = true; - emit connected(); - } -} - -//----------------------------------------------------------------------------- -void -TaisyncLink::_settingsReady() -{ - qCDebug(TaisyncLog) << "Taisync settings ready"; - _taiSettings->requestSettings(); -} - -//-------------------------------------------------------------------------- -//-- 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 deleted file mode 100644 index b2bb73076894bcdaa6f3be97efe6bd327408fa53..0000000000000000000000000000000000000000 --- a/src/comm/TaisyncLink.h +++ /dev/null @@ -1,133 +0,0 @@ -/**************************************************************************** - * - * (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; - - TaisyncSettings*taisyncSettings () { return _taiSettings; } - - // 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); - void _telemetryReady (); - void _settingsReady (); - -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; - bool _connected = false; - QVariant _savedVideoSource; - QVariant _savedVideoUDP; - QVariant _savedAR; -}; -