diff --git a/src/Taisync/TaisyncHandler.h b/src/Taisync/TaisyncHandler.h index 4d89b90ca51a6959e6a8de8c4069028e50a8c631..789181bfbbf2441c14d373361ce99fa6ccde19e4 100644 --- a/src/Taisync/TaisyncHandler.h +++ b/src/Taisync/TaisyncHandler.h @@ -22,7 +22,6 @@ #define TAISYNC_TELEM_TARGET_PORT 14550 #else #define TAISYNC_SETTINGS_PORT 80 -#define TAISYNC_SETTINGS_TARGET "192.168.1.99" #endif Q_DECLARE_LOGGING_CATEGORY(TaisyncLog) diff --git a/src/Taisync/TaisyncManager.cc b/src/Taisync/TaisyncManager.cc index cd04aa67e97a7773c296a4effbf658d40e206269..c7e1f877708893a8a53728a115c75626cc08c95b 100644 --- a/src/Taisync/TaisyncManager.cc +++ b/src/Taisync/TaisyncManager.cc @@ -13,12 +13,17 @@ #include "QGCApplication.h" #include "VideoManager.h" +#include + 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"; //----------------------------------------------------------------------------- TaisyncManager::TaisyncManager(QGCApplication* app, QGCToolbox* toolbox) @@ -26,6 +31,12 @@ TaisyncManager::TaisyncManager(QGCApplication* app, QGCToolbox* 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(); + settings.endGroup(); } //----------------------------------------------------------------------------- @@ -67,6 +78,8 @@ void TaisyncManager::_reset() { _close(); + _isConnected = false; + emit connectedChanged(); _taiSettings = new TaisyncSettings(this); connect(_taiSettings, &TaisyncSettings::updateSettings, this, &TaisyncManager::_updateSettings); connect(_taiSettings, &TaisyncSettings::connected, this, &TaisyncManager::_connected); @@ -180,14 +193,37 @@ TaisyncManager::setRTSPSettings(QString uri, QString account, QString password) //----------------------------------------------------------------------------- bool -TaisyncManager::setIPSettings(QString localIP, QString remoteIP, QString netMask) +TaisyncManager::setIPSettings(QString localIP_, QString remoteIP_, QString netMask_) { -#if !defined(__ios__) && !defined(__android__) - if(_taiSettings) { - return _taiSettings->setIPSettings(localIP, remoteIP, netMask); + bool res = false; + if(_localIPAddr != localIP_ || _remoteIPAddr != remoteIP_ || _netMask != netMask_) { + //-- If we are connected to the Taisync + if(_linkConnected) { + if(_taiSettings) { + //-- Change IP settings + res = _taiSettings->setIPSettings(localIP_, remoteIP_, netMask_); + } + } 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; } -#endif - return false; + return res; } //----------------------------------------------------------------------------- @@ -355,6 +391,7 @@ TaisyncManager::_checkTaisync() _taiSettings->start(); } } else { + //qCDebug(TaisyncVerbose) << bin << _reqMask; while(true) { if (_reqMask & REQ_LINK_STATUS) { _taiSettings->requestLinkStatus(); @@ -365,7 +402,7 @@ TaisyncManager::_checkTaisync() break; } if (_reqMask & REQ_FREQ_SCAN) { - _reqMask |= ~static_cast(REQ_FREQ_SCAN); + _reqMask &= ~static_cast(REQ_FREQ_SCAN); _taiSettings->requestFreqScan(); break; } @@ -378,12 +415,12 @@ TaisyncManager::_checkTaisync() break; } if (_reqMask & REQ_RTSP_SETTINGS) { - _reqMask |= ~static_cast(REQ_RTSP_SETTINGS); + _reqMask &= ~static_cast(REQ_RTSP_SETTINGS); _taiSettings->requestRTSPURISettings(); break; } if (_reqMask & REQ_IP_SETTINGS) { - _reqMask |= ~static_cast(REQ_IP_SETTINGS); + _reqMask &= ~static_cast(REQ_IP_SETTINGS); _taiSettings->requestIPSettings(); break; } @@ -408,7 +445,7 @@ TaisyncManager::_updateSettings(QByteArray jSonData) QJsonObject jObj = doc.object(); //-- Link Status? if(jSonData.contains("\"flight\":")) { - _reqMask |= ~static_cast(REQ_LINK_STATUS); + _reqMask &= ~static_cast(REQ_LINK_STATUS); bool tlinkConnected = jObj["flight"].toString("") == "online"; if(tlinkConnected != _linkConnected) { _linkConnected = tlinkConnected; @@ -425,7 +462,7 @@ TaisyncManager::_updateSettings(QByteArray jSonData) } //-- Device Info? } else if(jSonData.contains("\"firmwareversion\":")) { - _reqMask |= ~static_cast(REQ_DEV_INFO); + _reqMask &= ~static_cast(REQ_DEV_INFO); QString tfwVersion = jObj["firmwareversion"].toString(_fwVersion); QString tserialNumber = jObj["sn"].toString(_serialNumber); if(tfwVersion != _fwVersion || tserialNumber != _serialNumber) { @@ -435,7 +472,7 @@ TaisyncManager::_updateSettings(QByteArray jSonData) } //-- Radio Settings? } else if(jSonData.contains("\"freq\":")) { - _reqMask |= ~static_cast(REQ_RADIO_SETTINGS); + _reqMask &= ~static_cast(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())); @@ -443,7 +480,7 @@ TaisyncManager::_updateSettings(QByteArray jSonData) _radioChannel->_containerSetRawValue(idx); //-- Video Settings? } else if(jSonData.contains("\"maxbitrate\":")) { - _reqMask |= ~static_cast(REQ_VIDEO_SETTINGS); + _reqMask &= ~static_cast(REQ_VIDEO_SETTINGS); int idx; idx = _videoMode->valueIndex(jObj["mode"].toString(_videoMode->enumStringValue())); if(idx < 0) idx = 0; @@ -455,21 +492,33 @@ TaisyncManager::_updateSettings(QByteArray jSonData) //-- 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; diff --git a/src/Taisync/TaisyncSettings.cc b/src/Taisync/TaisyncSettings.cc index c9d029c075b53cab415b21826d367cb4681ce76a..a78ae0ae63eba160f4452e002be256cbea20e7eb 100644 --- a/src/Taisync/TaisyncSettings.cc +++ b/src/Taisync/TaisyncSettings.cc @@ -23,9 +23,7 @@ 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"; -#if !defined(__ios__) && !defined(__android__) static const char* kIPAddrURI = "/v1/ipaddr.json"; -#endif //----------------------------------------------------------------------------- TaisyncSettings::TaisyncSettings(QObject* parent) @@ -40,7 +38,7 @@ bool TaisyncSettings::start() #if defined(__ios__) || defined(__android__) return _start(TAISYNC_SETTINGS_PORT); #else - return _start(80, QHostAddress(TAISYNC_SETTINGS_TARGET)); + return _start(TAISYNC_SETTINGS_PORT, QHostAddress(qgcApp()->toolbox()->taisyncManager()->remoteIPAddr())); #endif } @@ -80,13 +78,11 @@ TaisyncSettings::requestRadioSettings() } //----------------------------------------------------------------------------- -#if !defined(__ios__) && !defined(__android__) bool TaisyncSettings::requestIPSettings() { return _request(kIPAddrURI); } -#endif //----------------------------------------------------------------------------- bool @@ -149,7 +145,6 @@ TaisyncSettings::setRTSPSettings(const QString& uri, const QString& account, con } //----------------------------------------------------------------------------- -#if !defined(__ios__) && !defined(__android__) bool TaisyncSettings::setIPSettings(const QString& localIP, const QString& remoteIP, const QString& netMask) { @@ -157,7 +152,6 @@ TaisyncSettings::setIPSettings(const QString& localIP, const QString& remoteIP, QString post = QString(kRTSPPost).arg(localIP).arg(netMask).arg(remoteIP); return _post(kIPAddrURI, post); } -#endif //----------------------------------------------------------------------------- void diff --git a/src/Taisync/TaisyncSettings.h b/src/Taisync/TaisyncSettings.h index 4ac69dec5ba81a5f733767dafb2e4398099b96a3..1ebc1d7580da84db9108e662ea8a76102f508ea8 100644 --- a/src/Taisync/TaisyncSettings.h +++ b/src/Taisync/TaisyncSettings.h @@ -22,16 +22,12 @@ public: bool requestFreqScan (); bool requestVideoSettings (); bool requestRadioSettings (); -#if !defined(__ios__) && !defined(__android__) bool requestIPSettings (); -#endif 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); -#if !defined(__ios__) && !defined(__android__) bool setIPSettings (const QString& localIP, const QString& remoteIP, const QString& netMask); -#endif signals: void updateSettings (QByteArray jSonData); diff --git a/src/Taisync/TaisyncSettings.qml b/src/Taisync/TaisyncSettings.qml index 7575b618d264372e1f07e453557b268bd1ef3468..41651d9201416fd5a37e4e1ddd6962b16b57f3e2 100644 --- a/src/Taisync/TaisyncSettings.qml +++ b/src/Taisync/TaisyncSettings.qml @@ -195,14 +195,14 @@ QGCView { Layout.minimumWidth: _labelWidth } QGCLabel { - text: QGroundControl.taisyncManager.linkConnected ? QGroundControl.taisyncManager.serialNumber : qsTr("") + text: QGroundControl.taisyncManager.connected ? QGroundControl.taisyncManager.serialNumber : qsTr("") Layout.minimumWidth: _valueWidth } QGCLabel { text: qsTr("Firmware Version:") } QGCLabel { - text: QGroundControl.taisyncManager.linkConnected ? QGroundControl.taisyncManager.fwVersion : qsTr("") + text: QGroundControl.taisyncManager.connected ? QGroundControl.taisyncManager.fwVersion : qsTr("") } } } @@ -322,6 +322,188 @@ QGCView { } } } + //----------------------------------------------------------------- + //-- RTSP Settings + Item { + width: _panelWidth + height: rtspSettingsLabel.height + anchors.margins: ScreenTools.defaultFontPixelWidth + anchors.horizontalCenter: parent.horizontalCenter + visible: _taisyncEnabled && QGroundControl.taisyncManager.linkConnected + 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.linkConnected + 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.linkConnected + inputMethodHints: Qt.ImhUrlCharactersOnly + Layout.minimumWidth: _valueWidth + } + QGCLabel { + text: qsTr("Account:") + } + QGCTextField { + id: rtspAccount + text: QGroundControl.taisyncManager.rtspAccount + enabled: QGroundControl.taisyncManager.linkConnected + Layout.minimumWidth: _valueWidth + } + QGCLabel { + text: qsTr("Password:") + } + QGCTextField { + id: rtspPassword + text: QGroundControl.taisyncManager.rtspPassword + enabled: QGroundControl.taisyncManager.linkConnected + inputMethodHints: Qt.ImhHiddenText + Layout.minimumWidth: _valueWidth + } + } + QGCButton { + function testEnabled() { + if(!QGroundControl.taisyncManager.linkConnected) + return false + if(rtspPassword.text === QGroundControl.taisyncManager.rtspPassword && + rtspAccount === QGroundControl.taisyncManager.rtspAccount && + rtspURI === QGroundControl.taisyncManager.rtspURI) + return false + if(rtspURI === "") + return false + return true + } + enabled: testEnabled() + text: qsTr("Apply") + anchors.horizontalCenter: parent.horizontalCenter + onClicked: { + + } + } + } + } + //----------------------------------------------------------------- + //-- 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 + inputMethodHints: Qt.ImhFormattedNumbersOnly + Layout.minimumWidth: _valueWidth + } + QGCLabel { + text: qsTr("Ground Unit IP Address:") + } + QGCTextField { + id: remoteIP + text: QGroundControl.taisyncManager.remoteIPAddr + inputMethodHints: Qt.ImhFormattedNumbersOnly + Layout.minimumWidth: _valueWidth + } + QGCLabel { + text: qsTr("Network Mask:") + } + QGCTextField { + id: netMask + text: QGroundControl.taisyncManager.netMask + inputMethodHints: Qt.ImhFormattedNumbersOnly + Layout.minimumWidth: _valueWidth + } + } + 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() + 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() + } + } + } + } + } } } }