Commit d0113827 authored by Gus Grubba's avatar Gus Grubba

Initial Taisync link integration

parent 5e63260b
......@@ -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
......
......@@ -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
......
......@@ -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
......
......@@ -199,6 +199,7 @@
<file alias="SurveyItemEditor.qml">src/PlanView/SurveyItemEditor.qml</file>
<file alias="SyslinkComponent.qml">src/AutoPilotPlugins/Common/SyslinkComponent.qml</file>
<file alias="TcpSettings.qml">src/ui/preferences/TcpSettings.qml</file>
<file alias="TaisyncSettings.qml">src/Taisync/TaisyncSettings.qml</file>
<file alias="test.qml">src/test.qml</file>
<file alias="UdpSettings.qml">src/ui/preferences/UdpSettings.qml</file>
<file alias="ValuePageWidget.qml">src/FlightMap/Widgets/ValuePageWidget.qml</file>
......
......@@ -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);
......
/****************************************************************************
*
* (c) 2009-2016 QGROUNDCONTROL PROJECT <http://www.qgroundcontrol.org>
*
* 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;
}
}
/****************************************************************************
*
* (c) 2009-2016 QGROUNDCONTROL PROJECT <http://www.qgroundcontrol.org>
*
* 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 <QTcpServer>
#include <QTcpSocket>
#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;
};
/****************************************************************************
*
* (c) 2009-2016 QGROUNDCONTROL PROJECT <http://www.qgroundcontrol.org>
*
* 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();
}
/****************************************************************************
*
* (c) 2009-2016 QGROUNDCONTROL PROJECT <http://www.qgroundcontrol.org>
*
* 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;
};
/****************************************************************************
*
* (c) 2009-2016 QGROUNDCONTROL PROJECT <http://www.qgroundcontrol.org>
*
* 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
}
}
}
/****************************************************************************
*
* (c) 2009-2016 QGROUNDCONTROL PROJECT <http://www.qgroundcontrol.org>
*
* 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);
}
}
/****************************************************************************
*
* (c) 2009-2016 QGROUNDCONTROL PROJECT <http://www.qgroundcontrol.org>
*
* 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 <QUdpSocket>
#include <QTimer>
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;
};
/****************************************************************************
*
* (c) 2009-2016 QGROUNDCONTROL PROJECT <http://www.qgroundcontrol.org>
*
* 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);
}
/****************************************************************************
*
* (c) 2009-2016 QGROUNDCONTROL PROJECT <http://www.qgroundcontrol.org>
*
* 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 <QUdpSocket>
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;
};
......@@ -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<MockConfiguration*>(source));
break;
#endif
#if defined(QGC_GST_TAISYNC_ENABLED)
case TypeTaisync:
dupe = new TaisyncConfiguration(dynamic_cast<TaisyncConfiguration*>(source));
break;
#endif
case TypeLast:
default:
break;
}
return dupe;
......
......@@ -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
......
This diff is collapsed.
/****************************************************************************
*
* (c) 2009-2016 QGROUNDCONTROL PROJECT <http://www.qgroundcontrol.org>
*
* QGroundControl is licensed according to the terms in the file
* COPYING.md in the root of the source code directory.
*
****************************************************************************/
#include <QtGlobal>
#include <QDebug>
#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<TaisyncConfiguration*>(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<quint64>(data.size()), QDateTime::currentMSecsSinceEpoch());
}
}
//-----------------------------------------------------------------------------
void
TaisyncLink::_readBytes(QByteArray bytes)
{
emit bytesReceived(this, bytes);
_logInputDataRate(static_cast<quint64>(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<TaisyncConfiguration*>(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<TaisyncLink*>(_link);
if(ulink) {
ulink->_restartConnection();
}
}
}
/****************************************************************************
*
* (c) 2009-2018 QGROUNDCONTROL PROJECT <http://www.qgroundcontrol.org>
*
* QGroundControl is licensed according to the terms in the file
* COPYING.md in the root of the source code directory.
*
****************************************************************************/
#pragma once
#include <QString>
#include <QList>
#include <QMap>
#include <QMutex>
#include <QUdpSocket>
#include <QMutexLocker>
#include <QQueue>
#include <QByteArray>
#include <QTcpServer>
#include <QTcpSocket>
#include <QVariant>
#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;
};
Markdown is supported
0% or
You are about to add 0 people to the discussion. Proceed with caution.
Finish editing this message first!
Please register or to comment