Unverified Commit 168a7326 authored by Gus Grubba's avatar Gus Grubba Committed by GitHub

Merge pull request #7103 from mavlink/taisyncLink

Taisync support
parents b5cf395c c00b0256
......@@ -21,6 +21,7 @@ linux {
message("Linux build")
CONFIG += LinuxBuild
DEFINES += __STDC_LIMIT_MACROS
DEFINES += QGC_GST_TAISYNC_ENABLED
linux-clang {
message("Linux clang")
QMAKE_CXXFLAGS += -Qunused-arguments -fcolor-diagnostics
......@@ -29,6 +30,7 @@ linux {
message("Linux R-Pi2 build")
CONFIG += LinuxBuild
DEFINES += __STDC_LIMIT_MACROS __rasp_pi2__
DEFINES += QGC_GST_TAISYNC_ENABLED
} else : android-g++ | android-clang {
CONFIG += AndroidBuild MobileBuild
DEFINES += __android__
......@@ -50,6 +52,7 @@ linux {
message("Windows build")
CONFIG += WindowsBuild
DEFINES += __STDC_LIMIT_MACROS
DEFINES += QGC_GST_TAISYNC_ENABLED
} else {
error("Unsupported Windows toolchain, only Visual Studio 2015 is supported")
}
......@@ -59,6 +62,7 @@ linux {
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 +87,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,33 @@ SOURCES += \
src/FactSystem/ParameterManager.cc \
src/FactSystem/SettingsFact.cc \
#-------------------------------------------------------------------------------------
# Taisync
contains (DEFINES, QGC_GST_TAISYNC_ENABLED) {
INCLUDEPATH += \
src/Taisync
HEADERS += \
src/Taisync/TaisyncManager.h \
src/Taisync/TaisyncHandler.h \
src/Taisync/TaisyncSettings.h \
SOURCES += \
src/Taisync/TaisyncManager.cc \
src/Taisync/TaisyncHandler.cc \
src/Taisync/TaisyncSettings.cc \
iOSBuild | AndroidBuild {
HEADERS += \
src/Taisync/TaisyncTelemetry.h \
src/Taisync/TaisyncVideoReceiver.h \
SOURCES += \
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>
......
......@@ -147,15 +147,20 @@ void Fact::setCookedValue(const QVariant& value)
}
}
void Fact::setEnumStringValue(const QString& value)
int Fact::valueIndex(const QString& value)
{
if (_metaData) {
int index = _metaData->enumStrings().indexOf(value);
if (index != -1) {
setCookedValue(_metaData->enumValues()[index]);
}
} else {
qWarning() << kMissingMetadata << name();
return _metaData->enumStrings().indexOf(value);
}
qWarning() << kMissingMetadata << name();
return -1;
}
void Fact::setEnumStringValue(const QString& value)
{
int index = valueIndex(value);
if (index != -1) {
setCookedValue(_metaData->enumValues()[index]);
}
}
......
......@@ -138,6 +138,7 @@ public:
void setCookedValue (const QVariant& value);
void setEnumIndex (int index);
void setEnumStringValue (const QString& value);
int valueIndex (const QString& value);
// The following methods allow you to defer sending of the valueChanged signals in order to implement
// rate limited signalling for ui performance. Used by FactGroup for example.
......
......@@ -34,10 +34,6 @@ QGC_LOGGING_CATEGORY(VideoManagerLog, "VideoManagerLog")
//-----------------------------------------------------------------------------
VideoManager::VideoManager(QGCApplication* app, QGCToolbox* toolbox)
: QGCTool(app, toolbox)
, _videoReceiver(nullptr)
, _videoSettings(nullptr)
, _fullScreen(false)
, _activeVehicle(nullptr)
{
}
......
......@@ -36,6 +36,7 @@ public:
Q_PROPERTY(bool hasVideo READ hasVideo NOTIFY hasVideoChanged)
Q_PROPERTY(bool isGStreamer READ isGStreamer NOTIFY isGStreamerChanged)
Q_PROPERTY(bool isAutoStream READ isAutoStream NOTIFY isAutoStreamChanged)
Q_PROPERTY(bool isTaisync READ isTaisync WRITE setIsTaisync NOTIFY isTaisyncChanged)
Q_PROPERTY(QString videoSourceID READ videoSourceID NOTIFY videoSourceIDChanged)
Q_PROPERTY(bool uvcEnabled READ uvcEnabled CONSTANT)
Q_PROPERTY(bool fullScreen READ fullScreen WRITE setfullScreen NOTIFY fullScreenChanged)
......@@ -45,6 +46,7 @@ public:
bool hasVideo ();
bool isGStreamer ();
bool isAutoStream ();
bool isTaisync () { return _isTaisync; }
bool fullScreen () { return _fullScreen; }
QString videoSourceID () { return _videoSourceID; }
QString autoURL () { return QString(_streamInfo.uri); }
......@@ -59,6 +61,7 @@ public:
#endif
void setfullScreen (bool f) { _fullScreen = f; emit fullScreenChanged(); }
void setIsTaisync (bool t) { _isTaisync = t; emit isTaisyncChanged(); }
// Override from QGCTool
void setToolbox (QGCToolbox *toolbox);
......@@ -73,6 +76,7 @@ signals:
void fullScreenChanged ();
void isAutoStreamChanged ();
void aspectRatioChanged ();
void isTaisyncChanged ();
private slots:
void _videoSourceChanged ();
......@@ -88,11 +92,13 @@ private:
void _updateSettings ();
void _restartVideo ();
VideoReceiver* _videoReceiver;
VideoSettings* _videoSettings;
private:
bool _isTaisync = false;
VideoReceiver* _videoReceiver = nullptr;
VideoSettings* _videoSettings = nullptr;
QString _videoSourceID;
bool _fullScreen;
Vehicle* _activeVehicle;
bool _fullScreen = false;
Vehicle* _activeVehicle = nullptr;
mavlink_video_stream_information_t _streamInfo;
};
......
......@@ -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_GST_TAISYNC_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": false
},
{
"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)
};
......@@ -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")
QGC_LOGGING_CATEGORY(TaisyncVerbose, "TaisyncVerbose")
//-----------------------------------------------------------------------------
TaisyncHandler::TaisyncHandler(QObject* parent)
: QObject (parent)
{
}
//-----------------------------------------------------------------------------
TaisyncHandler::~TaisyncHandler()
{
close();
}
//-----------------------------------------------------------------------------
bool TaisyncHandler::close()
{
bool res = (_tcpSocket || _tcpServer);
if(_tcpSocket) {
qCDebug(TaisyncLog) << "Close Taisync TCP socket on port" << _tcpSocket->localPort();
_tcpSocket->close();
_tcpSocket->deleteLater();
_tcpSocket = nullptr;
}
if(_tcpServer) {
qCDebug(TaisyncLog) << "Close Taisync TCP server on port" << _tcpServer->serverPort();;
_tcpServer->close();
_tcpServer->deleteLater();
_tcpServer = nullptr;
}
return res;
}
//-----------------------------------------------------------------------------
bool
TaisyncHandler::_start(uint16_t port, QHostAddress addr)
{
close();
_serverMode = addr == QHostAddress::AnyIPv4;
if(_serverMode) {
if(!_tcpServer) {
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;
}
//-----------------------------------------------------------------------------
void
TaisyncHandler::_newConnection()
{
qCDebug(TaisyncLog) << "New Taisync TCP Connection on port" << _tcpServer->serverPort();
if(_tcpSocket) {
_tcpSocket->close();
_tcpSocket->deleteLater();
}
_tcpSocket = _tcpServer->nextPendingConnection();
if(_tcpSocket) {
QObject::connect(_tcpSocket, &QIODevice::readyRead, this, &TaisyncHandler::_readBytes);
QObject::connect(_tcpSocket, &QAbstractSocket::disconnected, this, &TaisyncHandler::_socketDisconnected);
emit connected();
} else {
qCWarning(TaisyncLog) << "New Taisync TCP Connection provided no socket";
}
}
//-----------------------------------------------------------------------------
void
TaisyncHandler::_socketDisconnected()
{
qCDebug(TaisyncLog) << "Taisync TCP Connection Closed on port" << _tcpSocket->localPort();
if(_tcpSocket) {
_tcpSocket->close();
_tcpSocket->deleteLater();
_tcpSocket = nullptr;
}
emit disconnected();
}
/****************************************************************************
*
* (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>
#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
#define TAISYNC_TELEM_TARGET_PORT 14550
#else
#define TAISYNC_SETTINGS_PORT 80
#endif
Q_DECLARE_LOGGING_CATEGORY(TaisyncLog)
Q_DECLARE_LOGGING_CATEGORY(TaisyncVerbose)
class TaisyncHandler : public QObject
{
Q_OBJECT
public:
explicit TaisyncHandler (QObject* parent = nullptr);
~TaisyncHandler ();
virtual bool start () = 0;
virtual bool close ();
virtual bool isServerRunning () { return (_serverMode && _tcpServer); }
protected:
virtual bool _start (uint16_t port, QHostAddress addr = QHostAddress::AnyIPv4);
protected slots:
virtual void _newConnection ();
virtual void _socketDisconnected ();
virtual void _readBytes () = 0;
signals:
void connected ();
void disconnected ();
protected:
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.
*
****************************************************************************/
#include "TaisyncManager.h"
#include "TaisyncHandler.h"
#include "SettingsManager.h"
#include "QGCApplication.h"
#include "VideoManager.h"
#include <QSettings>
static const char *kTAISYNC_GROUP = "Taisync";
static const char *kRADIO_MODE = "RadioMode";
static const char *kRADIO_CHANNEL = "RadioChannel";
static const char *kVIDEO_OUTPUT = "VideoOutput";
static const char *kVIDEO_MODE = "VideoMode";
static const char *kVIDEO_RATE = "VideoRate";
static const char *kLOCAL_IP = "LocalIP";
static const char *kREMOTE_IP = "RemoteIP";
static const char *kNET_MASK = "NetMask";
static const char *kRTSP_URI = "RTSPURI";
static const char *kRTSP_ACCOUNT = "RTSPAccount";
static const char *kRTSP_PASSWORD = "RTSPPassword";
//-----------------------------------------------------------------------------
TaisyncManager::TaisyncManager(QGCApplication* app, QGCToolbox* toolbox)
: QGCTool(app, toolbox)
{
connect(&_workTimer, &QTimer::timeout, this, &TaisyncManager::_checkTaisync);
_workTimer.setSingleShot(true);
QSettings settings;
settings.beginGroup(kTAISYNC_GROUP);
_localIPAddr = settings.value(kLOCAL_IP, QString("192.168.199.33")).toString();
_remoteIPAddr = settings.value(kREMOTE_IP, QString("192.168.199.16")).toString();
_netMask = settings.value(kNET_MASK, QString("255.255.255.0")).toString();
_rtspURI = settings.value(kRTSP_URI, QString("rtsp://192.168.0.2")).toString();
_rtspAccount = settings.value(kRTSP_ACCOUNT, QString("admin")).toString();
_rtspPassword = settings.value(kRTSP_PASSWORD, QString("12345678")).toString();
settings.endGroup();
}
//-----------------------------------------------------------------------------
TaisyncManager::~TaisyncManager()
{
_close();
}
//-----------------------------------------------------------------------------
void
TaisyncManager::_close()
{
if(_taiSettings) {
_taiSettings->close();
_taiSettings->deleteLater();
_taiSettings = nullptr;
}
#if defined(__ios__) || defined(__android__)
if (_taiTelemetery) {
_taiTelemetery->close();
_taiTelemetery->deleteLater();
_taiTelemetery = nullptr;
}
if(_telemetrySocket) {
_telemetrySocket->close();
_telemetrySocket->deleteLater();
_telemetrySocket = nullptr;
}
if (_taiVideo) {
_taiVideo->close();
_taiVideo->deleteLater();
_taiVideo = nullptr;
}
#endif
}
//-----------------------------------------------------------------------------
void
TaisyncManager::_reset()
{
_close();
_isConnected = false;
emit connectedChanged();
_linkConnected = false;
emit linkConnectedChanged();
_taiSettings = new TaisyncSettings(this);
connect(_taiSettings, &TaisyncSettings::updateSettings, this, &TaisyncManager::_updateSettings);
connect(_taiSettings, &TaisyncSettings::connected, this, &TaisyncManager::_connected);
connect(_taiSettings, &TaisyncSettings::disconnected, this, &TaisyncManager::_disconnected);
if(!_appSettings) {
_appSettings = _toolbox->settingsManager()->appSettings();
connect(_appSettings->enableTaisync(), &Fact::rawValueChanged, this, &TaisyncManager::_setEnabled);
connect(_appSettings->enableTaisyncVideo(), &Fact::rawValueChanged, this, &TaisyncManager::_setVideoEnabled);
}
_setEnabled();
}
//-----------------------------------------------------------------------------
FactMetaData*
TaisyncManager::_createMetadata(const char* name, QStringList enums)
{
FactMetaData* metaData = new FactMetaData(FactMetaData::valueTypeUint32, name, this);
QQmlEngine::setObjectOwnership(metaData, QQmlEngine::CppOwnership);
metaData->setShortDescription(name);
metaData->setLongDescription(name);
metaData->setRawDefaultValue(QVariant(0));
metaData->setHasControl(true);
metaData->setReadOnly(false);
for(int i = 0; i < enums.size(); i++) {
metaData->addEnumInfo(enums[i], QVariant(i));
}
metaData->setRawMin(0);
metaData->setRawMin(enums.size() - 1);
return metaData;
}
//-----------------------------------------------------------------------------
void
TaisyncManager::setToolbox(QGCToolbox* toolbox)
{
QGCTool::setToolbox(toolbox);
{
//-- Radio Mode
QStringList enums;
enums.append(tr("Auto"));
enums.append(tr("Manual"));
FactMetaData* metaData = _createMetadata(kRADIO_MODE, enums);
_radioMode = new Fact(kTAISYNC_GROUP, metaData, this);
QQmlEngine::setObjectOwnership(_radioMode, QQmlEngine::CppOwnership);
_radioModeList.append("auto");
_radioModeList.append("manual");
connect(_radioMode, &Fact::_containerRawValueChanged, this, &TaisyncManager::_radioSettingsChanged);
}
{
//-- Radio Channel
QStringList enums;
for(int i = 0; i < 13; i++) {
enums.append(QString("ch%1").arg(i));
}
FactMetaData* metaData = _createMetadata(kRADIO_CHANNEL, enums);
_radioChannel = new Fact(kTAISYNC_GROUP, metaData, this);
QQmlEngine::setObjectOwnership(_radioChannel, QQmlEngine::CppOwnership);
connect(_radioChannel, &Fact::_containerRawValueChanged, this, &TaisyncManager::_radioSettingsChanged);
}
{
//-- Video Output
QStringList enums;
enums.append(tr("Stream"));
enums.append(tr("HDMI Port"));
FactMetaData* metaData = _createMetadata(kVIDEO_OUTPUT, enums);
_videoOutput = new Fact(kTAISYNC_GROUP, metaData, this);
QQmlEngine::setObjectOwnership(_videoOutput, QQmlEngine::CppOwnership);
_videoOutputList.append("phone");
_videoOutputList.append("hdmi");
connect(_videoOutput, &Fact::_containerRawValueChanged, this, &TaisyncManager::_videoSettingsChanged);
}
{
//-- Video Mode
QStringList enums;
enums.append("H264");
enums.append("H265");
FactMetaData* metaData = _createMetadata(kVIDEO_MODE, enums);
_videoMode = new Fact(kTAISYNC_GROUP, metaData, this);
QQmlEngine::setObjectOwnership(_videoMode, QQmlEngine::CppOwnership);
connect(_videoMode, &Fact::_containerRawValueChanged, this, &TaisyncManager::_videoSettingsChanged);
}
{
//-- Video Rate
QStringList enums;
enums.append(tr("Low"));
enums.append(tr("Medium"));
enums.append(tr("High"));
FactMetaData* metaData = _createMetadata(kVIDEO_RATE, enums);
_videoRate = new Fact(kTAISYNC_GROUP, metaData, this);
QQmlEngine::setObjectOwnership(_videoRate, QQmlEngine::CppOwnership);
_videoRateList.append("low");
_videoRateList.append("middle");
_videoRateList.append("high");
connect(_videoRate, &Fact::_containerRawValueChanged, this, &TaisyncManager::_videoSettingsChanged);
}
_reset();
}
//-----------------------------------------------------------------------------
bool
TaisyncManager::setRTSPSettings(QString uri, QString account, QString password)
{
if(_taiSettings && _isConnected) {
if(_taiSettings->setRTSPSettings(uri, account, password)) {
_rtspURI = uri;
_rtspAccount = account;
_rtspPassword = password;
QSettings settings;
settings.beginGroup(kTAISYNC_GROUP);
settings.setValue(kRTSP_URI, _rtspURI);
settings.setValue(kRTSP_ACCOUNT, _rtspAccount);
settings.setValue(kRTSP_PASSWORD, _rtspPassword);
settings.endGroup();
emit rtspURIChanged();
emit rtspAccountChanged();
emit rtspPasswordChanged();
_needReboot = true;
emit needRebootChanged();
return true;
}
}
return false;
}
//-----------------------------------------------------------------------------
bool
TaisyncManager::setIPSettings(QString localIP_, QString remoteIP_, QString netMask_)
{
bool res = false;
if(_localIPAddr != localIP_ || _remoteIPAddr != remoteIP_ || _netMask != netMask_) {
//-- If we are connected to the Taisync
if(_isConnected) {
if(_taiSettings) {
//-- Change IP settings
res = _taiSettings->setIPSettings(localIP_, remoteIP_, netMask_);
if(res) {
_needReboot = true;
emit needRebootChanged();
}
}
} else {
//-- We're not connected. Record the change and restart.
_localIPAddr = localIP_;
_remoteIPAddr = remoteIP_;
_netMask = netMask_;
_reset();
res = true;
}
if(res) {
QSettings settings;
settings.beginGroup(kTAISYNC_GROUP);
settings.setValue(kLOCAL_IP, localIP_);
settings.setValue(kREMOTE_IP, remoteIP_);
settings.setValue(kNET_MASK, netMask_);
settings.endGroup();
}
} else {
//-- Nothing to change
res = true;
}
return res;
}
//-----------------------------------------------------------------------------
void
TaisyncManager::_radioSettingsChanged(QVariant)
{
if(_taiSettings && _isConnected) {
_workTimer.stop();
_taiSettings->setRadioSettings(
_radioModeList[_radioMode->rawValue().toInt()],
_radioChannel->enumStringValue());
_reqMask |= REQ_RADIO_SETTINGS;
_workTimer.start(3000);
}
}
//-----------------------------------------------------------------------------
void
TaisyncManager::_videoSettingsChanged(QVariant)
{
if(_taiSettings && _isConnected) {
_workTimer.stop();
_taiSettings->setVideoSettings(
_videoOutputList[_videoOutput->rawValue().toInt()],
_videoMode->enumStringValue(),
_videoRateList[_videoRate->rawValue().toInt()]);
_reqMask |= REQ_VIDEO_SETTINGS;
_workTimer.start(500);
}
}
//-----------------------------------------------------------------------------
void
TaisyncManager::_setEnabled()
{
bool enable = _appSettings->enableTaisync()->rawValue().toBool();
if(enable) {
#if defined(__ios__) || defined(__android__)
if(!_taiTelemetery) {
_taiTelemetery = new TaisyncTelemetry(this);
QObject::connect(_taiTelemetery, &TaisyncTelemetry::bytesReady, this, &TaisyncManager::_readTelemBytes);
_telemetrySocket = new QUdpSocket(this);
_telemetrySocket->setSocketOption(QAbstractSocket::SendBufferSizeSocketOption, 64 * 1024);
_telemetrySocket->setSocketOption(QAbstractSocket::ReceiveBufferSizeSocketOption, 64 * 1024);
QObject::connect(_telemetrySocket, &QUdpSocket::readyRead, this, &TaisyncManager::_readUDPBytes);
_telemetrySocket->bind(QHostAddress::LocalHost, 0, QUdpSocket::ShareAddress);
_taiTelemetery->start();
}
#endif
_reqMask = REQ_ALL;
_workTimer.start(1000);
} else {
//-- Stop everything
_workTimer.stop();
_close();
}
_enabled = enable;
//-- Now handle video support
_setVideoEnabled();
}
//-----------------------------------------------------------------------------
void
TaisyncManager::_setVideoEnabled()
{
//-- Check both if video is enabled and Taisync support itself is enabled as well.
bool enable = _appSettings->enableTaisyncVideo()->rawValue().toBool() && _appSettings->enableTaisync()->rawValue().toBool();
if(enable) {
//-- If we haven't already saved the previous settings...
if(!_savedVideoSource.isValid()) {
//-- 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__)
if(!_taiVideo) {
//-- 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;
}
//-----------------------------------------------------------------------------
#if defined(__ios__) || defined(__android__)
void
TaisyncManager::_readTelemBytes(QByteArray bytesIn)
{
//-- Send telemetry from vehicle to QGC (using normal UDP)
_telemetrySocket->writeDatagram(bytesIn, QHostAddress::LocalHost, TAISYNC_TELEM_TARGET_PORT);
}
#endif
//-----------------------------------------------------------------------------
#if defined(__ios__) || defined(__android__)
void
TaisyncManager::_readUDPBytes()
{
if (!_telemetrySocket || !_taiTelemetery) {
return;
}
//-- Read UDP data from QGC
while (_telemetrySocket->hasPendingDatagrams()) {
QByteArray datagram;
datagram.resize(static_cast<int>(_telemetrySocket->pendingDatagramSize()));
_telemetrySocket->readDatagram(datagram.data(), datagram.size());
//-- Send it to vehicle
_taiTelemetery->writeBytes(datagram);
}
}
#endif
//-----------------------------------------------------------------------------
void
TaisyncManager::_connected()
{
qCDebug(TaisyncLog) << "Taisync Settings Connected";
_isConnected = true;
emit connectedChanged();
_needReboot = false;
emit needRebootChanged();
}
//-----------------------------------------------------------------------------
void
TaisyncManager::_disconnected()
{
qCDebug(TaisyncLog) << "Taisync Settings Disconnected";
_isConnected = false;
emit connectedChanged();
_needReboot = false;
emit needRebootChanged();
_linkConnected = false;
emit linkConnectedChanged();
_reset();
}
//-----------------------------------------------------------------------------
void
TaisyncManager::_checkTaisync()
{
if(_enabled) {
if(!_isConnected) {
if(!_taiSettings->isServerRunning()) {
_taiSettings->start();
}
} else {
//qCDebug(TaisyncVerbose) << bin << _reqMask;
while(true) {
if (_reqMask & REQ_LINK_STATUS) {
_taiSettings->requestLinkStatus();
break;
}
if (_reqMask & REQ_DEV_INFO) {
_taiSettings->requestDevInfo();
break;
}
if (_reqMask & REQ_FREQ_SCAN) {
_reqMask &= ~static_cast<uint32_t>(REQ_FREQ_SCAN);
_taiSettings->requestFreqScan();
break;
}
if (_reqMask & REQ_VIDEO_SETTINGS) {
_taiSettings->requestVideoSettings();
break;
}
if (_reqMask & REQ_RADIO_SETTINGS) {
_taiSettings->requestRadioSettings();
break;
}
if (_reqMask & REQ_RTSP_SETTINGS) {
_reqMask &= ~static_cast<uint32_t>(REQ_RTSP_SETTINGS);
_taiSettings->requestRTSPURISettings();
break;
}
if (_reqMask & REQ_IP_SETTINGS) {
_reqMask &= ~static_cast<uint32_t>(REQ_IP_SETTINGS);
_taiSettings->requestIPSettings();
break;
}
//-- Check link status
if(_timeoutTimer.elapsed() > 3000) {
//-- Give up and restart
_disconnected();
break;
}
//-- If it's been too long since we last heard, ping it.
if(_timeoutTimer.elapsed() > 1000) {
_taiSettings->requestLinkStatus();
break;
}
break;
}
}
_workTimer.start(_isConnected ? 500 : 5000);
}
}
//-----------------------------------------------------------------------------
void
TaisyncManager::_updateSettings(QByteArray jSonData)
{
_timeoutTimer.start();
qCDebug(TaisyncVerbose) << 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\":")) {
_reqMask &= ~static_cast<uint32_t>(REQ_LINK_STATUS);
bool tlinkConnected = jObj["flight"].toString("") == "online";
if(tlinkConnected != _linkConnected) {
_linkConnected = tlinkConnected;
emit linkConnectedChanged();
}
QString tlinkVidFormat = jObj["videoformat"].toString(_linkVidFormat);
int tdownlinkRSSI = jObj["radiorssi"].toInt(_downlinkRSSI);
int tuplinkRSSI = jObj["hdrssi"].toInt(_uplinkRSSI);
if(_linkVidFormat != tlinkVidFormat || _downlinkRSSI != tdownlinkRSSI || _uplinkRSSI != tuplinkRSSI) {
_linkVidFormat = tlinkVidFormat;
_downlinkRSSI = tdownlinkRSSI;
_uplinkRSSI = tuplinkRSSI;
emit linkChanged();
}
//-- Device Info?
} else if(jSonData.contains("\"firmwareversion\":")) {
_reqMask &= ~static_cast<uint32_t>(REQ_DEV_INFO);
QString tfwVersion = jObj["firmwareversion"].toString(_fwVersion);
QString tserialNumber = jObj["sn"].toString(_serialNumber);
if(tfwVersion != _fwVersion || tserialNumber != _serialNumber) {
_fwVersion = tfwVersion;
_serialNumber = tserialNumber;
emit infoChanged();
}
//-- Radio Settings?
} else if(jSonData.contains("\"freq\":")) {
_reqMask &= ~static_cast<uint32_t>(REQ_RADIO_SETTINGS);
int idx = _radioModeList.indexOf(jObj["mode"].toString(_radioMode->enumStringValue()));
if(idx >= 0) _radioMode->_containerSetRawValue(idx);
idx = _radioChannel->valueIndex(jObj["freq"].toString(_radioChannel->enumStringValue()));
if(idx < 0) idx = 0;
_radioChannel->_containerSetRawValue(idx);
//-- Video Settings?
} else if(jSonData.contains("\"maxbitrate\":")) {
_reqMask &= ~static_cast<uint32_t>(REQ_VIDEO_SETTINGS);
int idx;
idx = _videoMode->valueIndex(jObj["mode"].toString(_videoMode->enumStringValue()));
if(idx < 0) idx = 0;
_videoMode->_containerSetRawValue(idx);
idx = _videoRateList.indexOf(jObj["maxbitrate"].toString(_videoMode->enumStringValue()));
if(idx >= 0) _videoRate->_containerSetRawValue(idx);
idx = _videoOutputList.indexOf(jObj["decode"].toString(_videoOutput->enumStringValue()));
if(idx >= 0) _videoOutput->_containerSetRawValue(idx);
//-- IP Address Settings?
} else if(jSonData.contains("\"usbEthIp\":")) {
QString value;
bool changed = false;
value = jObj["ipaddr"].toString(_localIPAddr);
if(value != _localIPAddr) {
_localIPAddr = value;
changed = true;
emit localIPAddrChanged();
}
value = jObj["netmask"].toString(_netMask);
if(value != _netMask) {
_netMask = value;
changed = true;
emit netMaskChanged();
}
value = jObj["usbEthIp"].toString(_remoteIPAddr);
if(value != _remoteIPAddr) {
_remoteIPAddr = value;
changed = true;
emit remoteIPAddrChanged();
}
if(changed) {
QSettings settings;
settings.beginGroup(kTAISYNC_GROUP);
settings.setValue(kLOCAL_IP, _localIPAddr);
settings.setValue(kREMOTE_IP, _remoteIPAddr);
settings.setValue(kNET_MASK, _netMask);
settings.endGroup();
}
//-- RTSP URI Settings?
} else if(jSonData.contains("\"rtspURI\":")) {
QString value;
bool changed = false;
value = jObj["rtspURI"].toString(_rtspURI);
if(value != _rtspURI) {
_rtspURI = value;
changed = true;
emit rtspURIChanged();
}
value = jObj["account"].toString(_rtspAccount);
if(value != _rtspAccount) {
_rtspAccount = value;
changed = true;
emit rtspAccountChanged();
}
value = jObj["passwd"].toString(_rtspPassword);
if(value != _rtspPassword) {
_rtspPassword = value;
changed = true;
emit rtspPasswordChanged();
}
if(changed) {
QSettings settings;
settings.beginGroup(kTAISYNC_GROUP);
settings.setValue(kRTSP_URI, _rtspURI);
settings.setValue(kRTSP_ACCOUNT, _rtspAccount);
settings.setValue(kRTSP_PASSWORD, _rtspPassword);
settings.endGroup();
}
}
}
/****************************************************************************
*
* (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"
#include "Fact.h"
#if defined(__ios__) || defined(__android__)
#include "TaisyncTelemetry.h"
#include "TaisyncVideoReceiver.h"
#endif
#include <QTimer>
#include <QTime>
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 linkConnectedChanged)
Q_PROPERTY(bool needReboot READ needReboot NOTIFY needRebootChanged)
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 infoChanged)
Q_PROPERTY(QString fwVersion READ fwVersion NOTIFY infoChanged)
Q_PROPERTY(Fact* radioMode READ radioMode CONSTANT)
Q_PROPERTY(Fact* radioChannel READ radioChannel CONSTANT)
Q_PROPERTY(Fact* videoOutput READ videoOutput CONSTANT)
Q_PROPERTY(Fact* videoMode READ videoMode CONSTANT)
Q_PROPERTY(Fact* videoRate READ videoRate CONSTANT)
Q_PROPERTY(QString rtspURI READ rtspURI NOTIFY rtspURIChanged)
Q_PROPERTY(QString rtspAccount READ rtspAccount NOTIFY rtspAccountChanged)
Q_PROPERTY(QString rtspPassword READ rtspPassword NOTIFY rtspPasswordChanged)
Q_PROPERTY(QString localIPAddr READ localIPAddr NOTIFY localIPAddrChanged)
Q_PROPERTY(QString remoteIPAddr READ remoteIPAddr NOTIFY remoteIPAddrChanged)
Q_PROPERTY(QString netMask READ netMask NOTIFY netMaskChanged)
Q_INVOKABLE bool setRTSPSettings (QString uri, QString account, QString password);
Q_INVOKABLE bool setIPSettings (QString localIP, QString remoteIP, QString netMask);
explicit TaisyncManager (QGCApplication* app, QGCToolbox* toolbox);
~TaisyncManager () override;
void setToolbox (QGCToolbox* toolbox) override;
bool connected () { return _isConnected; }
bool linkConnected () { return _linkConnected; }
bool needReboot () { return _needReboot; }
QString linkVidFormat () { return _linkVidFormat; }
int uplinkRSSI () { return _downlinkRSSI; }
int downlinkRSSI () { return _uplinkRSSI; }
QString serialNumber () { return _serialNumber; }
QString fwVersion () { return _fwVersion; }
Fact* radioMode () { return _radioMode; }
Fact* radioChannel () { return _radioChannel; }
Fact* videoOutput () { return _videoOutput; }
Fact* videoMode () { return _videoMode; }
Fact* videoRate () { return _videoRate; }
QString rtspURI () { return _rtspURI; }
QString rtspAccount () { return _rtspAccount; }
QString rtspPassword () { return _rtspPassword; }
QString localIPAddr () { return _localIPAddr; }
QString remoteIPAddr () { return _remoteIPAddr; }
QString netMask () { return _netMask; }
signals:
void linkChanged ();
void linkConnectedChanged ();
void infoChanged ();
void connectedChanged ();
void decodeIndexChanged ();
void rateIndexChanged ();
void rtspURIChanged ();
void rtspAccountChanged ();
void rtspPasswordChanged ();
void localIPAddrChanged ();
void remoteIPAddrChanged ();
void netMaskChanged ();
void needRebootChanged ();
private slots:
void _connected ();
void _disconnected ();
void _checkTaisync ();
void _updateSettings (QByteArray jSonData);
void _setEnabled ();
void _setVideoEnabled ();
void _radioSettingsChanged (QVariant);
void _videoSettingsChanged (QVariant);
#if defined(__ios__) || defined(__android__)
void _readUDPBytes ();
void _readTelemBytes (QByteArray bytesIn);
#endif
private:
void _close ();
void _reset ();
FactMetaData *_createMetadata (const char *name, QStringList enums);
private:
enum {
REQ_LINK_STATUS = 1,
REQ_DEV_INFO = 2,
REQ_FREQ_SCAN = 4,
REQ_VIDEO_SETTINGS = 8,
REQ_RADIO_SETTINGS = 16,
REQ_RTSP_SETTINGS = 32,
REQ_IP_SETTINGS = 64,
REQ_ALL = 0xFFFFFFFF,
};
uint32_t _reqMask = REQ_ALL;
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;
QUdpSocket* _telemetrySocket= nullptr;
#endif
bool _enableVideo = true;
bool _enabled = true;
bool _linkConnected = false;
bool _needReboot = false;
QTimer _workTimer;
QString _linkVidFormat;
int _downlinkRSSI = 0;
int _uplinkRSSI = 0;
QStringList _decodeList;
int _decodeIndex = 0;
QStringList _rateList;
int _rateIndex = 0;
bool _savedVideoState = true;
QVariant _savedVideoSource;
QVariant _savedVideoUDP;
QVariant _savedAR;
QString _serialNumber;
QString _fwVersion;
Fact* _radioMode = nullptr;
Fact* _radioChannel = nullptr;
Fact* _videoOutput = nullptr;
Fact* _videoMode = nullptr;
Fact* _videoRate = nullptr;
QStringList _radioModeList;
QStringList _videoOutputList;
QStringList _videoRateList;
QString _rtspURI;
QString _rtspAccount;
QString _rtspPassword;
QString _localIPAddr;
QString _remoteIPAddr;
QString _netMask;
QTime _timeoutTimer;
};
/****************************************************************************
*
* (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 "TaisyncManager.h"
#include "TaisyncSettings.h"
#include "SettingsManager.h"
#include "QGCApplication.h"
#include "VideoManager.h"
static const char* kPostReq =
"POST %1 HTTP/1.1\r\n"
"Content-Type: application/json\r\n"
"Content-Length: %2\r\n\r\n"
"%3";
static const char* kGetReq = "GET %1 HTTP/1.1\r\n\r\n";
static const char* kRadioURI = "/v1/radio.json";
static const char* kVideoURI = "/v1/video.json";
static const char* kRTSPURI = "/v1/rtspuri.json";
static const char* kIPAddrURI = "/v1/ipaddr.json";
//-----------------------------------------------------------------------------
TaisyncSettings::TaisyncSettings(QObject* parent)
: TaisyncHandler(parent)
{
}
//-----------------------------------------------------------------------------
bool TaisyncSettings::start()
{
qCDebug(TaisyncLog) << "Start Taisync Settings";
#if defined(__ios__) || defined(__android__)
return _start(TAISYNC_SETTINGS_PORT);
#else
return _start(TAISYNC_SETTINGS_PORT, QHostAddress(qgcApp()->toolbox()->taisyncManager()->remoteIPAddr()));
#endif
}
//-----------------------------------------------------------------------------
bool
TaisyncSettings::requestLinkStatus()
{
return _request("/v1/baseband.json");
}
//-----------------------------------------------------------------------------
bool
TaisyncSettings::requestDevInfo()
{
return _request("/v1/device.json");
}
//-----------------------------------------------------------------------------
bool
TaisyncSettings::requestFreqScan()
{
return _request("/v1/freqscan.json");
}
//-----------------------------------------------------------------------------
bool
TaisyncSettings::requestVideoSettings()
{
return _request(kVideoURI);
}
//-----------------------------------------------------------------------------
bool
TaisyncSettings::requestRadioSettings()
{
return _request(kRadioURI);
}
//-----------------------------------------------------------------------------
bool
TaisyncSettings::requestIPSettings()
{
return _request(kIPAddrURI);
}
//-----------------------------------------------------------------------------
bool
TaisyncSettings::requestRTSPURISettings()
{
return _request(kRTSPURI);
}
//-----------------------------------------------------------------------------
bool
TaisyncSettings::_request(const QString& request)
{
if(_tcpSocket) {
QString req = QString(kGetReq).arg(request);
//qCDebug(TaisyncVerbose) << "Request" << req;
_tcpSocket->write(req.toUtf8());
return true;
}
return false;
}
//-----------------------------------------------------------------------------
bool
TaisyncSettings::_post(const QString& post, const QString &postPayload)
{
if(_tcpSocket) {
QString req = QString(kPostReq).arg(post).arg(postPayload.size()).arg(postPayload);
qCDebug(TaisyncVerbose) << "Post" << req;
_tcpSocket->write(req.toUtf8());
return true;
}
return false;
}
//-----------------------------------------------------------------------------
bool
TaisyncSettings::setRadioSettings(const QString& mode, const QString& channel)
{
static const char* kRadioPost = "{\"mode\":\"%1\",\"freq\":\"%2\"}";
QString post = QString(kRadioPost).arg(mode).arg(channel);
return _post(kRadioURI, post);
}
//-----------------------------------------------------------------------------
bool
TaisyncSettings::setVideoSettings(const QString& output, const QString& mode, const QString& rate)
{
static const char* kVideoPost = "{\"decode\":\"%1\",\"mode\":\"%2\",\"maxbitrate\":\"%3\"}";
QString post = QString(kVideoPost).arg(output).arg(mode).arg(rate);
return _post(kVideoURI, post);
}
//-----------------------------------------------------------------------------
bool
TaisyncSettings::setRTSPSettings(const QString& uri, const QString& account, const QString& password)
{
static const char* kRTSPPost = "{\"rtspURI\":\"%1\",\"account\":\"%2\",\"passwd\":\"%3\"}";
QString post = QString(kRTSPPost).arg(uri).arg(account).arg(password);
return _post(kRTSPURI, post);
}
//-----------------------------------------------------------------------------
bool
TaisyncSettings::setIPSettings(const QString& localIP, const QString& remoteIP, const QString& netMask)
{
static const char* kRTSPPost = "{\"ipaddr\":\"%1\",\"netmask\":\"%2\",\"usbEthIp\":\"%3\"}";
QString post = QString(kRTSPPost).arg(localIP).arg(netMask).arg(remoteIP);
return _post(kIPAddrURI, post);
}
//-----------------------------------------------------------------------------
void
TaisyncSettings::_readBytes()
{
QByteArray bytesIn = _tcpSocket->read(_tcpSocket->bytesAvailable());
//-- Go straight to Json payload
int idx = bytesIn.indexOf('{');
//-- We may receive more than one response within one TCP packet.
while(idx >= 0) {
bytesIn = bytesIn.mid(idx);
idx = bytesIn.indexOf('}');
if(idx > 0) {
QByteArray data = bytesIn.left(idx + 1);
emit updateSettings(data);
bytesIn = bytesIn.mid(idx+1);
idx = bytesIn.indexOf('{');
}
}
}
/****************************************************************************
*
* (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"
class TaisyncSettings : public TaisyncHandler
{
Q_OBJECT
public:
explicit TaisyncSettings (QObject* parent = nullptr);
bool start () override;
bool requestLinkStatus ();
bool requestDevInfo ();
bool requestFreqScan ();
bool requestVideoSettings ();
bool requestRadioSettings ();
bool requestIPSettings ();
bool requestRTSPURISettings ();
bool setRadioSettings (const QString& mode, const QString& channel);
bool setVideoSettings (const QString& output, const QString& mode, const QString& rate);
bool setRTSPSettings (const QString& uri, const QString& account, const QString& password);
bool setIPSettings (const QString& localIP, const QString& remoteIP, const QString& netMask);
signals:
void updateSettings (QByteArray jSonData);
protected slots:
void _readBytes () override;
private:
bool _request (const QString& request);
bool _post (const QString& post, const QString& postPayload);
};
/****************************************************************************
*
* (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 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.FactControls 1.0
import QGroundControl.FactSystem 1.0
import QGroundControl.Palette 1.0
import QGroundControl.ScreenTools 1.0
import QGroundControl.SettingsManager 1.0
QGCView {
id: _qgcView
viewPanel: panel
color: qgcPal.window
anchors.fill: parent
anchors.margins: ScreenTools.defaultFontPixelWidth
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: _taisyncEnabledFact.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
QGCLabel {
text: qsTr("Reboot ground unit for changes to take effect.")
color: qgcPal.colorOrange
visible: QGroundControl.taisyncManager.needReboot
font.family: ScreenTools.demiboldFontFamily
anchors.horizontalCenter: parent.horizontalCenter
}
//-----------------------------------------------------------------
//-- 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
enabled: !QGroundControl.taisyncManager.needReboot
visible: _taisyncEnabledFact.visible
}
FactCheckBox {
text: qsTr("Enable Taisync Video")
fact: _taisyncVideoEnabledFact
visible: _taisyncVideoEnabledFact.visible
enabled: _taisyncEnabled && !QGroundControl.taisyncManager.needReboot
}
}
}
}
//-----------------------------------------------------------------
//-- 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 && QGroundControl.taisyncManager.connected
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 && QGroundControl.taisyncManager.connected
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.connected ? QGroundControl.taisyncManager.serialNumber : qsTr("")
Layout.minimumWidth: _valueWidth
}
QGCLabel {
text: qsTr("Firmware Version:")
}
QGCLabel {
text: QGroundControl.taisyncManager.connected ? QGroundControl.taisyncManager.fwVersion : qsTr("")
}
}
}
}
//-----------------------------------------------------------------
//-- Radio Settings
Item {
width: _panelWidth
height: radioSettingsLabel.height
anchors.margins: ScreenTools.defaultFontPixelWidth
anchors.horizontalCenter: parent.horizontalCenter
visible: _taisyncEnabled && QGroundControl.taisyncManager.linkConnected
QGCLabel {
id: radioSettingsLabel
text: qsTr("Radio Settings")
font.family: ScreenTools.demiboldFontFamily
}
}
Rectangle {
height: radioSettingsCol.height + (ScreenTools.defaultFontPixelHeight * 2)
width: _panelWidth
color: qgcPal.windowShade
visible: _taisyncEnabled && QGroundControl.taisyncManager.linkConnected
anchors.margins: ScreenTools.defaultFontPixelWidth
anchors.horizontalCenter: parent.horizontalCenter
Column {
id: radioSettingsCol
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("Radio Mode:")
Layout.minimumWidth: _labelWidth
}
FactComboBox {
fact: QGroundControl.taisyncManager.radioMode
indexModel: true
enabled: QGroundControl.taisyncManager.linkConnected && !QGroundControl.taisyncManager.needReboot
Layout.minimumWidth: _valueWidth
}
QGCLabel {
text: qsTr("Radio Frequency:")
}
FactComboBox {
fact: QGroundControl.taisyncManager.radioChannel
indexModel: true
enabled: QGroundControl.taisyncManager.linkConnected && QGroundControl.taisyncManager.radioMode.rawValue > 0 && !QGroundControl.taisyncManager.needReboot
Layout.minimumWidth: _valueWidth
}
}
}
}
//-----------------------------------------------------------------
//-- Video Settings
Item {
width: _panelWidth
height: videoSettingsLabel.height
anchors.margins: ScreenTools.defaultFontPixelWidth
anchors.horizontalCenter: parent.horizontalCenter
visible: _taisyncEnabled && QGroundControl.taisyncManager.linkConnected
QGCLabel {
id: videoSettingsLabel
text: qsTr("Video Settings")
font.family: ScreenTools.demiboldFontFamily
}
}
Rectangle {
height: videoSettingsCol.height + (ScreenTools.defaultFontPixelHeight * 2)
width: _panelWidth
color: qgcPal.windowShade
visible: _taisyncEnabled && QGroundControl.taisyncManager.linkConnected
anchors.margins: ScreenTools.defaultFontPixelWidth
anchors.horizontalCenter: parent.horizontalCenter
Column {
id: videoSettingsCol
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("Video Output:")
Layout.minimumWidth: _labelWidth
}
FactComboBox {
fact: QGroundControl.taisyncManager.videoOutput
indexModel: true
enabled: QGroundControl.taisyncManager.linkConnected && !QGroundControl.taisyncManager.needReboot
Layout.minimumWidth: _valueWidth
}
QGCLabel {
text: qsTr("Encoder:")
}
FactComboBox {
fact: QGroundControl.taisyncManager.videoMode
indexModel: true
enabled: QGroundControl.taisyncManager.linkConnected && !QGroundControl.taisyncManager.needReboot
Layout.minimumWidth: _valueWidth
}
QGCLabel {
text: qsTr("Bit Rate:")
}
FactComboBox {
fact: QGroundControl.taisyncManager.videoRate
indexModel: true
enabled: QGroundControl.taisyncManager.linkConnected && !QGroundControl.taisyncManager.needReboot
Layout.minimumWidth: _valueWidth
}
}
}
}
//-----------------------------------------------------------------
//-- RTSP Settings
Item {
width: _panelWidth
height: rtspSettingsLabel.height
anchors.margins: ScreenTools.defaultFontPixelWidth
anchors.horizontalCenter: parent.horizontalCenter
visible: _taisyncEnabled && QGroundControl.taisyncManager.connected
QGCLabel {
id: rtspSettingsLabel
text: qsTr("Streaming Settings")
font.family: ScreenTools.demiboldFontFamily
}
}
Rectangle {
height: rtspSettingsCol.height + (ScreenTools.defaultFontPixelHeight * 2)
width: _panelWidth
color: qgcPal.windowShade
visible: _taisyncEnabled && QGroundControl.taisyncManager.connected
anchors.margins: ScreenTools.defaultFontPixelWidth
anchors.horizontalCenter: parent.horizontalCenter
Column {
id: rtspSettingsCol
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("RTSP URI:")
Layout.minimumWidth: _labelWidth
}
QGCTextField {
id: rtspURI
text: QGroundControl.taisyncManager.rtspURI
enabled: QGroundControl.taisyncManager.connected && !QGroundControl.taisyncManager.needReboot
inputMethodHints: Qt.ImhUrlCharactersOnly
Layout.minimumWidth: _valueWidth
}
QGCLabel {
text: qsTr("Account:")
}
QGCTextField {
id: rtspAccount
text: QGroundControl.taisyncManager.rtspAccount
enabled: QGroundControl.taisyncManager.connected && !QGroundControl.taisyncManager.needReboot
Layout.minimumWidth: _valueWidth
}
QGCLabel {
text: qsTr("Password:")
}
QGCTextField {
id: rtspPassword
text: QGroundControl.taisyncManager.rtspPassword
enabled: QGroundControl.taisyncManager.connected && !QGroundControl.taisyncManager.needReboot
inputMethodHints: Qt.ImhHiddenText
Layout.minimumWidth: _valueWidth
}
}
Item {
width: 1
height: ScreenTools.defaultFontPixelHeight
}
QGCButton {
function testEnabled() {
if(!QGroundControl.taisyncManager.connected)
return false
if(rtspPassword.text === QGroundControl.taisyncManager.rtspPassword &&
rtspAccount.text === QGroundControl.taisyncManager.rtspAccount &&
rtspURI.text === QGroundControl.taisyncManager.rtspURI)
return false
if(rtspURI === "")
return false
return true
}
enabled: testEnabled() && !QGroundControl.taisyncManager.needReboot
text: qsTr("Apply")
anchors.horizontalCenter: parent.horizontalCenter
onClicked: {
setRTSPDialog.open()
}
MessageDialog {
id: setRTSPDialog
icon: StandardIcon.Warning
standardButtons: StandardButton.Yes | StandardButton.No
title: qsTr("Set Streaming Settings")
text: qsTr("Once changed, you will need to reboot the ground unit for the changes to take effect.\n\nConfirm change?")
onYes: {
QGroundControl.taisyncManager.setRTSPSettings(rtspURI.text, rtspAccount.text, rtspPassword.text)
setRTSPDialog.close()
}
onNo: {
setRTSPDialog.close()
}
}
}
}
}
//-----------------------------------------------------------------
//-- IP Settings
Item {
width: _panelWidth
height: ipSettingsLabel.height
anchors.margins: ScreenTools.defaultFontPixelWidth
anchors.horizontalCenter: parent.horizontalCenter
visible: _taisyncEnabled
QGCLabel {
id: ipSettingsLabel
text: qsTr("Network Settings")
font.family: ScreenTools.demiboldFontFamily
}
}
Rectangle {
height: ipSettingsCol.height + (ScreenTools.defaultFontPixelHeight * 2)
width: _panelWidth
color: qgcPal.windowShade
visible: _taisyncEnabled
anchors.margins: ScreenTools.defaultFontPixelWidth
anchors.horizontalCenter: parent.horizontalCenter
Column {
id: ipSettingsCol
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("Local IP Address:")
Layout.minimumWidth: _labelWidth
}
QGCTextField {
id: localIP
text: QGroundControl.taisyncManager.localIPAddr
enabled: !QGroundControl.taisyncManager.needReboot
inputMethodHints: Qt.ImhFormattedNumbersOnly
Layout.minimumWidth: _valueWidth
}
QGCLabel {
text: qsTr("Ground Unit IP Address:")
}
QGCTextField {
id: remoteIP
text: QGroundControl.taisyncManager.remoteIPAddr
enabled: !QGroundControl.taisyncManager.needReboot
inputMethodHints: Qt.ImhFormattedNumbersOnly
Layout.minimumWidth: _valueWidth
}
QGCLabel {
text: qsTr("Network Mask:")
}
QGCTextField {
id: netMask
text: QGroundControl.taisyncManager.netMask
enabled: !QGroundControl.taisyncManager.needReboot
inputMethodHints: Qt.ImhFormattedNumbersOnly
Layout.minimumWidth: _valueWidth
}
}
Item {
width: 1
height: ScreenTools.defaultFontPixelHeight
}
QGCButton {
function validateIPaddress(ipaddress) {
if (/^(25[0-5]|2[0-4][0-9]|[01]?[0-9][0-9]?)\.(25[0-5]|2[0-4][0-9]|[01]?[0-9][0-9]?)\.(25[0-5]|2[0-4][0-9]|[01]?[0-9][0-9]?)\.(25[0-5]|2[0-4][0-9]|[01]?[0-9][0-9]?)$/.test(ipaddress))
return true
return false
}
function testEnabled() {
if(localIP.text === QGroundControl.taisyncManager.localIPAddr &&
remoteIP.text === QGroundControl.taisyncManager.remoteIPAddr &&
netMask.text === QGroundControl.taisyncManager.netMask)
return false
if(!validateIPaddress(localIP.text)) return false
if(!validateIPaddress(remoteIP.text)) return false
if(!validateIPaddress(netMask.text)) return false
return true
}
enabled: testEnabled() && !QGroundControl.taisyncManager.needReboot
text: qsTr("Apply")
anchors.horizontalCenter: parent.horizontalCenter
onClicked: {
setIPDialog.open()
}
MessageDialog {
id: setIPDialog
icon: StandardIcon.Warning
standardButtons: StandardButton.Yes | StandardButton.No
title: qsTr("Set Network Settings")
text: qsTr("Once changed, you will need to reboot the ground unit for the changes to take effect. The local IP address must match the one entered (%1).\n\nConfirm change?").arg(localIP.text)
onYes: {
QGroundControl.taisyncManager.setIPSettings(localIP.text, remoteIP.text, netMask.text)
setIPDialog.close()
}
onNo: {
setIPDialog.close()
}
}
}
}
}
}
}
}
}
/****************************************************************************
*
* (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"
//-----------------------------------------------------------------------------
TaisyncTelemetry::TaisyncTelemetry(QObject* parent)
: TaisyncHandler(parent)
{
}
//-----------------------------------------------------------------------------
bool
TaisyncTelemetry::close()
{
if(TaisyncHandler::close()) {
qCDebug(TaisyncLog) << "Close Taisync Telemetry";
return true;
}
return false;
}
//-----------------------------------------------------------------------------
bool TaisyncTelemetry::start()
{
qCDebug(TaisyncLog) << "Start Taisync Telemetry";
return _start(TAISYNC_TELEM_PORT);
}
//-----------------------------------------------------------------------------
void
TaisyncTelemetry::writeBytes(QByteArray bytes)
{
if(_tcpSocket) {
_tcpSocket->write(bytes);
}
}
//-----------------------------------------------------------------------------
void
TaisyncTelemetry::_newConnection()
{
TaisyncHandler::_newConnection();
qCDebug(TaisyncLog) << "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>
class TaisyncTelemetry : public TaisyncHandler
{
Q_OBJECT
public:
explicit TaisyncTelemetry (QObject* parent = nullptr);
bool close () override;
bool 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"
//-----------------------------------------------------------------------------
TaisyncVideoReceiver::TaisyncVideoReceiver(QObject* parent)
: TaisyncHandler(parent)
{
}
//-----------------------------------------------------------------------------
bool
TaisyncVideoReceiver::close()
{
if(TaisyncHandler::close() || _udpVideoSocket) {
qCDebug(TaisyncLog) << "Close Taisync Video Receiver";
if(_udpVideoSocket) {
_udpVideoSocket->close();
_udpVideoSocket->deleteLater();
_udpVideoSocket = nullptr;
}
return true;
}
return false;
}
//-----------------------------------------------------------------------------
bool
TaisyncVideoReceiver::start()
{
qCDebug(TaisyncLog) << "Start Taisync Video Receiver";
if(_start(TAISYNC_VIDEO_TCP_PORT)) {
_udpVideoSocket = new QUdpSocket(this);
return true;
}
return false;
}
//-----------------------------------------------------------------------------
void
TaisyncVideoReceiver::_readBytes()
{
if(_udpVideoSocket) {
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>
class TaisyncVideoReceiver : public TaisyncHandler
{
Q_OBJECT
public:
explicit TaisyncVideoReceiver (QObject* parent = nullptr);
bool start () override;
bool close () override;
private slots:
void _readBytes () override;
private:
QUdpSocket* _udpVideoSocket = nullptr;
};
......@@ -18,7 +18,9 @@
#include "SettingsManager.h"
#include "QGCApplication.h"
#include "VideoManager.h"
#ifdef QGC_GST_TAISYNC_ENABLED
#include "TaisyncHandler.h"
#endif
#include <QDebug>
#include <QUrl>
#include <QDir>
......@@ -218,6 +220,10 @@ VideoReceiver::_timeout()
void
VideoReceiver::start()
{
qCDebug(VideoReceiverLog) << "start():" << _uri;
if(qgcApp()->runningUnitTests()) {
return;
}
if(!_videoSettings->streamEnabled()->rawValue().toBool() ||
!_videoSettings->streamConfigured()) {
qCDebug(VideoReceiverLog) << "start() but not enabled/configured";
......@@ -227,7 +233,17 @@ VideoReceiver::start()
_stop = false;
qCDebug(VideoReceiverLog) << "start()";
if (_uri.isEmpty()) {
#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;
#endif
bool isUdp = _uri.contains("udp://") && !isTaisyncUSB;
bool isRtsp = _uri.contains("rtsp://") && !isTaisyncUSB;
bool isTCP = _uri.contains("tcp://") && !isTaisyncUSB;
if (!isTaisyncUSB && _uri.isEmpty()) {
qCritical() << "VideoReceiver::start() failed because URI is not specified";
return;
}
......@@ -242,17 +258,13 @@ VideoReceiver::start()
_starting = true;
bool isUdp = _uri.contains("udp://");
bool isRtsp = _uri.contains("rtsp://");
bool isTCP = _uri.contains("tcp://");
//-- For RTSP and TCP, check to see if server is there first
if(!_serverPresent && (isRtsp || isTCP)) {
_timer.start(100);
return;
}
bool running = false;
bool running = false;
bool pipelineUp = false;
GstElement* dataSource = nullptr;
......@@ -269,7 +281,7 @@ VideoReceiver::start()
break;
}
if(isUdp) {
if(isUdp || isTaisyncUSB) {
dataSource = gst_element_factory_make("udpsrc", "udp-source");
} else if(isTCP) {
dataSource = gst_element_factory_make("tcpclientsrc", "tcpclient-source");
......@@ -287,12 +299,18 @@ VideoReceiver::start()
qCritical() << "VideoReceiver::start() failed. Error with gst_caps_from_string()";
break;
}
g_object_set(G_OBJECT(dataSource), "uri", qPrintable(_uri), "caps", caps, nullptr);
g_object_set(static_cast<gpointer>(dataSource), "uri", qPrintable(_uri), "caps", caps, nullptr);
#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;
g_object_set(static_cast<gpointer>(dataSource), "port", TAISYNC_VIDEO_UDP_PORT, nullptr);
#endif
} else if(isTCP) {
QUrl url(_uri);
g_object_set(G_OBJECT(dataSource), "host", qPrintable(url.host()), "port", url.port(), nullptr );
g_object_set(static_cast<gpointer>(dataSource), "host", qPrintable(url.host()), "port", url.port(), nullptr );
} else {
g_object_set(G_OBJECT(dataSource), "location", qPrintable(_uri), "latency", 17, "udp-reconnect", 1, "timeout", _udpReconnect_us, NULL);
g_object_set(static_cast<gpointer>(dataSource), "location", qPrintable(_uri), "latency", 17, "udp-reconnect", 1, "timeout", _udpReconnect_us, NULL);
}
// Currently, we expect H264 when using anything except for TCP. Long term we may want this to be settable
......@@ -302,11 +320,13 @@ VideoReceiver::start()
break;
}
} else {
if ((demux = gst_element_factory_make("rtph264depay", "rtp-h264-depacketizer")) == nullptr) {
if(!isTaisyncUSB) {
if ((demux = gst_element_factory_make("rtph264depay", "rtp-h264-depacketizer")) == nullptr) {
qCritical() << "VideoReceiver::start() failed. Error with gst_element_factory_make('rtph264depay')";
break;
}
}
}
if ((parser = gst_element_factory_make("h264parse", "h264-parser")) == nullptr) {
qCritical() << "VideoReceiver::start() failed. Error with gst_element_factory_make('h264parse')";
......@@ -335,7 +355,11 @@ VideoReceiver::start()
break;
}
gst_bin_add_many(GST_BIN(_pipeline), dataSource, demux, parser, _tee, queue, decoder, queue1, _videoSink, nullptr);
if(isTaisyncUSB) {
gst_bin_add_many(GST_BIN(_pipeline), dataSource, parser, _tee, queue, decoder, queue1, _videoSink, nullptr);
} else {
gst_bin_add_many(GST_BIN(_pipeline), dataSource, demux, parser, _tee, queue, decoder, queue1, _videoSink, nullptr);
}
pipelineUp = true;
if(isUdp) {
......@@ -344,6 +368,12 @@ VideoReceiver::start()
qCritical() << "Unable to link UDP elements.";
break;
}
} else if(isTaisyncUSB) {
// Link the pipeline in front of the tee
if(!gst_element_link_many(dataSource, parser, _tee, queue, decoder, queue1, _videoSink, nullptr)) {
qCritical() << "Unable to link Taisync USB elements.";
break;
}
} else if (isTCP) {
if(!gst_element_link(dataSource, demux)) {
qCritical() << "Unable to link TCP dataSource to Demux.";
......@@ -439,6 +469,9 @@ VideoReceiver::start()
void
VideoReceiver::stop()
{
if(!qgcApp()->runningUnitTests()) {
return;
}
#if defined(QGC_GST_STREAMING)
_stop = true;
qCDebug(VideoReceiverLog) << "stop()";
......@@ -666,7 +699,7 @@ VideoReceiver::startRecording(const QString &videoFile)
}
emit videoFileChanged();
g_object_set(G_OBJECT(_sink->filesink), "location", qPrintable(_videoFile), nullptr);
g_object_set(static_cast<gpointer>(_sink->filesink), "location", qPrintable(_videoFile), nullptr);
qCDebug(VideoReceiverLog) << "New video file:" << _videoFile;
gst_object_ref(_sink->queue);
......
......@@ -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<QmlComponentInfo*>(_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<QmlComponentInfo*>(_p->pTaisync)));
#endif
#if defined(QGC_AIRMAP_ENABLED)
_p->pAirmap = new QmlComponentInfo(tr("AirMap"),
QUrl::fromUserInput("qrc:/qml/AirmapSettings.qml"),
......
......@@ -33,7 +33,7 @@
#define LINK_SETTING_ROOT "LinkConfigurations"
LinkConfiguration::LinkConfiguration(const QString& name)
: _link(NULL)
: _link(nullptr)
, _name(name)
, _dynamic(false)
, _autoConnect(false)
......@@ -80,7 +80,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:
......@@ -118,7 +118,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:
......@@ -147,7 +147,6 @@ LinkConfiguration* LinkConfiguration::duplicateSettings(LinkConfiguration* sourc
break;
#endif
case TypeLast:
default:
break;
}
return dupe;
......
......@@ -49,11 +49,11 @@ LinkManager::LinkManager(QGCApplication* app, QGCToolbox* toolbox)
, _configurationsLoaded(false)
, _connectionsSuspended(false)
, _mavlinkChannelsUsedBitMask(1) // We never use channel 0 to avoid sequence numbering problems
, _autoConnectSettings(NULL)
, _mavlinkProtocol(NULL)
, _autoConnectSettings(nullptr)
, _mavlinkProtocol(nullptr)
#ifndef __mobile__
#ifndef NO_SERIAL_LINK
, _nmeaPort(NULL)
, _nmeaPort(nullptr)
#endif
#endif
{
......@@ -104,11 +104,11 @@ void LinkManager::createConnectedLink(LinkConfiguration* config)
LinkInterface* LinkManager::createConnectedLink(SharedLinkConfigurationPointer& config, bool isPX4Flow)
{
if (!config) {
qWarning() << "LinkManager::createConnectedLink called with NULL config";
return NULL;
qWarning() << "LinkManager::createConnectedLink called with nullptr config";
return nullptr;
}
LinkInterface* pLink = NULL;
LinkInterface* pLink = nullptr;
switch(config->type()) {
#ifndef NO_SERIAL_LINK
case LinkConfiguration::TypeSerial:
......@@ -117,7 +117,7 @@ LinkInterface* LinkManager::createConnectedLink(SharedLinkConfigurationPointer&
if (serialConfig) {
pLink = new SerialLink(config, isPX4Flow);
if (serialConfig->usbDirect()) {
_activeLinkCheckList.append((SerialLink*)pLink);
_activeLinkCheckList.append(dynamic_cast<SerialLink*>(pLink));
if (!_activeLinkCheckTimer.isActive()) {
_activeLinkCheckTimer.start();
}
......@@ -150,15 +150,12 @@ LinkInterface* LinkManager::createConnectedLink(SharedLinkConfigurationPointer&
break;
#endif
case LinkConfiguration::TypeLast:
default:
break;
}
if (pLink) {
_addLink(pLink);
connectLink(pLink);
}
return pLink;
}
......@@ -174,7 +171,7 @@ LinkInterface* LinkManager::createConnectedLink(const QString& name)
}
}
}
return NULL;
return nullptr;
}
void LinkManager::_addLink(LinkInterface* link)
......@@ -289,8 +286,8 @@ SharedLinkInterfacePointer LinkManager::sharedLinkInterfacePointerForLink(LinkIn
}
}
qWarning() << "LinkManager::sharedLinkInterfaceForLink returning NULL";
return SharedLinkInterfacePointer(NULL);
qWarning() << "LinkManager::sharedLinkInterfaceForLink returning nullptr";
return SharedLinkInterfacePointer(nullptr);
}
/// @brief If all new connections should be suspended a message is displayed to the user and true
......@@ -371,42 +368,41 @@ void LinkManager::loadLinkConfigurationList()
QString root(LinkConfiguration::settingsRoot());
root += QString("/Link%1").arg(i);
if(settings.contains(root + "/type")) {
int type = settings.value(root + "/type").toInt();
if((LinkConfiguration::LinkType)type < LinkConfiguration::TypeLast) {
LinkConfiguration::LinkType type = static_cast<LinkConfiguration::LinkType>(settings.value(root + "/type").toInt());
if(type < LinkConfiguration::TypeLast) {
if(settings.contains(root + "/name")) {
QString name = settings.value(root + "/name").toString();
if(!name.isEmpty()) {
LinkConfiguration* pLink = NULL;
LinkConfiguration* pLink = nullptr;
bool autoConnect = settings.value(root + "/auto").toBool();
bool highLatency = settings.value(root + "/high_latency").toBool();
switch((LinkConfiguration::LinkType)type) {
switch(type) {
#ifndef NO_SERIAL_LINK
case LinkConfiguration::TypeSerial:
pLink = (LinkConfiguration*)new SerialConfiguration(name);
pLink = dynamic_cast<LinkConfiguration*>(new SerialConfiguration(name));
break;
#endif
case LinkConfiguration::TypeUdp:
pLink = (LinkConfiguration*)new UDPConfiguration(name);
pLink = dynamic_cast<LinkConfiguration*>(new UDPConfiguration(name));
break;
case LinkConfiguration::TypeTcp:
pLink = (LinkConfiguration*)new TCPConfiguration(name);
pLink = dynamic_cast<LinkConfiguration*>(new TCPConfiguration(name));
break;
#ifdef QGC_ENABLE_BLUETOOTH
case LinkConfiguration::TypeBluetooth:
pLink = (LinkConfiguration*)new BluetoothConfiguration(name);
pLink = dynamic_cast<LinkConfiguration*>(new BluetoothConfiguration(name));
break;
#endif
#ifndef __mobile__
case LinkConfiguration::TypeLogReplay:
pLink = (LinkConfiguration*)new LogReplayLinkConfiguration(name);
pLink = dynamic_cast<LinkConfiguration*>(new LogReplayLinkConfiguration(name));
break;
#endif
#ifdef QT_DEBUG
case LinkConfiguration::TypeMock:
pLink = (LinkConfiguration*)new MockConfiguration(name);
pLink = dynamic_cast<LinkConfiguration*>(new MockConfiguration(name));
break;
#endif
default:
case LinkConfiguration::TypeLast:
break;
}
......@@ -456,7 +452,7 @@ SerialConfiguration* LinkManager::_autoconnectConfigurationsContainsPort(const Q
qWarning() << "Internal error";
}
}
return NULL;
return nullptr;
}
#endif
......@@ -465,10 +461,9 @@ void LinkManager::_updateAutoConnectLinks(void)
if (_connectionsSuspended || qgcApp()->runningUnitTests()) {
return;
}
// Re-add UDP if we need to
bool foundUDP = false;
for (int i=0; i<_sharedLinks.count(); i++) {
for (int i = 0; i < _sharedLinks.count(); i++) {
LinkConfiguration* linkConfig = _sharedLinks[i]->getLinkConfiguration();
if (linkConfig->type() == LinkConfiguration::TypeUdp && linkConfig->name() == _defaultUPDLinkName) {
foundUDP = true;
......@@ -477,7 +472,7 @@ void LinkManager::_updateAutoConnectLinks(void)
}
if (!foundUDP && _autoConnectSettings->autoConnectUDP()->rawValue().toBool()) {
qCDebug(LinkManagerLog) << "New auto-connect UDP port added";
// Default UDPConfiguration is set up for autoconnect
//-- Default UDPConfiguration is set up for autoconnect
UDPConfiguration* udpConfig = new UDPConfiguration(_defaultUPDLinkName);
udpConfig->setDynamic(true);
SharedLinkConfigurationPointer config = addConfiguration(udpConfig);
......@@ -488,7 +483,6 @@ void LinkManager::_updateAutoConnectLinks(void)
#ifndef NO_SERIAL_LINK
QStringList currentPorts;
QList<QGCSerialPortInfo> portList;
#ifdef __android__
// Android builds only support a single serial connection. Repeatedly calling availablePorts after that one serial
// port is connected leaks file handles due to a bug somewhere in android serial code. In order to work around that
......@@ -524,22 +518,18 @@ void LinkManager::_updateAutoConnectLinks(void)
_nmeaDeviceName = portInfo.systemLocation().trimmed();
qCDebug(LinkManagerLog) << "Configuring nmea port" << _nmeaDeviceName;
QSerialPort* newPort = new QSerialPort(portInfo);
_nmeaBaud = _autoConnectSettings->autoConnectNmeaBaud()->cookedValue().toUInt();
newPort->setBaudRate(_nmeaBaud);
newPort->setBaudRate(static_cast<qint32>(_nmeaBaud));
qCDebug(LinkManagerLog) << "Configuring nmea baudrate" << _nmeaBaud;
// This will stop polling old device if previously set
_toolbox->qgcPositionManager()->setNmeaSourceDevice(newPort);
if (_nmeaPort) {
delete _nmeaPort;
}
_nmeaPort = newPort;
} else if (_autoConnectSettings->autoConnectNmeaBaud()->cookedValue().toUInt() != _nmeaBaud) {
_nmeaBaud = _autoConnectSettings->autoConnectNmeaBaud()->cookedValue().toUInt();
_nmeaPort->setBaudRate(_nmeaBaud);
_nmeaPort->setBaudRate(static_cast<qint32>(_nmeaBaud));
qCDebug(LinkManagerLog) << "Configuring nmea baudrate" << _nmeaBaud;
}
} else
......@@ -551,7 +541,6 @@ void LinkManager::_updateAutoConnectLinks(void)
qCDebug(LinkManagerLog) << "Waiting for bootloader to finish" << portInfo.systemLocation();
continue;
}
if (_autoconnectConfigurationsContainsPort(portInfo.systemLocation()) || _autoConnectRTKPort == portInfo.systemLocation()) {
qCDebug(LinkManagerVerboseLog) << "Skipping existing autoconnect" << portInfo.systemLocation();
} else if (!_autoconnectWaitList.contains(portInfo.systemLocation())) {
......@@ -561,10 +550,8 @@ void LinkManager::_updateAutoConnectLinks(void)
qCDebug(LinkManagerLog) << "Waiting for next autoconnect pass" << portInfo.systemLocation();
_autoconnectWaitList[portInfo.systemLocation()] = 1;
} else if (++_autoconnectWaitList[portInfo.systemLocation()] * _autoconnectUpdateTimerMSecs > _autoconnectConnectDelayMSecs) {
SerialConfiguration* pSerialConfig = NULL;
SerialConfiguration* pSerialConfig = nullptr;
_autoconnectWaitList.remove(portInfo.systemLocation());
switch (boardType) {
case QGCSerialPortInfo::BoardTypePixhawk:
if (_autoConnectSettings->autoConnectPixhawk()->rawValue().toBool()) {
......@@ -600,7 +587,6 @@ void LinkManager::_updateAutoConnectLinks(void)
qWarning() << "Internal error";
continue;
}
if (pSerialConfig) {
qCDebug(LinkManagerLog) << "New auto-connect port added: " << pSerialConfig->name() << portInfo.systemLocation();
pSerialConfig->setBaud(boardType == QGCSerialPortInfo::BoardTypeSiKRadio ? 57600 : 115200);
......@@ -616,7 +602,7 @@ void LinkManager::_updateAutoConnectLinks(void)
#ifndef __android__
// Android builds only support a single serial connection. Repeatedly calling availablePorts after that one serial
// port is connected leaks file handles due to a bug somewhere in android serial code. In order to work around that
// bug after we connect the first serial port we stop probing for additional ports. The means we must rely on
// bug after we connect the first serial port we stop probing for additional ports. That means we must rely on
// the port disconnecting itself when the radio is pulled to signal communication list as opposed to automatically
// closing the Link.
......@@ -683,20 +669,20 @@ QStringList LinkManager::linkTypeStrings(void) const
if(!list.size())
{
#ifndef NO_SERIAL_LINK
list += "Serial";
list += tr("Serial");
#endif
list += "UDP";
list += "TCP";
list += tr("UDP");
list += tr("TCP");
#ifdef QGC_ENABLE_BLUETOOTH
list += "Bluetooth";
#endif
#ifdef QT_DEBUG
list += "Mock Link";
list += tr("Mock Link");
#endif
#ifndef __mobile__
list += "Log Replay";
list += tr("Log Replay");
#endif
if (list.size() != (int)LinkConfiguration::TypeLast) {
if (list.size() != static_cast<int>(LinkConfiguration::TypeLast)) {
qWarning() << "Internal error";
}
}
......@@ -777,7 +763,7 @@ bool LinkManager::endCreateConfiguration(LinkConfiguration* config)
LinkConfiguration* LinkManager::createConfiguration(int type, const QString& name)
{
#ifndef NO_SERIAL_LINK
if((LinkConfiguration::LinkType)type == LinkConfiguration::TypeSerial)
if(static_cast<LinkConfiguration::LinkType>(type) == LinkConfiguration::TypeSerial)
_updateSerialPorts();
#endif
return LinkConfiguration::createSettings(type, name);
......@@ -793,11 +779,10 @@ LinkConfiguration* LinkManager::startConfigurationEditing(LinkConfiguration* con
return LinkConfiguration::duplicateSettings(config);
} else {
qWarning() << "Internal error";
return NULL;
return nullptr;
}
}
void LinkManager::_fixUnnamed(LinkConfiguration* config)
{
if (config) {
......@@ -819,13 +804,13 @@ void LinkManager::_fixUnnamed(LinkConfiguration* config)
#endif
case LinkConfiguration::TypeUdp:
config->setName(
QString("UDP Link on Port %1").arg(dynamic_cast<UDPConfiguration*>(config)->localPort()));
QString("UDP Link on Port %1").arg(dynamic_cast<UDPConfiguration*>(config)->localPort()));
break;
case LinkConfiguration::TypeTcp: {
TCPConfiguration* tconfig = dynamic_cast<TCPConfiguration*>(config);
if(tconfig) {
config->setName(
QString("TCP Link %1:%2").arg(tconfig->address().toString()).arg((int)tconfig->port()));
QString("TCP Link %1:%2").arg(tconfig->address().toString()).arg(static_cast<int>(tconfig->port())));
}
}
break;
......@@ -849,12 +834,10 @@ void LinkManager::_fixUnnamed(LinkConfiguration* config)
#endif
#ifdef QT_DEBUG
case LinkConfiguration::TypeMock:
config->setName(
QString("Mock Link"));
config->setName(QString("Mock Link"));
break;
#endif
case LinkConfiguration::TypeLast:
default:
break;
}
}
......@@ -896,9 +879,8 @@ bool LinkManager::isBluetoothAvailable(void)
#ifndef NO_SERIAL_LINK
void LinkManager::_activeLinkCheck(void)
{
SerialLink* link = NULL;
SerialLink* link = nullptr;
bool found = false;
if (_activeLinkCheckList.count() != 0) {
link = _activeLinkCheckList.takeFirst();
if (containsLink(link) && link->isConnected()) {
......@@ -912,14 +894,12 @@ void LinkManager::_activeLinkCheck(void)
}
}
} else {
link = NULL;
link = nullptr;
}
}
if (_activeLinkCheckList.count() == 0) {
_activeLinkCheckTimer.stop();
}
if (!found && link) {
// See if we can get an NSH prompt on this link
bool foundNSHPrompt = false;
......@@ -931,10 +911,10 @@ void LinkManager::_activeLinkCheck(void)
foundNSHPrompt = true;
}
}
qgcApp()->showMessage(foundNSHPrompt ?
tr("Please check to make sure you have an SD Card inserted in your Vehicle and try again.") :
tr("Your Vehicle is not responding. If this continues, shutdown %1, restart the Vehicle letting it boot completely, then start %1.").arg(qgcApp()->applicationName()));
qgcApp()->showMessage(
foundNSHPrompt ?
tr("Please check to make sure you have an SD Card inserted in your Vehicle and try again.") :
tr("Your Vehicle is not responding. If this continues, shutdown %1, restart the Vehicle letting it boot completely, then start %1.").arg(qgcApp()->applicationName()));
}
}
#endif
......@@ -959,32 +939,27 @@ SharedLinkConfigurationPointer LinkManager::addConfiguration(LinkConfiguration*
void LinkManager::_removeConfiguration(LinkConfiguration* config)
{
_qmlConfigurations.removeOne(config);
for (int i=0; i<_sharedConfigurations.count(); i++) {
if (_sharedConfigurations[i].data() == config) {
_sharedConfigurations.removeAt(i);
return;
}
}
qWarning() << "LinkManager::_removeConfiguration called with unknown config";
}
QList<LinkInterface*> LinkManager::links(void)
{
QList<LinkInterface*> rawLinks;
for (int i=0; i<_sharedLinks.count(); i++) {
rawLinks.append(_sharedLinks[i].data());
}
return rawLinks;
}
void LinkManager::startAutoConnectedLinks(void)
{
SharedLinkConfigurationPointer conf;
for(int i = 0; i < _sharedConfigurations.count(); i++) {
conf = _sharedConfigurations[i];
if (conf->isAutoConnect())
......@@ -995,7 +970,7 @@ void LinkManager::startAutoConnectedLinks(void)
int LinkManager::_reserveMavlinkChannel(void)
{
// Find a mavlink channel to use for this link, Channel 0 is reserved for internal use.
for (int mavlinkChannel=1; mavlinkChannel<32; mavlinkChannel++) {
for (uint8_t mavlinkChannel = 1; mavlinkChannel < 32; mavlinkChannel++) {
if (!(_mavlinkChannelsUsedBitMask & 1 << mavlinkChannel)) {
mavlink_reset_channel_status(mavlinkChannel);
// Start the channel on Mav 1 protocol
......@@ -1005,7 +980,6 @@ int LinkManager::_reserveMavlinkChannel(void)
return mavlinkChannel;
}
}
return 0; // All channels reserved
}
......
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