Skip to content
Projects
Groups
Snippets
Help
Loading...
Help
Support
Submit feedback
Contribute to GitLab
Sign in
Toggle navigation
Q
qgroundcontrol
Project
Project
Details
Activity
Releases
Cycle Analytics
Repository
Repository
Files
Commits
Branches
Tags
Contributors
Graph
Compare
Charts
Issues
0
Issues
0
List
Boards
Labels
Milestones
Merge Requests
0
Merge Requests
0
CI / CD
CI / CD
Pipelines
Jobs
Schedules
Charts
Wiki
Wiki
Snippets
Snippets
Members
Members
Collapse sidebar
Close sidebar
Activity
Graph
Charts
Create a new issue
Jobs
Commits
Issue Boards
Open sidebar
Valentin Platzgummer
qgroundcontrol
Commits
68a5ab42
Commit
68a5ab42
authored
Dec 26, 2018
by
Gus Grubba
Browse files
Options
Browse Files
Download
Email Patches
Plain Diff
Network Settings
parent
df27e66b
Changes
5
Hide whitespace changes
Inline
Side-by-side
Showing
5 changed files
with
247 additions
and
27 deletions
+247
-27
TaisyncHandler.h
src/Taisync/TaisyncHandler.h
+0
-1
TaisyncManager.cc
src/Taisync/TaisyncManager.cc
+62
-13
TaisyncSettings.cc
src/Taisync/TaisyncSettings.cc
+1
-7
TaisyncSettings.h
src/Taisync/TaisyncSettings.h
+0
-4
TaisyncSettings.qml
src/Taisync/TaisyncSettings.qml
+184
-2
No files found.
src/Taisync/TaisyncHandler.h
View file @
68a5ab42
...
@@ -22,7 +22,6 @@
...
@@ -22,7 +22,6 @@
#define TAISYNC_TELEM_TARGET_PORT 14550
#define TAISYNC_TELEM_TARGET_PORT 14550
#else
#else
#define TAISYNC_SETTINGS_PORT 80
#define TAISYNC_SETTINGS_PORT 80
#define TAISYNC_SETTINGS_TARGET "192.168.1.99"
#endif
#endif
Q_DECLARE_LOGGING_CATEGORY
(
TaisyncLog
)
Q_DECLARE_LOGGING_CATEGORY
(
TaisyncLog
)
...
...
src/Taisync/TaisyncManager.cc
View file @
68a5ab42
...
@@ -13,12 +13,17 @@
...
@@ -13,12 +13,17 @@
#include "QGCApplication.h"
#include "QGCApplication.h"
#include "VideoManager.h"
#include "VideoManager.h"
#include <QSettings>
static
const
char
*
kTAISYNC_GROUP
=
"Taisync"
;
static
const
char
*
kTAISYNC_GROUP
=
"Taisync"
;
static
const
char
*
kRADIO_MODE
=
"RadioMode"
;
static
const
char
*
kRADIO_MODE
=
"RadioMode"
;
static
const
char
*
kRADIO_CHANNEL
=
"RadioChannel"
;
static
const
char
*
kRADIO_CHANNEL
=
"RadioChannel"
;
static
const
char
*
kVIDEO_OUTPUT
=
"VideoOutput"
;
static
const
char
*
kVIDEO_OUTPUT
=
"VideoOutput"
;
static
const
char
*
kVIDEO_MODE
=
"VideoMode"
;
static
const
char
*
kVIDEO_MODE
=
"VideoMode"
;
static
const
char
*
kVIDEO_RATE
=
"VideoRate"
;
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
)
TaisyncManager
::
TaisyncManager
(
QGCApplication
*
app
,
QGCToolbox
*
toolbox
)
...
@@ -26,6 +31,12 @@ TaisyncManager::TaisyncManager(QGCApplication* app, QGCToolbox* toolbox)
...
@@ -26,6 +31,12 @@ TaisyncManager::TaisyncManager(QGCApplication* app, QGCToolbox* toolbox)
{
{
connect
(
&
_workTimer
,
&
QTimer
::
timeout
,
this
,
&
TaisyncManager
::
_checkTaisync
);
connect
(
&
_workTimer
,
&
QTimer
::
timeout
,
this
,
&
TaisyncManager
::
_checkTaisync
);
_workTimer
.
setSingleShot
(
true
);
_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
...
@@ -67,6 +78,8 @@ void
TaisyncManager
::
_reset
()
TaisyncManager
::
_reset
()
{
{
_close
();
_close
();
_isConnected
=
false
;
emit
connectedChanged
();
_taiSettings
=
new
TaisyncSettings
(
this
);
_taiSettings
=
new
TaisyncSettings
(
this
);
connect
(
_taiSettings
,
&
TaisyncSettings
::
updateSettings
,
this
,
&
TaisyncManager
::
_updateSettings
);
connect
(
_taiSettings
,
&
TaisyncSettings
::
updateSettings
,
this
,
&
TaisyncManager
::
_updateSettings
);
connect
(
_taiSettings
,
&
TaisyncSettings
::
connected
,
this
,
&
TaisyncManager
::
_connected
);
connect
(
_taiSettings
,
&
TaisyncSettings
::
connected
,
this
,
&
TaisyncManager
::
_connected
);
...
@@ -180,14 +193,37 @@ TaisyncManager::setRTSPSettings(QString uri, QString account, QString password)
...
@@ -180,14 +193,37 @@ TaisyncManager::setRTSPSettings(QString uri, QString account, QString password)
//-----------------------------------------------------------------------------
//-----------------------------------------------------------------------------
bool
bool
TaisyncManager
::
setIPSettings
(
QString
localIP
,
QString
remoteIP
,
QString
netMask
)
TaisyncManager
::
setIPSettings
(
QString
localIP
_
,
QString
remoteIP_
,
QString
netMask_
)
{
{
#if !defined(__ios__) && !defined(__android__)
bool
res
=
false
;
if
(
_taiSettings
)
{
if
(
_localIPAddr
!=
localIP_
||
_remoteIPAddr
!=
remoteIP_
||
_netMask
!=
netMask_
)
{
return
_taiSettings
->
setIPSettings
(
localIP
,
remoteIP
,
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
res
;
return
false
;
}
}
//-----------------------------------------------------------------------------
//-----------------------------------------------------------------------------
...
@@ -355,6 +391,7 @@ TaisyncManager::_checkTaisync()
...
@@ -355,6 +391,7 @@ TaisyncManager::_checkTaisync()
_taiSettings
->
start
();
_taiSettings
->
start
();
}
}
}
else
{
}
else
{
//qCDebug(TaisyncVerbose) << bin << _reqMask;
while
(
true
)
{
while
(
true
)
{
if
(
_reqMask
&
REQ_LINK_STATUS
)
{
if
(
_reqMask
&
REQ_LINK_STATUS
)
{
_taiSettings
->
requestLinkStatus
();
_taiSettings
->
requestLinkStatus
();
...
@@ -365,7 +402,7 @@ TaisyncManager::_checkTaisync()
...
@@ -365,7 +402,7 @@ TaisyncManager::_checkTaisync()
break
;
break
;
}
}
if
(
_reqMask
&
REQ_FREQ_SCAN
)
{
if
(
_reqMask
&
REQ_FREQ_SCAN
)
{
_reqMask
|
=
~
static_cast
<
uint32_t
>
(
REQ_FREQ_SCAN
);
_reqMask
&
=
~
static_cast
<
uint32_t
>
(
REQ_FREQ_SCAN
);
_taiSettings
->
requestFreqScan
();
_taiSettings
->
requestFreqScan
();
break
;
break
;
}
}
...
@@ -378,12 +415,12 @@ TaisyncManager::_checkTaisync()
...
@@ -378,12 +415,12 @@ TaisyncManager::_checkTaisync()
break
;
break
;
}
}
if
(
_reqMask
&
REQ_RTSP_SETTINGS
)
{
if
(
_reqMask
&
REQ_RTSP_SETTINGS
)
{
_reqMask
|
=
~
static_cast
<
uint32_t
>
(
REQ_RTSP_SETTINGS
);
_reqMask
&
=
~
static_cast
<
uint32_t
>
(
REQ_RTSP_SETTINGS
);
_taiSettings
->
requestRTSPURISettings
();
_taiSettings
->
requestRTSPURISettings
();
break
;
break
;
}
}
if
(
_reqMask
&
REQ_IP_SETTINGS
)
{
if
(
_reqMask
&
REQ_IP_SETTINGS
)
{
_reqMask
|
=
~
static_cast
<
uint32_t
>
(
REQ_IP_SETTINGS
);
_reqMask
&
=
~
static_cast
<
uint32_t
>
(
REQ_IP_SETTINGS
);
_taiSettings
->
requestIPSettings
();
_taiSettings
->
requestIPSettings
();
break
;
break
;
}
}
...
@@ -408,7 +445,7 @@ TaisyncManager::_updateSettings(QByteArray jSonData)
...
@@ -408,7 +445,7 @@ TaisyncManager::_updateSettings(QByteArray jSonData)
QJsonObject
jObj
=
doc
.
object
();
QJsonObject
jObj
=
doc
.
object
();
//-- Link Status?
//-- Link Status?
if
(
jSonData
.
contains
(
"
\"
flight
\"
:"
))
{
if
(
jSonData
.
contains
(
"
\"
flight
\"
:"
))
{
_reqMask
|
=
~
static_cast
<
uint32_t
>
(
REQ_LINK_STATUS
);
_reqMask
&
=
~
static_cast
<
uint32_t
>
(
REQ_LINK_STATUS
);
bool
tlinkConnected
=
jObj
[
"flight"
].
toString
(
""
)
==
"online"
;
bool
tlinkConnected
=
jObj
[
"flight"
].
toString
(
""
)
==
"online"
;
if
(
tlinkConnected
!=
_linkConnected
)
{
if
(
tlinkConnected
!=
_linkConnected
)
{
_linkConnected
=
tlinkConnected
;
_linkConnected
=
tlinkConnected
;
...
@@ -425,7 +462,7 @@ TaisyncManager::_updateSettings(QByteArray jSonData)
...
@@ -425,7 +462,7 @@ TaisyncManager::_updateSettings(QByteArray jSonData)
}
}
//-- Device Info?
//-- Device Info?
}
else
if
(
jSonData
.
contains
(
"
\"
firmwareversion
\"
:"
))
{
}
else
if
(
jSonData
.
contains
(
"
\"
firmwareversion
\"
:"
))
{
_reqMask
|
=
~
static_cast
<
uint32_t
>
(
REQ_DEV_INFO
);
_reqMask
&
=
~
static_cast
<
uint32_t
>
(
REQ_DEV_INFO
);
QString
tfwVersion
=
jObj
[
"firmwareversion"
].
toString
(
_fwVersion
);
QString
tfwVersion
=
jObj
[
"firmwareversion"
].
toString
(
_fwVersion
);
QString
tserialNumber
=
jObj
[
"sn"
].
toString
(
_serialNumber
);
QString
tserialNumber
=
jObj
[
"sn"
].
toString
(
_serialNumber
);
if
(
tfwVersion
!=
_fwVersion
||
tserialNumber
!=
_serialNumber
)
{
if
(
tfwVersion
!=
_fwVersion
||
tserialNumber
!=
_serialNumber
)
{
...
@@ -435,7 +472,7 @@ TaisyncManager::_updateSettings(QByteArray jSonData)
...
@@ -435,7 +472,7 @@ TaisyncManager::_updateSettings(QByteArray jSonData)
}
}
//-- Radio Settings?
//-- Radio Settings?
}
else
if
(
jSonData
.
contains
(
"
\"
freq
\"
:"
))
{
}
else
if
(
jSonData
.
contains
(
"
\"
freq
\"
:"
))
{
_reqMask
|
=
~
static_cast
<
uint32_t
>
(
REQ_RADIO_SETTINGS
);
_reqMask
&
=
~
static_cast
<
uint32_t
>
(
REQ_RADIO_SETTINGS
);
int
idx
=
_radioModeList
.
indexOf
(
jObj
[
"mode"
].
toString
(
_radioMode
->
enumStringValue
()));
int
idx
=
_radioModeList
.
indexOf
(
jObj
[
"mode"
].
toString
(
_radioMode
->
enumStringValue
()));
if
(
idx
>=
0
)
_radioMode
->
_containerSetRawValue
(
idx
);
if
(
idx
>=
0
)
_radioMode
->
_containerSetRawValue
(
idx
);
idx
=
_radioChannel
->
valueIndex
(
jObj
[
"freq"
].
toString
(
_radioChannel
->
enumStringValue
()));
idx
=
_radioChannel
->
valueIndex
(
jObj
[
"freq"
].
toString
(
_radioChannel
->
enumStringValue
()));
...
@@ -443,7 +480,7 @@ TaisyncManager::_updateSettings(QByteArray jSonData)
...
@@ -443,7 +480,7 @@ TaisyncManager::_updateSettings(QByteArray jSonData)
_radioChannel
->
_containerSetRawValue
(
idx
);
_radioChannel
->
_containerSetRawValue
(
idx
);
//-- Video Settings?
//-- Video Settings?
}
else
if
(
jSonData
.
contains
(
"
\"
maxbitrate
\"
:"
))
{
}
else
if
(
jSonData
.
contains
(
"
\"
maxbitrate
\"
:"
))
{
_reqMask
|
=
~
static_cast
<
uint32_t
>
(
REQ_VIDEO_SETTINGS
);
_reqMask
&
=
~
static_cast
<
uint32_t
>
(
REQ_VIDEO_SETTINGS
);
int
idx
;
int
idx
;
idx
=
_videoMode
->
valueIndex
(
jObj
[
"mode"
].
toString
(
_videoMode
->
enumStringValue
()));
idx
=
_videoMode
->
valueIndex
(
jObj
[
"mode"
].
toString
(
_videoMode
->
enumStringValue
()));
if
(
idx
<
0
)
idx
=
0
;
if
(
idx
<
0
)
idx
=
0
;
...
@@ -455,21 +492,33 @@ TaisyncManager::_updateSettings(QByteArray jSonData)
...
@@ -455,21 +492,33 @@ TaisyncManager::_updateSettings(QByteArray jSonData)
//-- IP Address Settings?
//-- IP Address Settings?
}
else
if
(
jSonData
.
contains
(
"
\"
usbEthIp
\"
:"
))
{
}
else
if
(
jSonData
.
contains
(
"
\"
usbEthIp
\"
:"
))
{
QString
value
;
QString
value
;
bool
changed
=
false
;
value
=
jObj
[
"ipaddr"
].
toString
(
_localIPAddr
);
value
=
jObj
[
"ipaddr"
].
toString
(
_localIPAddr
);
if
(
value
!=
_localIPAddr
)
{
if
(
value
!=
_localIPAddr
)
{
_localIPAddr
=
value
;
_localIPAddr
=
value
;
changed
=
true
;
emit
localIPAddrChanged
();
emit
localIPAddrChanged
();
}
}
value
=
jObj
[
"netmask"
].
toString
(
_netMask
);
value
=
jObj
[
"netmask"
].
toString
(
_netMask
);
if
(
value
!=
_netMask
)
{
if
(
value
!=
_netMask
)
{
_netMask
=
value
;
_netMask
=
value
;
changed
=
true
;
emit
netMaskChanged
();
emit
netMaskChanged
();
}
}
value
=
jObj
[
"usbEthIp"
].
toString
(
_remoteIPAddr
);
value
=
jObj
[
"usbEthIp"
].
toString
(
_remoteIPAddr
);
if
(
value
!=
_remoteIPAddr
)
{
if
(
value
!=
_remoteIPAddr
)
{
_remoteIPAddr
=
value
;
_remoteIPAddr
=
value
;
changed
=
true
;
emit
remoteIPAddrChanged
();
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?
//-- RTSP URI Settings?
}
else
if
(
jSonData
.
contains
(
"
\"
rtspURI
\"
:"
))
{
}
else
if
(
jSonData
.
contains
(
"
\"
rtspURI
\"
:"
))
{
QString
value
;
QString
value
;
...
...
src/Taisync/TaisyncSettings.cc
View file @
68a5ab42
...
@@ -23,9 +23,7 @@ static const char* kGetReq = "GET %1 HTTP/1.1\r\n\r\n";
...
@@ -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
*
kRadioURI
=
"/v1/radio.json"
;
static
const
char
*
kVideoURI
=
"/v1/video.json"
;
static
const
char
*
kVideoURI
=
"/v1/video.json"
;
static
const
char
*
kRTSPURI
=
"/v1/rtspuri.json"
;
static
const
char
*
kRTSPURI
=
"/v1/rtspuri.json"
;
#if !defined(__ios__) && !defined(__android__)
static
const
char
*
kIPAddrURI
=
"/v1/ipaddr.json"
;
static
const
char
*
kIPAddrURI
=
"/v1/ipaddr.json"
;
#endif
//-----------------------------------------------------------------------------
//-----------------------------------------------------------------------------
TaisyncSettings
::
TaisyncSettings
(
QObject
*
parent
)
TaisyncSettings
::
TaisyncSettings
(
QObject
*
parent
)
...
@@ -40,7 +38,7 @@ bool TaisyncSettings::start()
...
@@ -40,7 +38,7 @@ bool TaisyncSettings::start()
#if defined(__ios__) || defined(__android__)
#if defined(__ios__) || defined(__android__)
return
_start
(
TAISYNC_SETTINGS_PORT
);
return
_start
(
TAISYNC_SETTINGS_PORT
);
#else
#else
return
_start
(
80
,
QHostAddress
(
TAISYNC_SETTINGS_TARGET
));
return
_start
(
TAISYNC_SETTINGS_PORT
,
QHostAddress
(
qgcApp
()
->
toolbox
()
->
taisyncManager
()
->
remoteIPAddr
()
));
#endif
#endif
}
}
...
@@ -80,13 +78,11 @@ TaisyncSettings::requestRadioSettings()
...
@@ -80,13 +78,11 @@ TaisyncSettings::requestRadioSettings()
}
}
//-----------------------------------------------------------------------------
//-----------------------------------------------------------------------------
#if !defined(__ios__) && !defined(__android__)
bool
bool
TaisyncSettings
::
requestIPSettings
()
TaisyncSettings
::
requestIPSettings
()
{
{
return
_request
(
kIPAddrURI
);
return
_request
(
kIPAddrURI
);
}
}
#endif
//-----------------------------------------------------------------------------
//-----------------------------------------------------------------------------
bool
bool
...
@@ -149,7 +145,6 @@ TaisyncSettings::setRTSPSettings(const QString& uri, const QString& account, con
...
@@ -149,7 +145,6 @@ TaisyncSettings::setRTSPSettings(const QString& uri, const QString& account, con
}
}
//-----------------------------------------------------------------------------
//-----------------------------------------------------------------------------
#if !defined(__ios__) && !defined(__android__)
bool
bool
TaisyncSettings
::
setIPSettings
(
const
QString
&
localIP
,
const
QString
&
remoteIP
,
const
QString
&
netMask
)
TaisyncSettings
::
setIPSettings
(
const
QString
&
localIP
,
const
QString
&
remoteIP
,
const
QString
&
netMask
)
{
{
...
@@ -157,7 +152,6 @@ TaisyncSettings::setIPSettings(const QString& localIP, const QString& remoteIP,
...
@@ -157,7 +152,6 @@ TaisyncSettings::setIPSettings(const QString& localIP, const QString& remoteIP,
QString
post
=
QString
(
kRTSPPost
).
arg
(
localIP
).
arg
(
netMask
).
arg
(
remoteIP
);
QString
post
=
QString
(
kRTSPPost
).
arg
(
localIP
).
arg
(
netMask
).
arg
(
remoteIP
);
return
_post
(
kIPAddrURI
,
post
);
return
_post
(
kIPAddrURI
,
post
);
}
}
#endif
//-----------------------------------------------------------------------------
//-----------------------------------------------------------------------------
void
void
...
...
src/Taisync/TaisyncSettings.h
View file @
68a5ab42
...
@@ -22,16 +22,12 @@ public:
...
@@ -22,16 +22,12 @@ public:
bool
requestFreqScan
();
bool
requestFreqScan
();
bool
requestVideoSettings
();
bool
requestVideoSettings
();
bool
requestRadioSettings
();
bool
requestRadioSettings
();
#if !defined(__ios__) && !defined(__android__)
bool
requestIPSettings
();
bool
requestIPSettings
();
#endif
bool
requestRTSPURISettings
();
bool
requestRTSPURISettings
();
bool
setRadioSettings
(
const
QString
&
mode
,
const
QString
&
channel
);
bool
setRadioSettings
(
const
QString
&
mode
,
const
QString
&
channel
);
bool
setVideoSettings
(
const
QString
&
output
,
const
QString
&
mode
,
const
QString
&
rate
);
bool
setVideoSettings
(
const
QString
&
output
,
const
QString
&
mode
,
const
QString
&
rate
);
bool
setRTSPSettings
(
const
QString
&
uri
,
const
QString
&
account
,
const
QString
&
password
);
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
);
bool
setIPSettings
(
const
QString
&
localIP
,
const
QString
&
remoteIP
,
const
QString
&
netMask
);
#endif
signals:
signals:
void
updateSettings
(
QByteArray
jSonData
);
void
updateSettings
(
QByteArray
jSonData
);
...
...
src/Taisync/TaisyncSettings.qml
View file @
68a5ab42
...
@@ -195,14 +195,14 @@ QGCView {
...
@@ -195,14 +195,14 @@ QGCView {
Layout.minimumWidth
:
_labelWidth
Layout.minimumWidth
:
_labelWidth
}
}
QGCLabel
{
QGCLabel
{
text
:
QGroundControl
.
taisyncManager
.
linkC
onnected
?
QGroundControl
.
taisyncManager
.
serialNumber
:
qsTr
(
""
)
text
:
QGroundControl
.
taisyncManager
.
c
onnected
?
QGroundControl
.
taisyncManager
.
serialNumber
:
qsTr
(
""
)
Layout.minimumWidth
:
_valueWidth
Layout.minimumWidth
:
_valueWidth
}
}
QGCLabel
{
QGCLabel
{
text
:
qsTr
(
"
Firmware Version:
"
)
text
:
qsTr
(
"
Firmware Version:
"
)
}
}
QGCLabel
{
QGCLabel
{
text
:
QGroundControl
.
taisyncManager
.
linkC
onnected
?
QGroundControl
.
taisyncManager
.
fwVersion
:
qsTr
(
""
)
text
:
QGroundControl
.
taisyncManager
.
c
onnected
?
QGroundControl
.
taisyncManager
.
fwVersion
:
qsTr
(
""
)
}
}
}
}
}
}
...
@@ -322,6 +322,188 @@ QGCView {
...
@@ -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\n
Confirm change?
"
).
arg
(
localIP
.
text
)
onYes
:
{
QGroundControl
.
taisyncManager
.
setIPSettings
(
localIP
.
text
,
remoteIP
.
text
,
netMask
.
text
)
setIPDialog
.
close
()
}
onNo
:
{
setIPDialog
.
close
()
}
}
}
}
}
}
}
}
}
}
}
...
...
Write
Preview
Markdown
is supported
0%
Try again
or
attach a new file
Attach a file
Cancel
You are about to add
0
people
to the discussion. Proceed with caution.
Finish editing this message first!
Cancel
Please
register
or
sign in
to comment