Commit 352c53b1 authored by Gus Grubba's avatar Gus Grubba

On desktop (Ethernet connection), the ground unit pushes UDP directly, which...

On desktop (Ethernet connection), the ground unit pushes UDP directly, which makes the use of an actual "Link" not possible. Instead, I've moved all of Taisync support to a "manager" owned by QGCToolbox.
Added a Taisync settings with some basics already wired and running.
parent bab3c35a
......@@ -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 \
}
}
#-------------------------------------------------------------------------------------
......
......@@ -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)
{
}
......
......@@ -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;
};
......
......@@ -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)
......
......@@ -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;
......
......@@ -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
}
]
......@@ -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)
{
......
......@@ -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)
......
......@@ -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
}
]
......@@ -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)
{
......
......@@ -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)
};
......@@ -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;
}
//-----------------------------------------------------------------------------
......
......@@ -14,12 +14,18 @@
#include <QTcpServer>
#include <QTcpSocket>
#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;
};
/****************************************************************************
*
* (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 "QGCToolbox.h"
#include "QGCLoggingCategory.h"
#include "TaisyncSettings.h"
#if defined(__ios__) || defined(__android__)
#include "TaisyncTelemetry.h"
#include "TaisyncVideoReceiver.h"
#endif
#include <QTimer>
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;
};
......@@ -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);