34 changed files with 2200 additions and 266 deletions
@ -0,0 +1,107 @@
@@ -0,0 +1,107 @@
|
||||
/****************************************************************************
|
||||
* |
||||
* (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(); |
||||
} |
@ -0,0 +1,57 @@
@@ -0,0 +1,57 @@
|
||||
/****************************************************************************
|
||||
* |
||||
* (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; |
||||
}; |
@ -0,0 +1,600 @@
@@ -0,0 +1,600 @@
|
||||
/****************************************************************************
|
||||
* |
||||
* (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(); |
||||
} |
||||
} |
||||
} |
@ -0,0 +1,172 @@
@@ -0,0 +1,172 @@
|
||||
/****************************************************************************
|
||||
* |
||||
* (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; |
||||
}; |
@ -0,0 +1,175 @@
@@ -0,0 +1,175 @@
|
||||
/****************************************************************************
|
||||
* |
||||
* (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('{'); |
||||
} |
||||
} |
||||
} |
||||
|
@ -0,0 +1,41 @@
@@ -0,0 +1,41 @@
|
||||
/****************************************************************************
|
||||
* |
||||
* (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); |
||||
}; |
@ -0,0 +1,543 @@
@@ -0,0 +1,543 @@
|
||||
/**************************************************************************** |
||||
* |
||||
* (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() |
||||
} |
||||
} |
||||
} |
||||
} |
||||
} |
||||
} |
||||
} |
||||
} |
||||
} |
@ -0,0 +1,64 @@
@@ -0,0 +1,64 @@
|
||||
/****************************************************************************
|
||||
* |
||||
* (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); |
||||
} |
||||
} |
@ -0,0 +1,33 @@
@@ -0,0 +1,33 @@
|
||||
/****************************************************************************
|
||||
* |
||||
* (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; |
||||
|
||||
}; |
@ -0,0 +1,57 @@
@@ -0,0 +1,57 @@
|
||||
/****************************************************************************
|
||||
* |
||||
* (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); |
||||
} |
||||
} |
@ -0,0 +1,29 @@
@@ -0,0 +1,29 @@
|
||||
/****************************************************************************
|
||||
* |
||||
* (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; |
||||
}; |
Loading…
Reference in new issue