Commit 8bc0c95c authored by Matej Frančeškin's avatar Matej Frančeškin

Microhard - removed unneeded settings

parent 4c989f93
/**************************************************************************** /****************************************************************************
* *
* (c) 2009-2016 QGROUNDCONTROL PROJECT <http://www.qgroundcontrol.org> * (c) 2019 QGROUNDCONTROL PROJECT <http://www.qgroundcontrol.org>
* *
* QGroundControl is licensed according to the terms in the file * QGroundControl is licensed according to the terms in the file
* COPYING.md in the root of the source code directory. * COPYING.md in the root of the source code directory.
...@@ -12,7 +12,6 @@ ...@@ -12,7 +12,6 @@
#include "QGCApplication.h" #include "QGCApplication.h"
#include "VideoManager.h" #include "VideoManager.h"
QGC_LOGGING_CATEGORY(MicrohardLog, "MicrohardLog") QGC_LOGGING_CATEGORY(MicrohardLog, "MicrohardLog")
QGC_LOGGING_CATEGORY(MicrohardVerbose, "MicrohardVerbose") QGC_LOGGING_CATEGORY(MicrohardVerbose, "MicrohardVerbose")
...@@ -29,20 +28,16 @@ MicrohardHandler::~MicrohardHandler() ...@@ -29,20 +28,16 @@ MicrohardHandler::~MicrohardHandler()
} }
//----------------------------------------------------------------------------- //-----------------------------------------------------------------------------
bool MicrohardHandler::close() bool
MicrohardHandler::close()
{ {
bool res = (_tcpSocket || _tcpServer); bool res = false;
if(_tcpSocket) { if(_tcpSocket) {
qCDebug(MicrohardLog) << "Close Microhard TCP socket on port" << _tcpSocket->localPort(); qCDebug(MicrohardLog) << "Close Microhard TCP socket on port" << _tcpSocket->localPort();
_tcpSocket->close(); _tcpSocket->close();
_tcpSocket->deleteLater(); _tcpSocket->deleteLater();
_tcpSocket = nullptr; _tcpSocket = nullptr;
} res = true;
if(_tcpServer) {
qCDebug(MicrohardLog) << "Close Microhard TCP server on port" << _tcpServer->serverPort();;
_tcpServer->close();
_tcpServer->deleteLater();
_tcpServer = nullptr;
} }
return res; return res;
} }
...@@ -52,53 +47,26 @@ bool ...@@ -52,53 +47,26 @@ bool
MicrohardHandler::_start(uint16_t port, QHostAddress addr) MicrohardHandler::_start(uint16_t port, QHostAddress addr)
{ {
close(); close();
_serverMode = addr == QHostAddress::AnyIPv4;
if(_serverMode) {
if(!_tcpServer) {
qCDebug(MicrohardLog) << "Listen for Microhard TCP on port" << port;
_tcpServer = new QTcpServer(this);
QObject::connect(_tcpServer, &QTcpServer::newConnection, this, &MicrohardHandler::_newConnection);
_tcpServer->listen(QHostAddress::AnyIPv4, port);
}
} else {
_tcpSocket = new QTcpSocket();
QObject::connect(_tcpSocket, &QIODevice::readyRead, this, &MicrohardHandler::_readBytes);
qCDebug(MicrohardLog) << "Connecting to" << addr;
_tcpSocket->connectToHost(addr, port);
if (!_tcpSocket->waitForConnected(1000)) {
close();
return false;
}
emit connected();
}
return true;
}
//----------------------------------------------------------------------------- _tcpSocket = new QTcpSocket();
void QObject::connect(_tcpSocket, &QIODevice::readyRead, this, &MicrohardHandler::_readBytes);
MicrohardHandler::_newConnection() qCDebug(MicrohardLog) << "Connecting to" << addr;
{ _tcpSocket->connectToHost(addr, port);
qCDebug(MicrohardLog) << "New Microhard TCP Connection on port" << _tcpServer->serverPort(); if (!_tcpSocket->waitForConnected(1000)) {
if(_tcpSocket) { close();
_tcpSocket->close(); return false;
_tcpSocket->deleteLater();
}
_tcpSocket = _tcpServer->nextPendingConnection();
if(_tcpSocket) {
QObject::connect(_tcpSocket, &QIODevice::readyRead, this, &MicrohardHandler::_readBytes);
QObject::connect(_tcpSocket, &QAbstractSocket::disconnected, this, &MicrohardHandler::_socketDisconnected);
emit connected();
} else {
qCWarning(MicrohardLog) << "New Microhard TCP Connection provided no socket";
} }
emit connected();
return true;
} }
//----------------------------------------------------------------------------- //-----------------------------------------------------------------------------
void void
MicrohardHandler::_socketDisconnected() MicrohardHandler::_socketDisconnected()
{ {
qCDebug(MicrohardLog) << "Microhard TCP Connection Closed on port" << _tcpSocket->localPort();
if(_tcpSocket) { if(_tcpSocket) {
qCDebug(MicrohardLog) << "Microhard TCP Connection Closed on port" << _tcpSocket->localPort();
_tcpSocket->close(); _tcpSocket->close();
_tcpSocket->deleteLater(); _tcpSocket->deleteLater();
_tcpSocket = nullptr; _tcpSocket = nullptr;
......
/**************************************************************************** /****************************************************************************
* *
* (c) 2009-2016 QGROUNDCONTROL PROJECT <http://www.qgroundcontrol.org> * (c) 2019 QGROUNDCONTROL PROJECT <http://www.qgroundcontrol.org>
* *
* QGroundControl is licensed according to the terms in the file * QGroundControl is licensed according to the terms in the file
* COPYING.md in the root of the source code directory. * COPYING.md in the root of the source code directory.
...@@ -11,7 +11,7 @@ ...@@ -11,7 +11,7 @@
#include "QGCLoggingCategory.h" #include "QGCLoggingCategory.h"
#include <QTcpServer> #include <QHostAddress>
#include <QTcpSocket> #include <QTcpSocket>
#define MICROHARD_SETTINGS_PORT 23 #define MICROHARD_SETTINGS_PORT 23
...@@ -28,13 +28,11 @@ public: ...@@ -28,13 +28,11 @@ public:
~MicrohardHandler (); ~MicrohardHandler ();
virtual bool start () = 0; virtual bool start () = 0;
virtual bool close (); virtual bool close ();
virtual bool isServerRunning () { return (_serverMode && _tcpServer); }
protected: protected:
virtual bool _start (uint16_t port, QHostAddress addr = QHostAddress::AnyIPv4); virtual bool _start (uint16_t port, QHostAddress addr = QHostAddress::AnyIPv4);
protected slots: protected slots:
virtual void _newConnection ();
virtual void _socketDisconnected (); virtual void _socketDisconnected ();
virtual void _readBytes () = 0; virtual void _readBytes () = 0;
...@@ -43,7 +41,5 @@ signals: ...@@ -43,7 +41,5 @@ signals:
void disconnected (); void disconnected ();
protected: protected:
bool _serverMode = true;
QTcpServer* _tcpServer = nullptr;
QTcpSocket* _tcpSocket = nullptr; QTcpSocket* _tcpSocket = nullptr;
}; };
/**************************************************************************** /****************************************************************************
* *
* (c) 2009-2016 QGROUNDCONTROL PROJECT <http://www.qgroundcontrol.org> * (c) 2019 QGROUNDCONTROL PROJECT <http://www.qgroundcontrol.org>
* *
* QGroundControl is licensed according to the terms in the file * QGroundControl is licensed according to the terms in the file
* COPYING.md in the root of the source code directory. * COPYING.md in the root of the source code directory.
...@@ -8,26 +8,18 @@ ...@@ -8,26 +8,18 @@
****************************************************************************/ ****************************************************************************/
#include "MicrohardManager.h" #include "MicrohardManager.h"
#include "MicrohardHandler.h" #include "MicrohardSettings.h"
#include "SettingsManager.h" #include "SettingsManager.h"
#include "QGCApplication.h" #include "QGCApplication.h"
#include "QGCCorePlugin.h" #include "QGCCorePlugin.h"
#include "VideoManager.h"
#include <QSettings> #include <QSettings>
static const char *kMICROHARD_GROUP = "Microhard"; static const char *kMICROHARD_GROUP = "Microhard";
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 *kLOCAL_IP = "LocalIP";
static const char *kREMOTE_IP = "RemoteIP"; static const char *kREMOTE_IP = "RemoteIP";
static const char *kNET_MASK = "NetMask"; static const char *kNET_MASK = "NetMask";
static const char *kRTSP_URI = "RTSPURI"; static const char *kCFG_PASSWORD = "ConfigPassword";
static const char *kRTSP_ACCOUNT = "RTSPAccount";
static const char *kRTSP_PASSWORD = "RTSPPassword";
//----------------------------------------------------------------------------- //-----------------------------------------------------------------------------
MicrohardManager::MicrohardManager(QGCApplication* app, QGCToolbox* toolbox) MicrohardManager::MicrohardManager(QGCApplication* app, QGCToolbox* toolbox)
...@@ -37,12 +29,10 @@ MicrohardManager::MicrohardManager(QGCApplication* app, QGCToolbox* toolbox) ...@@ -37,12 +29,10 @@ MicrohardManager::MicrohardManager(QGCApplication* app, QGCToolbox* toolbox)
_workTimer.setSingleShot(true); _workTimer.setSingleShot(true);
QSettings settings; QSettings settings;
settings.beginGroup(kMICROHARD_GROUP); settings.beginGroup(kMICROHARD_GROUP);
_localIPAddr = settings.value(kLOCAL_IP, QString("192.168.199.33")).toString(); _localIPAddr = settings.value(kLOCAL_IP, QString("192.168.168.1")).toString();
_remoteIPAddr = settings.value(kREMOTE_IP, QString("192.168.199.16")).toString(); _remoteIPAddr = settings.value(kREMOTE_IP, QString("192.168.168.2")).toString();
_netMask = settings.value(kNET_MASK, QString("255.255.255.0")).toString(); _netMask = settings.value(kNET_MASK, QString("255.255.255.0")).toString();
_rtspURI = settings.value(kRTSP_URI, QString("rtsp://192.168.0.2")).toString(); _configPassword = settings.value(kCFG_PASSWORD, QString("admin")).toString();
_rtspAccount = settings.value(kRTSP_ACCOUNT, QString("admin")).toString();
_rtspPassword = settings.value(kRTSP_PASSWORD, QString("12345678")).toString();
settings.endGroup(); settings.endGroup();
} }
...@@ -74,8 +64,7 @@ MicrohardManager::_reset() ...@@ -74,8 +64,7 @@ MicrohardManager::_reset()
emit linkConnectedChanged(); emit linkConnectedChanged();
if(!_appSettings) { if(!_appSettings) {
_appSettings = _toolbox->settingsManager()->appSettings(); _appSettings = _toolbox->settingsManager()->appSettings();
connect(_appSettings->enableMicrohard(), &Fact::rawValueChanged, this, &MicrohardManager::_setEnabled); connect(_appSettings->enableMicrohard(), &Fact::rawValueChanged, this, &MicrohardManager::_setEnabled);
connect(_appSettings->enableMicrohardVideo(), &Fact::rawValueChanged, this, &MicrohardManager::_setVideoEnabled);
} }
_setEnabled(); _setEnabled();
} }
...@@ -104,95 +93,10 @@ void ...@@ -104,95 +93,10 @@ void
MicrohardManager::setToolbox(QGCToolbox* toolbox) MicrohardManager::setToolbox(QGCToolbox* toolbox)
{ {
QGCTool::setToolbox(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(kMICROHARD_GROUP, metaData, this);
QQmlEngine::setObjectOwnership(_radioMode, QQmlEngine::CppOwnership);
_radioModeList.append("auto");
_radioModeList.append("manual");
connect(_radioMode, &Fact::_containerRawValueChanged, this, &MicrohardManager::_radioSettingsChanged);
}
{
//-- Radio Channel
QStringList enums;
for(int i = 0; i < 14; i++) {
enums.append(QString("ch%1").arg(i));
}
FactMetaData* metaData = _createMetadata(kRADIO_CHANNEL, enums);
_radioChannel = new Fact(kMICROHARD_GROUP, metaData, this);
QQmlEngine::setObjectOwnership(_radioChannel, QQmlEngine::CppOwnership);
connect(_radioChannel, &Fact::_containerRawValueChanged, this, &MicrohardManager::_radioSettingsChanged);
}
{
//-- Video Output
QStringList enums;
enums.append(tr("Stream"));
enums.append(tr("HDMI Port"));
FactMetaData* metaData = _createMetadata(kVIDEO_OUTPUT, enums);
_videoOutput = new Fact(kMICROHARD_GROUP, metaData, this);
QQmlEngine::setObjectOwnership(_videoOutput, QQmlEngine::CppOwnership);
_videoOutputList.append("phone");
_videoOutputList.append("hdmi");
connect(_videoOutput, &Fact::_containerRawValueChanged, this, &MicrohardManager::_videoSettingsChanged);
}
{
//-- Video Mode
QStringList enums;
enums.append("H264");
enums.append("H265");
FactMetaData* metaData = _createMetadata(kVIDEO_MODE, enums);
_videoMode = new Fact(kMICROHARD_GROUP, metaData, this);
QQmlEngine::setObjectOwnership(_videoMode, QQmlEngine::CppOwnership);
connect(_videoMode, &Fact::_containerRawValueChanged, this, &MicrohardManager::_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(kMICROHARD_GROUP, metaData, this);
QQmlEngine::setObjectOwnership(_videoRate, QQmlEngine::CppOwnership);
_videoRateList.append("low");
_videoRateList.append("middle");
_videoRateList.append("high");
connect(_videoRate, &Fact::_containerRawValueChanged, this, &MicrohardManager::_videoSettingsChanged);
}
//-- Start it all //-- Start it all
_reset(); _reset();
} }
//-----------------------------------------------------------------------------
bool
MicrohardManager::setRTSPSettings(QString uri, QString account, QString password)
{
if(_mhSettings && _isConnected) {
if(_mhSettings->setRTSPSettings(uri, account, password)) {
_rtspURI = uri;
_rtspAccount = account;
_rtspPassword = password;
QSettings settings;
settings.beginGroup(kMICROHARD_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 bool
MicrohardManager::setIPSettings(QString localIP_, QString remoteIP_, QString netMask_) MicrohardManager::setIPSettings(QString localIP_, QString remoteIP_, QString netMask_)
...@@ -232,35 +136,6 @@ MicrohardManager::setIPSettings(QString localIP_, QString remoteIP_, QString net ...@@ -232,35 +136,6 @@ MicrohardManager::setIPSettings(QString localIP_, QString remoteIP_, QString net
return res; return res;
} }
//-----------------------------------------------------------------------------
void
MicrohardManager::_radioSettingsChanged(QVariant)
{
if(_mhSettings && _isConnected) {
_workTimer.stop();
_mhSettings->setRadioSettings(
_radioModeList[_radioMode->rawValue().toInt()],
_radioChannel->enumStringValue());
_reqMask |= REQ_RADIO_SETTINGS;
_workTimer.start(3000);
}
}
//-----------------------------------------------------------------------------
void
MicrohardManager::_videoSettingsChanged(QVariant)
{
if(_mhSettings && _isConnected) {
_workTimer.stop();
_mhSettings->setVideoSettings(
_videoOutputList[_videoOutput->rawValue().toInt()],
_videoMode->enumStringValue(),
_videoRateList[_videoRate->rawValue().toInt()]);
_reqMask |= REQ_VIDEO_SETTINGS;
_workTimer.start(500);
}
}
//----------------------------------------------------------------------------- //-----------------------------------------------------------------------------
void void
MicrohardManager::_setEnabled() MicrohardManager::_setEnabled()
...@@ -281,43 +156,6 @@ MicrohardManager::_setEnabled() ...@@ -281,43 +156,6 @@ MicrohardManager::_setEnabled()
_close(); _close();
} }
_enabled = enable; _enabled = enable;
//-- Now handle video support
_setVideoEnabled();
}
//-----------------------------------------------------------------------------
void
MicrohardManager::_restoreVideoSettings(Fact* setting)
{
SettingsFact* pFact = dynamic_cast<SettingsFact*>(setting);
if(pFact) {
pFact->setVisible(qgcApp()->toolbox()->corePlugin()->adjustSettingMetaData(VideoSettings::settingsGroup, *setting->metaData()));
}
}
//-----------------------------------------------------------------------------
void
MicrohardManager::_setVideoEnabled()
{
//-- Check both if video is enabled and Microhard support itself is enabled as well.
bool enable = _appSettings->enableMicrohardVideo()->rawValue().toBool() && _appSettings->enableMicrohard()->rawValue().toBool();
if(enable) {
//-- Set it up the way we need it do be.
VideoSettings* pVSettings = qgcApp()->toolbox()->settingsManager()->videoSettings();
pVSettings->setVisible(false);
pVSettings->udpPort()->setRawValue(5600);
//-- TODO: this AR must come from somewhere
pVSettings->aspectRatio()->setRawValue(1024.0 / 768.0);
pVSettings->videoSource()->setRawValue(QString(VideoSettings::videoSourceUDP));
} else {
//-- Restore video settings.
VideoSettings* pVSettings = qgcApp()->toolbox()->settingsManager()->videoSettings();
_restoreVideoSettings(pVSettings->videoSource());
_restoreVideoSettings(pVSettings->aspectRatio());
_restoreVideoSettings(pVSettings->udpPort());
pVSettings->setVisible(true);
}
_enableVideo = enable;
} }
//----------------------------------------------------------------------------- //-----------------------------------------------------------------------------
...@@ -352,9 +190,7 @@ MicrohardManager::_checkMicrohard() ...@@ -352,9 +190,7 @@ MicrohardManager::_checkMicrohard()
if(_enabled) { if(_enabled) {
if(!_isConnected) { if(!_isConnected) {
if(_mhSettings) { if(_mhSettings) {
if(!_mhSettings->isServerRunning()) { _mhSettings->start();
_mhSettings->start();
}
} }
} else { } else {
//qCDebug(MicrohardVerbose) << bin << _reqMask; //qCDebug(MicrohardVerbose) << bin << _reqMask;
...@@ -363,33 +199,6 @@ MicrohardManager::_checkMicrohard() ...@@ -363,33 +199,6 @@ MicrohardManager::_checkMicrohard()
_mhSettings->requestLinkStatus(); _mhSettings->requestLinkStatus();
break; break;
} }
if (_reqMask & REQ_DEV_INFO) {
_mhSettings->requestDevInfo();
break;
}
if (_reqMask & REQ_FREQ_SCAN) {
_reqMask &= ~static_cast<uint32_t>(REQ_FREQ_SCAN);
_mhSettings->requestFreqScan();
break;
}
if (_reqMask & REQ_VIDEO_SETTINGS) {
_mhSettings->requestVideoSettings();
break;
}
if (_reqMask & REQ_RADIO_SETTINGS) {
_mhSettings->requestRadioSettings();
break;
}
if (_reqMask & REQ_RTSP_SETTINGS) {
_reqMask &= ~static_cast<uint32_t>(REQ_RTSP_SETTINGS);
_mhSettings->requestRTSPURISettings();
break;
}
if (_reqMask & REQ_IP_SETTINGS) {
_reqMask &= ~static_cast<uint32_t>(REQ_IP_SETTINGS);
_mhSettings->requestIPSettings();
break;
}
//-- Check link status //-- Check link status
if(_timeoutTimer.elapsed() > 3000) { if(_timeoutTimer.elapsed() > 3000) {
//-- Give up and restart //-- Give up and restart
...@@ -429,44 +238,13 @@ MicrohardManager::_updateSettings(QByteArray jSonData) ...@@ -429,44 +238,13 @@ MicrohardManager::_updateSettings(QByteArray jSonData)
_linkConnected = tlinkConnected; _linkConnected = tlinkConnected;
emit linkConnectedChanged(); emit linkConnectedChanged();
} }
QString tlinkVidFormat = jObj["videoformat"].toString(_linkVidFormat);
int tdownlinkRSSI = jObj["radiorssi"].toInt(_downlinkRSSI); int tdownlinkRSSI = jObj["radiorssi"].toInt(_downlinkRSSI);
int tuplinkRSSI = jObj["hdrssi"].toInt(_uplinkRSSI); int tuplinkRSSI = jObj["hdrssi"].toInt(_uplinkRSSI);
if(_linkVidFormat != tlinkVidFormat || _downlinkRSSI != tdownlinkRSSI || _uplinkRSSI != tuplinkRSSI) { if(_downlinkRSSI != tdownlinkRSSI || _uplinkRSSI != tuplinkRSSI) {
_linkVidFormat = tlinkVidFormat;
_downlinkRSSI = tdownlinkRSSI; _downlinkRSSI = tdownlinkRSSI;
_uplinkRSSI = tuplinkRSSI; _uplinkRSSI = tuplinkRSSI;
emit linkChanged(); 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? //-- IP Address Settings?
} else if(jSonData.contains("\"usbEthIp\":")) { } else if(jSonData.contains("\"usbEthIp\":")) {
QString value; QString value;
...@@ -492,39 +270,10 @@ MicrohardManager::_updateSettings(QByteArray jSonData) ...@@ -492,39 +270,10 @@ MicrohardManager::_updateSettings(QByteArray jSonData)
if(changed) { if(changed) {
QSettings settings; QSettings settings;
settings.beginGroup(kMICROHARD_GROUP); settings.beginGroup(kMICROHARD_GROUP);
settings.setValue(kLOCAL_IP, _localIPAddr); settings.setValue(kLOCAL_IP, _localIPAddr);
settings.setValue(kREMOTE_IP, _remoteIPAddr); settings.setValue(kREMOTE_IP, _remoteIPAddr);
settings.setValue(kNET_MASK, _netMask); settings.setValue(kNET_MASK, _netMask);
settings.endGroup(); settings.setValue(kCFG_PASSWORD, _configPassword);
}
//-- 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(kMICROHARD_GROUP);
settings.setValue(kRTSP_URI, _rtspURI);
settings.setValue(kRTSP_ACCOUNT, _rtspAccount);
settings.setValue(kRTSP_PASSWORD, _rtspPassword);
settings.endGroup(); settings.endGroup();
} }
} }
......
/**************************************************************************** /****************************************************************************
* *
* (c) 2009-2016 QGROUNDCONTROL PROJECT <http://www.qgroundcontrol.org> * (c) 2019 QGROUNDCONTROL PROJECT <http://www.qgroundcontrol.org>
* *
* QGroundControl is licensed according to the terms in the file * QGroundControl is licensed according to the terms in the file
* COPYING.md in the root of the source code directory. * COPYING.md in the root of the source code directory.
...@@ -29,24 +29,13 @@ public: ...@@ -29,24 +29,13 @@ public:
Q_PROPERTY(bool connected READ connected NOTIFY connectedChanged) Q_PROPERTY(bool connected READ connected NOTIFY connectedChanged)
Q_PROPERTY(bool linkConnected READ linkConnected NOTIFY linkConnectedChanged) Q_PROPERTY(bool linkConnected READ linkConnected NOTIFY linkConnectedChanged)
Q_PROPERTY(bool needReboot READ needReboot NOTIFY needRebootChanged) 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 uplinkRSSI READ uplinkRSSI NOTIFY linkChanged)
Q_PROPERTY(int downlinkRSSI READ downlinkRSSI 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 localIPAddr READ localIPAddr NOTIFY localIPAddrChanged)
Q_PROPERTY(QString remoteIPAddr READ remoteIPAddr NOTIFY remoteIPAddrChanged) Q_PROPERTY(QString remoteIPAddr READ remoteIPAddr NOTIFY remoteIPAddrChanged)
Q_PROPERTY(QString netMask READ netMask NOTIFY netMaskChanged) Q_PROPERTY(QString netMask READ netMask NOTIFY netMaskChanged)
Q_PROPERTY(QString configPassword READ configPassword NOTIFY configPasswordChanged)
Q_INVOKABLE bool setRTSPSettings (QString uri, QString account, QString password);
Q_INVOKABLE bool setIPSettings (QString localIP, QString remoteIP, QString netMask); Q_INVOKABLE bool setIPSettings (QString localIP, QString remoteIP, QString netMask);
explicit MicrohardManager (QGCApplication* app, QGCToolbox* toolbox); explicit MicrohardManager (QGCApplication* app, QGCToolbox* toolbox);
...@@ -57,22 +46,12 @@ public: ...@@ -57,22 +46,12 @@ public:
bool connected () { return _isConnected; } bool connected () { return _isConnected; }
bool linkConnected () { return _linkConnected; } bool linkConnected () { return _linkConnected; }
bool needReboot () { return _needReboot; } bool needReboot () { return _needReboot; }
QString linkVidFormat () { return _linkVidFormat; }
int uplinkRSSI () { return _downlinkRSSI; } int uplinkRSSI () { return _downlinkRSSI; }
int downlinkRSSI () { return _uplinkRSSI; } 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 localIPAddr () { return _localIPAddr; }
QString remoteIPAddr () { return _remoteIPAddr; } QString remoteIPAddr () { return _remoteIPAddr; }
QString netMask () { return _netMask; } QString netMask () { return _netMask; }
QString configPassword () { return _configPassword; }
signals: signals:
void linkChanged (); void linkChanged ();
...@@ -81,13 +60,11 @@ signals: ...@@ -81,13 +60,11 @@ signals:
void connectedChanged (); void connectedChanged ();
void decodeIndexChanged (); void decodeIndexChanged ();
void rateIndexChanged (); void rateIndexChanged ();
void rtspURIChanged ();
void rtspAccountChanged ();
void rtspPasswordChanged ();
void localIPAddrChanged (); void localIPAddrChanged ();
void remoteIPAddrChanged (); void remoteIPAddrChanged ();
void netMaskChanged (); void netMaskChanged ();
void needRebootChanged (); void needRebootChanged ();
void configPasswordChanged ();
private slots: private slots:
void _connected (); void _connected ();
...@@ -95,14 +72,10 @@ private slots: ...@@ -95,14 +72,10 @@ private slots:
void _checkMicrohard (); void _checkMicrohard ();
void _updateSettings (QByteArray jSonData); void _updateSettings (QByteArray jSonData);
void _setEnabled (); void _setEnabled ();
void _setVideoEnabled ();
void _radioSettingsChanged (QVariant);
void _videoSettingsChanged (QVariant);
private: private:
void _close (); void _close ();
void _reset (); void _reset ();
void _restoreVideoSettings (Fact* setting);
FactMetaData *_createMetadata (const char *name, QStringList enums); FactMetaData *_createMetadata (const char *name, QStringList enums);
private: private:
...@@ -122,34 +95,16 @@ private: ...@@ -122,34 +95,16 @@ private:
bool _running = false; bool _running = false;
bool _isConnected = false; bool _isConnected = false;
AppSettings* _appSettings = nullptr; AppSettings* _appSettings = nullptr;
MicrohardSettings* _mhSettings = nullptr; MicrohardSettings* _mhSettings = nullptr;
bool _enableVideo = true;
bool _enabled = true; bool _enabled = true;
bool _linkConnected = false; bool _linkConnected = false;
bool _needReboot = false; bool _needReboot = false;
QTimer _workTimer; QTimer _workTimer;
QString _linkVidFormat;
int _downlinkRSSI = 0; int _downlinkRSSI = 0;
int _uplinkRSSI = 0; int _uplinkRSSI = 0;
QStringList _decodeList;
int _decodeIndex = 0;
QStringList _rateList;
int _rateIndex = 0;
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 _localIPAddr;
QString _remoteIPAddr; QString _remoteIPAddr;
QString _netMask; QString _netMask;
QString _configPassword;
QTime _timeoutTimer; QTime _timeoutTimer;
}; };
/**************************************************************************** /****************************************************************************
* *
* (c) 2009-2016 QGROUNDCONTROL PROJECT <http://www.qgroundcontrol.org> * (c) 2019 QGROUNDCONTROL PROJECT <http://www.qgroundcontrol.org>
* *
* QGroundControl is licensed according to the terms in the file * QGroundControl is licensed according to the terms in the file
* COPYING.md in the root of the source code directory. * COPYING.md in the root of the source code directory.
...@@ -8,6 +8,7 @@ ...@@ -8,6 +8,7 @@
****************************************************************************/ ****************************************************************************/
#include "MicrohardSettings.h" #include "MicrohardSettings.h"
#include "MicrohardManager.h"
#include "SettingsManager.h" #include "SettingsManager.h"
#include "QGCApplication.h" #include "QGCApplication.h"
#include "VideoManager.h" #include "VideoManager.h"
...@@ -19,11 +20,11 @@ MicrohardSettings::MicrohardSettings(QObject* parent) ...@@ -19,11 +20,11 @@ MicrohardSettings::MicrohardSettings(QObject* parent)
} }
//----------------------------------------------------------------------------- //-----------------------------------------------------------------------------
bool MicrohardSettings::start() bool
MicrohardSettings::start()
{ {
qCDebug(MicrohardLog) << "Start Microhard Settings"; qCDebug(MicrohardLog) << "Start Microhard Settings";
return false; return _start(MICROHARD_SETTINGS_PORT, QHostAddress(qgcApp()->toolbox()->microhardManager()->remoteIPAddr()));
// return _start(MICROHARD_SETTINGS_PORT, QHostAddress(qgcApp()->toolbox()->microhardManager()->remoteIPAddr()));
} }
//----------------------------------------------------------------------------- //-----------------------------------------------------------------------------
...@@ -33,52 +34,6 @@ MicrohardSettings::requestLinkStatus() ...@@ -33,52 +34,6 @@ MicrohardSettings::requestLinkStatus()
return _request("/v1/baseband.json"); return _request("/v1/baseband.json");
} }
//-----------------------------------------------------------------------------
bool
MicrohardSettings::requestDevInfo()
{
return _request("/v1/device.json");
}
//-----------------------------------------------------------------------------
bool
MicrohardSettings::requestFreqScan()
{
return _request("/v1/freqscan.json");
}
//-----------------------------------------------------------------------------
bool
MicrohardSettings::requestVideoSettings()
{
return false;
// return _request(kVideoURI);
}
//-----------------------------------------------------------------------------
bool
MicrohardSettings::requestRadioSettings()
{
return false;
// return _request(kRadioURI);
}
//-----------------------------------------------------------------------------
bool
MicrohardSettings::requestIPSettings()
{
return false;
// return _request(kIPAddrURI);
}
//-----------------------------------------------------------------------------
bool
MicrohardSettings::requestRTSPURISettings()
{
return false;
// return _request(kRTSPURI);
}
//----------------------------------------------------------------------------- //-----------------------------------------------------------------------------
bool bool
MicrohardSettings::_request(const QString& request) MicrohardSettings::_request(const QString& request)
...@@ -109,38 +64,6 @@ MicrohardSettings::_post(const QString& post, const QString &postPayload) ...@@ -109,38 +64,6 @@ MicrohardSettings::_post(const QString& post, const QString &postPayload)
return false; return false;
} }
//-----------------------------------------------------------------------------
bool
MicrohardSettings::setRadioSettings(const QString& mode, const QString& channel)
{
// static const char* kRadioPost = "{\"mode\":\"%1\",\"freq\":\"%2\"}";
// QString post = QString(kRadioPost).arg(mode).arg(channel);
return false;
// return _post(kRadioURI, post);
}
//-----------------------------------------------------------------------------
bool
MicrohardSettings::setVideoSettings(const QString& output, const QString& mode, const QString& rate)
{
return false;
/*
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
MicrohardSettings::setRTSPSettings(const QString& uri, const QString& account, const QString& password)
{
return false;
// 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 bool
MicrohardSettings::setIPSettings(const QString& localIP, const QString& remoteIP, const QString& netMask) MicrohardSettings::setIPSettings(const QString& localIP, const QString& remoteIP, const QString& netMask)
...@@ -156,6 +79,8 @@ void ...@@ -156,6 +79,8 @@ void
MicrohardSettings::_readBytes() MicrohardSettings::_readBytes()
{ {
QByteArray bytesIn = _tcpSocket->read(_tcpSocket->bytesAvailable()); QByteArray bytesIn = _tcpSocket->read(_tcpSocket->bytesAvailable());
QString s_data = QString::fromStdString(bytesIn.toStdString());
//-- Go straight to Json payload //-- Go straight to Json payload
int idx = bytesIn.indexOf('{'); int idx = bytesIn.indexOf('{');
//-- We may receive more than one response within one TCP packet. //-- We may receive more than one response within one TCP packet.
......
/**************************************************************************** /****************************************************************************
* *
* (c) 2009-2016 QGROUNDCONTROL PROJECT <http://www.qgroundcontrol.org> * (c) 2019 QGROUNDCONTROL PROJECT <http://www.qgroundcontrol.org>
* *
* QGroundControl is licensed according to the terms in the file * QGroundControl is licensed according to the terms in the file
* COPYING.md in the root of the source code directory. * COPYING.md in the root of the source code directory.
...@@ -15,18 +15,9 @@ class MicrohardSettings : public MicrohardHandler ...@@ -15,18 +15,9 @@ class MicrohardSettings : public MicrohardHandler
{ {
Q_OBJECT Q_OBJECT
public: public:
explicit MicrohardSettings (QObject* parent = nullptr); explicit MicrohardSettings (QObject* parent = nullptr);
bool start () override; bool start () override;
bool requestLinkStatus (); 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); bool setIPSettings (const QString& localIP, const QString& remoteIP, const QString& netMask);
signals: signals:
......
...@@ -38,7 +38,6 @@ QGCView { ...@@ -38,7 +38,6 @@ QGCView {
property real _valueWidth: ScreenTools.defaultFontPixelWidth * 20 property real _valueWidth: ScreenTools.defaultFontPixelWidth * 20
property real _panelWidth: _qgcView.width * _internalWidthRatio property real _panelWidth: _qgcView.width * _internalWidthRatio
property Fact _microhardEnabledFact: QGroundControl.settingsManager.appSettings.enableMicrohard property Fact _microhardEnabledFact: QGroundControl.settingsManager.appSettings.enableMicrohard
property Fact _microhardVideoEnabledFact: QGroundControl.settingsManager.appSettings.enableMicrohardVideo
property bool _microhardEnabled: _microhardEnabledFact.rawValue property bool _microhardEnabled: _microhardEnabledFact.rawValue
readonly property real _internalWidthRatio: 0.8 readonly property real _internalWidthRatio: 0.8
...@@ -96,12 +95,6 @@ QGCView { ...@@ -96,12 +95,6 @@ QGCView {
enabled: !QGroundControl.microhardManager.needReboot enabled: !QGroundControl.microhardManager.needReboot
visible: _microhardEnabledFact.visible visible: _microhardEnabledFact.visible
} }
FactCheckBox {
text: qsTr("Enable Microhard Video")
fact: _microhardVideoEnabledFact
visible: _microhardVideoEnabledFact.visible
enabled: _microhardEnabled && !QGroundControl.microhardManager.needReboot
}
} }
} }
} }
...@@ -168,270 +161,6 @@ QGCView { ...@@ -168,270 +161,6 @@ QGCView {
} }
} }
//----------------------------------------------------------------- //-----------------------------------------------------------------
//-- Device Info
Item {
width: _panelWidth
height: devInfoLabel.height
anchors.margins: ScreenTools.defaultFontPixelWidth
anchors.horizontalCenter: parent.horizontalCenter
visible: _microhardEnabled && QGroundControl.microhardManager.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: _microhardEnabled && QGroundControl.microhardManager.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.microhardManager.connected ? QGroundControl.microhardManager.serialNumber : qsTr("")
Layout.minimumWidth: _valueWidth
}
QGCLabel {
text: qsTr("Firmware Version:")
}
QGCLabel {
text: QGroundControl.microhardManager.connected ? QGroundControl.microhardManager.fwVersion : qsTr("")
}
}
}
}
//-----------------------------------------------------------------
//-- Radio Settings
Item {
width: _panelWidth
height: radioSettingsLabel.height
anchors.margins: ScreenTools.defaultFontPixelWidth
anchors.horizontalCenter: parent.horizontalCenter
visible: _microhardEnabled && QGroundControl.microhardManager.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: _microhardEnabled && QGroundControl.microhardManager.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.microhardManager.radioMode
indexModel: true
enabled: QGroundControl.microhardManager.linkConnected && !QGroundControl.microhardManager.needReboot
Layout.minimumWidth: _valueWidth
}
QGCLabel {
text: qsTr("Radio Frequency:")
}
FactComboBox {
fact: QGroundControl.microhardManager.radioChannel
indexModel: true
enabled: QGroundControl.microhardManager.linkConnected && QGroundControl.microhardManager.radioMode.rawValue > 0 && !QGroundControl.microhardManager.needReboot
Layout.minimumWidth: _valueWidth
}
}
}
}
//-----------------------------------------------------------------
//-- Video Settings
Item {
width: _panelWidth
height: videoSettingsLabel.height
anchors.margins: ScreenTools.defaultFontPixelWidth
anchors.horizontalCenter: parent.horizontalCenter
visible: _microhardEnabled && QGroundControl.microhardManager.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: _microhardEnabled && QGroundControl.microhardManager.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.microhardManager.videoOutput
indexModel: true
enabled: QGroundControl.microhardManager.linkConnected && !QGroundControl.microhardManager.needReboot
Layout.minimumWidth: _valueWidth
}
QGCLabel {
text: qsTr("Encoder:")
}
FactComboBox {
fact: QGroundControl.microhardManager.videoMode
indexModel: true
enabled: QGroundControl.microhardManager.linkConnected && !QGroundControl.microhardManager.needReboot
Layout.minimumWidth: _valueWidth
}
QGCLabel {
text: qsTr("Bit Rate:")
}
FactComboBox {
fact: QGroundControl.microhardManager.videoRate
indexModel: true
enabled: QGroundControl.microhardManager.linkConnected && !QGroundControl.microhardManager.needReboot
Layout.minimumWidth: _valueWidth
}
}
}
}
//-----------------------------------------------------------------
//-- RTSP Settings
Item {
width: _panelWidth
height: rtspSettingsLabel.height
anchors.margins: ScreenTools.defaultFontPixelWidth
anchors.horizontalCenter: parent.horizontalCenter
visible: _microhardEnabled && QGroundControl.microhardManager.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: _microhardEnabled && QGroundControl.microhardManager.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.microhardManager.rtspURI
enabled: QGroundControl.microhardManager.connected && !QGroundControl.microhardManager.needReboot
inputMethodHints: Qt.ImhUrlCharactersOnly
Layout.minimumWidth: _valueWidth
}
QGCLabel {
text: qsTr("Account:")
}
QGCTextField {
id: rtspAccount
text: QGroundControl.microhardManager.rtspAccount
enabled: QGroundControl.microhardManager.connected && !QGroundControl.microhardManager.needReboot
Layout.minimumWidth: _valueWidth
}
QGCLabel {
text: qsTr("Password:")
}
QGCTextField {
id: rtspPassword
text: QGroundControl.microhardManager.rtspPassword
enabled: QGroundControl.microhardManager.connected && !QGroundControl.microhardManager.needReboot
inputMethodHints: Qt.ImhHiddenText
Layout.minimumWidth: _valueWidth
}
}
Item {
width: 1
height: ScreenTools.defaultFontPixelHeight
}
QGCButton {
function testEnabled() {
if(!QGroundControl.microhardManager.connected)
return false
if(rtspPassword.text === QGroundControl.microhardManager.rtspPassword &&
rtspAccount.text === QGroundControl.microhardManager.rtspAccount &&
rtspURI.text === QGroundControl.microhardManager.rtspURI)
return false
if(rtspURI === "")
return false
return true
}
enabled: testEnabled() && !QGroundControl.microhardManager.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.microhardManager.setRTSPSettings(rtspURI.text, rtspAccount.text, rtspPassword.text)
setRTSPDialog.close()
}
onNo: {
setRTSPDialog.close()
}
}
}
}
}
//-----------------------------------------------------------------
//-- IP Settings //-- IP Settings
Item { Item {
width: _panelWidth width: _panelWidth
...@@ -463,7 +192,7 @@ QGCView { ...@@ -463,7 +192,7 @@ QGCView {
anchors.horizontalCenter: parent.horizontalCenter anchors.horizontalCenter: parent.horizontalCenter
columns: 2 columns: 2
QGCLabel { QGCLabel {
text: qsTr("Local IP Address:") text: qsTr("Ground Unit IP Address:")
Layout.minimumWidth: _labelWidth Layout.minimumWidth: _labelWidth
} }
QGCTextField { QGCTextField {
...@@ -474,7 +203,7 @@ QGCView { ...@@ -474,7 +203,7 @@ QGCView {
Layout.minimumWidth: _valueWidth Layout.minimumWidth: _valueWidth
} }
QGCLabel { QGCLabel {
text: qsTr("Ground Unit IP Address:") text: qsTr("Air Unit IP Address:")
} }
QGCTextField { QGCTextField {
id: remoteIP id: remoteIP
...@@ -493,6 +222,16 @@ QGCView { ...@@ -493,6 +222,16 @@ QGCView {
inputMethodHints: Qt.ImhFormattedNumbersOnly inputMethodHints: Qt.ImhFormattedNumbersOnly
Layout.minimumWidth: _valueWidth Layout.minimumWidth: _valueWidth
} }
QGCLabel {
text: qsTr("Configuration password:")
}
QGCTextField {
id: configPassword
text: QGroundControl.microhardManager.configPassword
enabled: !QGroundControl.microhardManager.needReboot
inputMethodHints: Qt.ImhHiddenText
Layout.minimumWidth: _valueWidth
}
} }
Item { Item {
width: 1 width: 1
......
...@@ -38,6 +38,9 @@ ...@@ -38,6 +38,9 @@
#if defined(QGC_GST_TAISYNC_ENABLED) #if defined(QGC_GST_TAISYNC_ENABLED)
#include "TaisyncManager.h" #include "TaisyncManager.h"
#endif #endif
#if defined(QGC_GST_MICROHARD_ENABLED)
#include "MicrohardManager.h"
#endif
#if defined(QGC_CUSTOM_BUILD) #if defined(QGC_CUSTOM_BUILD)
#include CUSTOMHEADER #include CUSTOMHEADER
...@@ -78,6 +81,9 @@ QGCToolbox::QGCToolbox(QGCApplication* app) ...@@ -78,6 +81,9 @@ QGCToolbox::QGCToolbox(QGCApplication* app)
#if defined(QGC_GST_TAISYNC_ENABLED) #if defined(QGC_GST_TAISYNC_ENABLED)
_taisyncManager = new TaisyncManager (app, this); _taisyncManager = new TaisyncManager (app, this);
#endif #endif
#if defined(QGC_GST_MICROHARD_ENABLED)
_microhardManager = new MicrohardManager (app, this);
#endif
} }
void QGCToolbox::setChildToolboxes(void) void QGCToolbox::setChildToolboxes(void)
...@@ -107,6 +113,9 @@ void QGCToolbox::setChildToolboxes(void) ...@@ -107,6 +113,9 @@ void QGCToolbox::setChildToolboxes(void)
#if defined(QGC_GST_TAISYNC_ENABLED) #if defined(QGC_GST_TAISYNC_ENABLED)
_taisyncManager->setToolbox(this); _taisyncManager->setToolbox(this);
#endif #endif
#if defined(QGC_GST_MICROHARD_ENABLED)
_microhardManager->setToolbox(this);
#endif
} }
void QGCToolbox::_scanAndLoadPlugins(QGCApplication* app) void QGCToolbox::_scanAndLoadPlugins(QGCApplication* app)
......
...@@ -104,7 +104,7 @@ private: ...@@ -104,7 +104,7 @@ private:
TaisyncManager* _taisyncManager = nullptr; TaisyncManager* _taisyncManager = nullptr;
#endif #endif
#if defined(QGC_GST_MICROHARD_ENABLED) #if defined(QGC_GST_MICROHARD_ENABLED)
MicrohardManager* _microhardManager = nullptr; MicrohardManager* _microhardManager = nullptr;
#endif #endif
friend class QGCApplication; friend class QGCApplication;
}; };
......
...@@ -228,11 +228,4 @@ ...@@ -228,11 +228,4 @@
"longDescription": "Enable Microhard Module Support", "longDescription": "Enable Microhard Module Support",
"type": "bool", "type": "bool",
"defaultValue": false "defaultValue": false
},
{
"name": "enableMicrohardVideo",
"shortDescription": "Enable Microhard Video Support",
"longDescription": "Enable Microhard Video Support",
"type": "bool",
"defaultValue": true
}] }]
...@@ -88,7 +88,6 @@ DECLARE_SETTINGSFACT(AppSettings, apmStartMavlinkStreams) ...@@ -88,7 +88,6 @@ DECLARE_SETTINGSFACT(AppSettings, apmStartMavlinkStreams)
DECLARE_SETTINGSFACT(AppSettings, enableTaisync) DECLARE_SETTINGSFACT(AppSettings, enableTaisync)
DECLARE_SETTINGSFACT(AppSettings, enableTaisyncVideo) DECLARE_SETTINGSFACT(AppSettings, enableTaisyncVideo)
DECLARE_SETTINGSFACT(AppSettings, enableMicrohard) DECLARE_SETTINGSFACT(AppSettings, enableMicrohard)
DECLARE_SETTINGSFACT(AppSettings, enableMicrohardVideo)
DECLARE_SETTINGSFACT_NO_FUNC(AppSettings, indoorPalette) DECLARE_SETTINGSFACT_NO_FUNC(AppSettings, indoorPalette)
{ {
......
...@@ -46,7 +46,6 @@ public: ...@@ -46,7 +46,6 @@ public:
DEFINE_SETTINGFACT(enableTaisync) DEFINE_SETTINGFACT(enableTaisync)
DEFINE_SETTINGFACT(enableTaisyncVideo) DEFINE_SETTINGFACT(enableTaisyncVideo)
DEFINE_SETTINGFACT(enableMicrohard) DEFINE_SETTINGFACT(enableMicrohard)
DEFINE_SETTINGFACT(enableMicrohardVideo)
// Although this is a global setting it only affects ArduPilot vehicle since PX4 automatically starts the stream from the vehicle side // Although this is a global setting it only affects ArduPilot vehicle since PX4 automatically starts the stream from the vehicle side
DEFINE_SETTINGFACT(apmStartMavlinkStreams) DEFINE_SETTINGFACT(apmStartMavlinkStreams)
......
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