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
9dba67b9
Commit
9dba67b9
authored
Dec 10, 2018
by
Gus Grubba
Browse files
Options
Browse Files
Download
Email Patches
Plain Diff
Initial work on video stream discovery
parent
cafc8cee
Changes
7
Hide whitespace changes
Inline
Side-by-side
Showing
7 changed files
with
184 additions
and
71 deletions
+184
-71
FlightDisplayViewVideo.qml
src/FlightDisplay/FlightDisplayViewVideo.qml
+1
-1
VideoManager.cc
src/FlightDisplay/VideoManager.cc
+81
-1
VideoManager.h
src/FlightDisplay/VideoManager.h
+14
-0
VideoSettings.cc
src/Settings/VideoSettings.cc
+16
-20
VideoSettings.h
src/Settings/VideoSettings.h
+11
-5
Vehicle.h
src/Vehicle/Vehicle.h
+17
-6
GeneralSettings.qml
src/ui/preferences/GeneralSettings.qml
+44
-38
No files found.
src/FlightDisplay/FlightDisplayViewVideo.qml
View file @
9dba67b9
...
@@ -22,7 +22,7 @@ import QGroundControl.Controllers 1.0
...
@@ -22,7 +22,7 @@ import QGroundControl.Controllers 1.0
Item
{
Item
{
id
:
root
id
:
root
property
double
_ar
:
QGroundControl
.
settingsManager
.
videoSettings
.
aspectRatio
.
rawValue
property
double
_ar
:
QGroundControl
.
videoManager
.
aspectRatio
property
bool
_showGrid
:
QGroundControl
.
settingsManager
.
videoSettings
.
gridLines
.
rawValue
>
0
property
bool
_showGrid
:
QGroundControl
.
settingsManager
.
videoSettings
.
gridLines
.
rawValue
>
0
property
var
_videoReceiver
:
QGroundControl
.
videoManager
.
videoReceiver
property
var
_videoReceiver
:
QGroundControl
.
videoManager
.
videoReceiver
property
var
_activeVehicle
:
QGroundControl
.
multiVehicleManager
.
activeVehicle
property
var
_activeVehicle
:
QGroundControl
.
multiVehicleManager
.
activeVehicle
...
...
src/FlightDisplay/VideoManager.cc
View file @
9dba67b9
...
@@ -25,7 +25,9 @@
...
@@ -25,7 +25,9 @@
#include "QGCToolbox.h"
#include "QGCToolbox.h"
#include "QGCCorePlugin.h"
#include "QGCCorePlugin.h"
#include "QGCOptions.h"
#include "QGCOptions.h"
#include "MultiVehicleManager.h"
#include "Settings/SettingsManager.h"
#include "Settings/SettingsManager.h"
#include "Vehicle.h"
QGC_LOGGING_CATEGORY
(
VideoManagerLog
,
"VideoManagerLog"
)
QGC_LOGGING_CATEGORY
(
VideoManagerLog
,
"VideoManagerLog"
)
...
@@ -35,6 +37,7 @@ VideoManager::VideoManager(QGCApplication* app, QGCToolbox* toolbox)
...
@@ -35,6 +37,7 @@ VideoManager::VideoManager(QGCApplication* app, QGCToolbox* toolbox)
,
_videoReceiver
(
nullptr
)
,
_videoReceiver
(
nullptr
)
,
_videoSettings
(
nullptr
)
,
_videoSettings
(
nullptr
)
,
_fullScreen
(
false
)
,
_fullScreen
(
false
)
,
_activeVehicle
(
nullptr
)
{
{
}
}
...
@@ -61,6 +64,9 @@ VideoManager::setToolbox(QGCToolbox *toolbox)
...
@@ -61,6 +64,9 @@ VideoManager::setToolbox(QGCToolbox *toolbox)
connect
(
_videoSettings
->
udpPort
(),
&
Fact
::
rawValueChanged
,
this
,
&
VideoManager
::
_udpPortChanged
);
connect
(
_videoSettings
->
udpPort
(),
&
Fact
::
rawValueChanged
,
this
,
&
VideoManager
::
_udpPortChanged
);
connect
(
_videoSettings
->
rtspUrl
(),
&
Fact
::
rawValueChanged
,
this
,
&
VideoManager
::
_rtspUrlChanged
);
connect
(
_videoSettings
->
rtspUrl
(),
&
Fact
::
rawValueChanged
,
this
,
&
VideoManager
::
_rtspUrlChanged
);
connect
(
_videoSettings
->
tcpUrl
(),
&
Fact
::
rawValueChanged
,
this
,
&
VideoManager
::
_tcpUrlChanged
);
connect
(
_videoSettings
->
tcpUrl
(),
&
Fact
::
rawValueChanged
,
this
,
&
VideoManager
::
_tcpUrlChanged
);
connect
(
_videoSettings
->
aspectRatio
(),
&
Fact
::
rawValueChanged
,
this
,
&
VideoManager
::
_aspectRatioChanged
);
MultiVehicleManager
*
manager
=
qgcApp
()
->
toolbox
()
->
multiVehicleManager
();
connect
(
manager
,
&
MultiVehicleManager
::
activeVehicleChanged
,
this
,
&
VideoManager
::
_setActiveVehicle
);
#if defined(QGC_GST_STREAMING)
#if defined(QGC_GST_STREAMING)
#ifndef QGC_DISABLE_UVC
#ifndef QGC_DISABLE_UVC
...
@@ -81,6 +87,19 @@ VideoManager::setToolbox(QGCToolbox *toolbox)
...
@@ -81,6 +87,19 @@ VideoManager::setToolbox(QGCToolbox *toolbox)
#endif
#endif
}
}
//-----------------------------------------------------------------------------
double
VideoManager
::
aspectRatio
()
{
if
(
isAutoStream
())
{
if
(
_streamInfo
.
resolution_h
&&
_streamInfo
.
resolution_v
)
{
return
static_cast
<
double
>
(
_streamInfo
.
resolution_h
)
/
static_cast
<
double
>
(
_streamInfo
.
resolution_v
);
}
return
1.0
;
}
else
{
return
_videoSettings
->
aspectRatio
()
->
rawValue
().
toDouble
();
}
}
//-----------------------------------------------------------------------------
//-----------------------------------------------------------------------------
void
void
VideoManager
::
_updateUVC
()
VideoManager
::
_updateUVC
()
...
@@ -106,6 +125,7 @@ VideoManager::_videoSourceChanged()
...
@@ -106,6 +125,7 @@ VideoManager::_videoSourceChanged()
_updateUVC
();
_updateUVC
();
emit
hasVideoChanged
();
emit
hasVideoChanged
();
emit
isGStreamerChanged
();
emit
isGStreamerChanged
();
emit
isAutoStreamChanged
();
_restartVideo
();
_restartVideo
();
}
}
...
@@ -144,7 +164,23 @@ VideoManager::isGStreamer()
...
@@ -144,7 +164,23 @@ VideoManager::isGStreamer()
{
{
#if defined(QGC_GST_STREAMING)
#if defined(QGC_GST_STREAMING)
QString
videoSource
=
_videoSettings
->
videoSource
()
->
rawValue
().
toString
();
QString
videoSource
=
_videoSettings
->
videoSource
()
->
rawValue
().
toString
();
return
videoSource
==
VideoSettings
::
videoSourceUDP
||
videoSource
==
VideoSettings
::
videoSourceRTSP
||
videoSource
==
VideoSettings
::
videoSourceTCP
;
return
videoSource
==
VideoSettings
::
videoSourceUDP
||
videoSource
==
VideoSettings
::
videoSourceRTSP
||
videoSource
==
VideoSettings
::
videoSourceAuto
||
videoSource
==
VideoSettings
::
videoSourceTCP
;
#else
return
false
;
#endif
}
//-----------------------------------------------------------------------------
bool
VideoManager
::
isAutoStream
()
{
#if defined(QGC_GST_STREAMING)
QString
videoSource
=
_videoSettings
->
videoSource
()
->
rawValue
().
toString
();
return
videoSource
==
VideoSettings
::
videoSourceAuto
;
#else
#else
return
false
;
return
false
;
#endif
#endif
...
@@ -171,6 +207,8 @@ VideoManager::_updateSettings()
...
@@ -171,6 +207,8 @@ VideoManager::_updateSettings()
_videoReceiver
->
setUri
(
_videoSettings
->
rtspUrl
()
->
rawValue
().
toString
());
_videoReceiver
->
setUri
(
_videoSettings
->
rtspUrl
()
->
rawValue
().
toString
());
else
if
(
_videoSettings
->
videoSource
()
->
rawValue
().
toString
()
==
VideoSettings
::
videoSourceTCP
)
else
if
(
_videoSettings
->
videoSource
()
->
rawValue
().
toString
()
==
VideoSettings
::
videoSourceTCP
)
_videoReceiver
->
setUri
(
QStringLiteral
(
"tcp://%1"
).
arg
(
_videoSettings
->
tcpUrl
()
->
rawValue
().
toString
()));
_videoReceiver
->
setUri
(
QStringLiteral
(
"tcp://%1"
).
arg
(
_videoSettings
->
tcpUrl
()
->
rawValue
().
toString
()));
else
if
(
isAutoStream
())
_videoReceiver
->
setUri
(
QString
(
_streamInfo
.
uri
));
}
}
//-----------------------------------------------------------------------------
//-----------------------------------------------------------------------------
...
@@ -185,3 +223,45 @@ VideoManager::_restartVideo()
...
@@ -185,3 +223,45 @@ VideoManager::_restartVideo()
_videoReceiver
->
start
();
_videoReceiver
->
start
();
#endif
#endif
}
}
//----------------------------------------------------------------------------------------
void
VideoManager
::
_setActiveVehicle
(
Vehicle
*
vehicle
)
{
if
(
_activeVehicle
)
{
disconnect
(
_activeVehicle
,
&
Vehicle
::
mavlinkMessageReceived
,
this
,
&
VideoManager
::
_vehicleMessageReceived
);
}
_activeVehicle
=
vehicle
;
if
(
_activeVehicle
)
{
if
(
isAutoStream
())
{
_videoReceiver
->
stop
();
}
//-- Video Stream Discovery
connect
(
_activeVehicle
,
&
Vehicle
::
mavlinkMessageReceived
,
this
,
&
VideoManager
::
_vehicleMessageReceived
);
_activeVehicle
->
sendMavCommand
(
0
,
// Target component
MAV_CMD_REQUEST_VIDEO_STREAM_INFORMATION
,
// Command id
false
,
// ShowError
1
,
// First camera only
0
);
// Reserved (Set to 0)
}
}
//----------------------------------------------------------------------------------------
void
VideoManager
::
_vehicleMessageReceived
(
const
mavlink_message_t
&
message
)
{
//-- For now we only handle one stream. There is no UI to pick different streams.
if
(
message
.
msgid
==
MAVLINK_MSG_ID_VIDEO_STREAM_INFORMATION
)
{
mavlink_msg_video_stream_information_decode
(
&
message
,
&
_streamInfo
);
_restartVideo
();
emit
aspectRatioChanged
();
}
}
//----------------------------------------------------------------------------------------
void
VideoManager
::
_aspectRatioChanged
()
{
emit
aspectRatioChanged
();
}
src/FlightDisplay/VideoManager.h
View file @
9dba67b9
...
@@ -15,6 +15,7 @@
...
@@ -15,6 +15,7 @@
#include <QTimer>
#include <QTimer>
#include <QUrl>
#include <QUrl>
#include "QGCMAVLink.h"
#include "QGCLoggingCategory.h"
#include "QGCLoggingCategory.h"
#include "VideoReceiver.h"
#include "VideoReceiver.h"
#include "QGCToolbox.h"
#include "QGCToolbox.h"
...
@@ -22,6 +23,7 @@
...
@@ -22,6 +23,7 @@
Q_DECLARE_LOGGING_CATEGORY
(
VideoManagerLog
)
Q_DECLARE_LOGGING_CATEGORY
(
VideoManagerLog
)
class
VideoSettings
;
class
VideoSettings
;
class
Vehicle
;
class
VideoManager
:
public
QGCTool
class
VideoManager
:
public
QGCTool
{
{
...
@@ -33,15 +35,20 @@ public:
...
@@ -33,15 +35,20 @@ public:
Q_PROPERTY
(
bool
hasVideo
READ
hasVideo
NOTIFY
hasVideoChanged
)
Q_PROPERTY
(
bool
hasVideo
READ
hasVideo
NOTIFY
hasVideoChanged
)
Q_PROPERTY
(
bool
isGStreamer
READ
isGStreamer
NOTIFY
isGStreamerChanged
)
Q_PROPERTY
(
bool
isGStreamer
READ
isGStreamer
NOTIFY
isGStreamerChanged
)
Q_PROPERTY
(
bool
isAutoStream
READ
isAutoStream
NOTIFY
isAutoStreamChanged
)
Q_PROPERTY
(
QString
videoSourceID
READ
videoSourceID
NOTIFY
videoSourceIDChanged
)
Q_PROPERTY
(
QString
videoSourceID
READ
videoSourceID
NOTIFY
videoSourceIDChanged
)
Q_PROPERTY
(
bool
uvcEnabled
READ
uvcEnabled
CONSTANT
)
Q_PROPERTY
(
bool
uvcEnabled
READ
uvcEnabled
CONSTANT
)
Q_PROPERTY
(
bool
fullScreen
READ
fullScreen
WRITE
setfullScreen
NOTIFY
fullScreenChanged
)
Q_PROPERTY
(
bool
fullScreen
READ
fullScreen
WRITE
setfullScreen
NOTIFY
fullScreenChanged
)
Q_PROPERTY
(
VideoReceiver
*
videoReceiver
READ
videoReceiver
CONSTANT
)
Q_PROPERTY
(
VideoReceiver
*
videoReceiver
READ
videoReceiver
CONSTANT
)
Q_PROPERTY
(
double
aspectRatio
READ
aspectRatio
NOTIFY
aspectRatioChanged
)
bool
hasVideo
();
bool
hasVideo
();
bool
isGStreamer
();
bool
isGStreamer
();
bool
isAutoStream
();
bool
fullScreen
()
{
return
_fullScreen
;
}
bool
fullScreen
()
{
return
_fullScreen
;
}
QString
videoSourceID
()
{
return
_videoSourceID
;
}
QString
videoSourceID
()
{
return
_videoSourceID
;
}
QString
autoURL
()
{
return
QString
(
_streamInfo
.
uri
);
}
double
aspectRatio
();
VideoReceiver
*
videoReceiver
()
{
return
_videoReceiver
;
}
VideoReceiver
*
videoReceiver
()
{
return
_videoReceiver
;
}
...
@@ -64,6 +71,8 @@ signals:
...
@@ -64,6 +71,8 @@ signals:
void
isGStreamerChanged
();
void
isGStreamerChanged
();
void
videoSourceIDChanged
();
void
videoSourceIDChanged
();
void
fullScreenChanged
();
void
fullScreenChanged
();
void
isAutoStreamChanged
();
void
aspectRatioChanged
();
private
slots
:
private
slots
:
void
_videoSourceChanged
();
void
_videoSourceChanged
();
...
@@ -71,6 +80,9 @@ private slots:
...
@@ -71,6 +80,9 @@ private slots:
void
_rtspUrlChanged
();
void
_rtspUrlChanged
();
void
_tcpUrlChanged
();
void
_tcpUrlChanged
();
void
_updateUVC
();
void
_updateUVC
();
void
_aspectRatioChanged
();
void
_setActiveVehicle
(
Vehicle
*
vehicle
);
void
_vehicleMessageReceived
(
const
mavlink_message_t
&
message
);
private:
private:
void
_updateSettings
();
void
_updateSettings
();
...
@@ -80,6 +92,8 @@ private:
...
@@ -80,6 +92,8 @@ private:
VideoSettings
*
_videoSettings
;
VideoSettings
*
_videoSettings
;
QString
_videoSourceID
;
QString
_videoSourceID
;
bool
_fullScreen
;
bool
_fullScreen
;
Vehicle
*
_activeVehicle
;
mavlink_video_stream_information_t
_streamInfo
;
};
};
#endif
#endif
src/Settings/VideoSettings.cc
View file @
9dba67b9
...
@@ -8,6 +8,8 @@
...
@@ -8,6 +8,8 @@
****************************************************************************/
****************************************************************************/
#include "VideoSettings.h"
#include "VideoSettings.h"
#include "QGCApplication.h"
#include "VideoManager.h"
#include <QQmlEngine>
#include <QQmlEngine>
#include <QtQml>
#include <QtQml>
...
@@ -17,14 +19,12 @@
...
@@ -17,14 +19,12 @@
#include <QCameraInfo>
#include <QCameraInfo>
#endif
#endif
const
char
*
VideoSettings
::
videoSourceNoVideo
=
"No Video Available"
;
const
char
*
VideoSettings
::
videoSourceNoVideo
=
"No Video Available"
;
const
char
*
VideoSettings
::
videoDisabled
=
"Video Stream Disabled"
;
const
char
*
VideoSettings
::
videoDisabled
=
"Video Stream Disabled"
;
const
char
*
VideoSettings
::
videoSourceUDP
=
"UDP Video Stream"
;
const
char
*
VideoSettings
::
videoSourceAuto
=
"Automatic Video Stream"
;
const
char
*
VideoSettings
::
videoSourceRTSP
=
"RTSP Video Stream"
;
const
char
*
VideoSettings
::
videoSourceRTSP
=
"RTSP Video Stream"
;
const
char
*
VideoSettings
::
videoSourceTCP
=
"TCP-MPEG2 Video Stream"
;
const
char
*
VideoSettings
::
videoSourceUDP
=
"UDP Video Stream"
;
#ifdef QGC_GST_TAISYNC_USB
const
char
*
VideoSettings
::
videoSourceTCP
=
"TCP-MPEG2 Video Stream"
;
const
char
*
VideoSettings
::
videoSourceTaiSyncUSB
=
"Taisync USB"
;
#endif
DECLARE_SETTINGGROUP
(
Video
,
"Video"
)
DECLARE_SETTINGGROUP
(
Video
,
"Video"
)
{
{
...
@@ -34,14 +34,12 @@ DECLARE_SETTINGGROUP(Video, "Video")
...
@@ -34,14 +34,12 @@ DECLARE_SETTINGGROUP(Video, "Video")
// Setup enum values for videoSource settings into meta data
// Setup enum values for videoSource settings into meta data
QStringList
videoSourceList
;
QStringList
videoSourceList
;
#ifdef QGC_GST_STREAMING
#ifdef QGC_GST_STREAMING
videoSourceList
.
append
(
videoSourceAuto
);
videoSourceList
.
append
(
videoSourceRTSP
);
#ifndef NO_UDP_VIDEO
#ifndef NO_UDP_VIDEO
videoSourceList
.
append
(
videoSourceUDP
);
videoSourceList
.
append
(
videoSourceUDP
);
#endif
#endif
videoSourceList
.
append
(
videoSourceRTSP
);
videoSourceList
.
append
(
videoSourceTCP
);
videoSourceList
.
append
(
videoSourceTCP
);
#ifdef QGC_GST_TAISYNC_USB
videoSourceList
.
append
(
videoSourceTaiSyncUSB
);
#endif
#endif
#endif
#ifndef QGC_DISABLE_UVC
#ifndef QGC_DISABLE_UVC
QList
<
QCameraInfo
>
cameras
=
QCameraInfo
::
availableCameras
();
QList
<
QCameraInfo
>
cameras
=
QCameraInfo
::
availableCameras
();
...
@@ -60,7 +58,6 @@ DECLARE_SETTINGGROUP(Video, "Video")
...
@@ -60,7 +58,6 @@ DECLARE_SETTINGGROUP(Video, "Video")
videoSourceVarList
.
append
(
QVariant
::
fromValue
(
videoSource
));
videoSourceVarList
.
append
(
QVariant
::
fromValue
(
videoSource
));
}
}
_nameToMetaDataMap
[
videoSourceName
]
->
setEnumInfo
(
videoSourceList
,
videoSourceVarList
);
_nameToMetaDataMap
[
videoSourceName
]
->
setEnumInfo
(
videoSourceList
,
videoSourceVarList
);
// Set default value for videoSource
// Set default value for videoSource
_setDefaults
();
_setDefaults
();
}
}
...
@@ -138,11 +135,6 @@ bool VideoSettings::streamConfigured(void)
...
@@ -138,11 +135,6 @@ bool VideoSettings::streamConfigured(void)
if
(
vSource
==
videoSourceNoVideo
||
vSource
==
videoDisabled
)
{
if
(
vSource
==
videoSourceNoVideo
||
vSource
==
videoDisabled
)
{
return
false
;
return
false
;
}
}
#ifdef QGC_GST_TAISYNC_USB
if
(
vSource
==
videoSourceTaiSyncUSB
)
{
return
true
;
}
#endif
//-- If UDP, check if port is set
//-- If UDP, check if port is set
if
(
vSource
==
videoSourceUDP
)
{
if
(
vSource
==
videoSourceUDP
)
{
return
udpPort
()
->
rawValue
().
toInt
()
!=
0
;
return
udpPort
()
->
rawValue
().
toInt
()
!=
0
;
...
@@ -151,9 +143,13 @@ bool VideoSettings::streamConfigured(void)
...
@@ -151,9 +143,13 @@ bool VideoSettings::streamConfigured(void)
if
(
vSource
==
videoSourceRTSP
)
{
if
(
vSource
==
videoSourceRTSP
)
{
return
!
rtspUrl
()
->
rawValue
().
toString
().
isEmpty
();
return
!
rtspUrl
()
->
rawValue
().
toString
().
isEmpty
();
}
}
//-- If TCP, check for URL
//-- If Auto, check for URL
if
(
vSource
==
videoSourceAuto
)
{
return
!
rtspUrl
()
->
rawValue
().
toString
().
isEmpty
();
}
//-- If Auto, check for received URL
if
(
vSource
==
videoSourceTCP
)
{
if
(
vSource
==
videoSourceTCP
)
{
return
!
tcpUrl
()
->
rawValue
().
toString
().
isEmpty
();
return
!
qgcApp
()
->
toolbox
()
->
videoManager
()
->
autoURL
().
isEmpty
();
}
}
return
false
;
return
false
;
}
}
...
...
src/Settings/VideoSettings.h
View file @
9dba67b9
...
@@ -35,18 +35,24 @@ public:
...
@@ -35,18 +35,24 @@ public:
DEFINE_SETTINGFACT
(
streamEnabled
)
DEFINE_SETTINGFACT
(
streamEnabled
)
DEFINE_SETTINGFACT
(
disableWhenDisarmed
)
DEFINE_SETTINGFACT
(
disableWhenDisarmed
)
Q_PROPERTY
(
bool
streamConfigured
READ
streamConfigured
NOTIFY
streamConfiguredChanged
)
Q_PROPERTY
(
bool
streamConfigured
READ
streamConfigured
NOTIFY
streamConfiguredChanged
)
Q_PROPERTY
(
QString
autoVideoSource
READ
autoVideoSource
CONSTANT
)
Q_PROPERTY
(
QString
rtspVideoSource
READ
rtspVideoSource
CONSTANT
)
Q_PROPERTY
(
QString
udpVideoSource
READ
udpVideoSource
CONSTANT
)
Q_PROPERTY
(
QString
tcpVideoSource
READ
tcpVideoSource
CONSTANT
)
bool
streamConfigured
();
bool
streamConfigured
();
QString
autoVideoSource
()
{
return
videoSourceAuto
;
}
QString
rtspVideoSource
()
{
return
videoSourceRTSP
;
}
QString
udpVideoSource
()
{
return
videoSourceUDP
;
}
QString
tcpVideoSource
()
{
return
videoSourceTCP
;
}
static
const
char
*
videoSourceNoVideo
;
static
const
char
*
videoSourceNoVideo
;
static
const
char
*
videoDisabled
;
static
const
char
*
videoDisabled
;
static
const
char
*
videoSourceUDP
;
static
const
char
*
videoSourceUDP
;
static
const
char
*
videoSourceRTSP
;
static
const
char
*
videoSourceRTSP
;
static
const
char
*
videoSourceAuto
;
static
const
char
*
videoSourceTCP
;
static
const
char
*
videoSourceTCP
;
#ifdef QGC_GST_TAISYNC_USB
static
const
char
*
videoSourceTaiSyncUSB
;
#endif
signals:
signals:
void
streamConfiguredChanged
();
void
streamConfiguredChanged
();
...
...
src/Vehicle/Vehicle.h
View file @
9dba67b9
...
@@ -501,7 +501,7 @@ public:
...
@@ -501,7 +501,7 @@ public:
Vehicle
(
MAV_AUTOPILOT
firmwareType
,
Vehicle
(
MAV_AUTOPILOT
firmwareType
,
MAV_TYPE
vehicleType
,
MAV_TYPE
vehicleType
,
FirmwarePluginManager
*
firmwarePluginManager
,
FirmwarePluginManager
*
firmwarePluginManager
,
QObject
*
parent
=
NULL
);
QObject
*
parent
=
nullptr
);
~
Vehicle
();
~
Vehicle
();
...
@@ -892,9 +892,9 @@ public:
...
@@ -892,9 +892,9 @@ public:
QString
formatedMessages
();
QString
formatedMessages
();
QString
formatedMessage
()
{
return
_formatedMessage
;
}
QString
formatedMessage
()
{
return
_formatedMessage
;
}
QString
latestError
()
{
return
_latestError
;
}
QString
latestError
()
{
return
_latestError
;
}
float
latitude
()
{
return
_coordinate
.
latitude
(
);
}
float
latitude
()
{
return
static_cast
<
float
>
(
_coordinate
.
latitude
()
);
}
float
longitude
()
{
return
_coordinate
.
longitude
(
);
}
float
longitude
()
{
return
static_cast
<
float
>
(
_coordinate
.
longitude
()
);
}
bool
mavPresent
()
{
return
_mav
!=
NULL
;
}
bool
mavPresent
()
{
return
_mav
!=
nullptr
;
}
int
rcRSSI
()
{
return
_rcRSSI
;
}
int
rcRSSI
()
{
return
_rcRSSI
;
}
bool
px4Firmware
()
const
{
return
_firmwareType
==
MAV_AUTOPILOT_PX4
;
}
bool
px4Firmware
()
const
{
return
_firmwareType
==
MAV_AUTOPILOT_PX4
;
}
bool
apmFirmware
()
const
{
return
_firmwareType
==
MAV_AUTOPILOT_ARDUPILOTMEGA
;
}
bool
apmFirmware
()
const
{
return
_firmwareType
==
MAV_AUTOPILOT_ARDUPILOTMEGA
;
}
...
@@ -990,8 +990,19 @@ public:
...
@@ -990,8 +990,19 @@ public:
void
sendMavCommandInt
(
int
component
,
MAV_CMD
command
,
MAV_FRAME
frame
,
bool
showError
,
float
param1
,
float
param2
,
float
param3
,
float
param4
,
double
param5
,
double
param6
,
float
param7
);
void
sendMavCommandInt
(
int
component
,
MAV_CMD
command
,
MAV_FRAME
frame
,
bool
showError
,
float
param1
,
float
param2
,
float
param3
,
float
param4
,
double
param5
,
double
param6
,
float
param7
);
/// Same as sendMavCommand but available from Qml.
/// Same as sendMavCommand but available from Qml.
Q_INVOKABLE
void
sendCommand
(
int
component
,
int
command
,
bool
showError
,
double
param1
=
0
.
0
f
,
double
param2
=
0
.
0
f
,
double
param3
=
0
.
0
f
,
double
param4
=
0
.
0
f
,
double
param5
=
0
.
0
f
,
double
param6
=
0
.
0
f
,
double
param7
=
0
.
0
f
)
Q_INVOKABLE
void
sendCommand
(
int
component
,
int
command
,
bool
showError
,
double
param1
=
0
.
0
,
double
param2
=
0
.
0
,
double
param3
=
0
.
0
,
double
param4
=
0
.
0
,
double
param5
=
0
.
0
,
double
param6
=
0
.
0
,
double
param7
=
0
.
0
)
{
sendMavCommand
(
component
,
(
MAV_CMD
)
command
,
showError
,
param1
,
param2
,
param3
,
param4
,
param5
,
param6
,
param7
);
}
{
sendMavCommand
(
component
,
static_cast
<
MAV_CMD
>
(
command
),
showError
,
static_cast
<
float
>
(
param1
),
static_cast
<
float
>
(
param2
),
static_cast
<
float
>
(
param3
),
static_cast
<
float
>
(
param4
),
static_cast
<
float
>
(
param5
),
static_cast
<
float
>
(
param6
),
static_cast
<
float
>
(
param7
));
}
int
firmwareMajorVersion
(
void
)
const
{
return
_firmwareMajorVersion
;
}
int
firmwareMajorVersion
(
void
)
const
{
return
_firmwareMajorVersion
;
}
int
firmwareMinorVersion
(
void
)
const
{
return
_firmwareMinorVersion
;
}
int
firmwareMinorVersion
(
void
)
const
{
return
_firmwareMinorVersion
;
}
...
...
src/ui/preferences/GeneralSettings.qml
View file @
9dba67b9
...
@@ -45,7 +45,14 @@ QGCView {
...
@@ -45,7 +45,14 @@ QGCView {
property
real
_panelWidth
:
_qgcView
.
width
*
_internalWidthRatio
property
real
_panelWidth
:
_qgcView
.
width
*
_internalWidthRatio
property
real
_margins
:
ScreenTools
.
defaultFontPixelWidth
property
real
_margins
:
ScreenTools
.
defaultFontPixelWidth
readonly
property
real
_internalWidthRatio
:
0.8
property
string
_videoSource
:
QGroundControl
.
settingsManager
.
videoSettings
.
videoSource
.
value
property
bool
_isGst
:
QGroundControl
.
videoManager
.
isGStreamer
property
bool
_isAutoStream
:
QGroundControl
.
videoManager
.
isAutoStream
property
bool
_isUDP
:
_isGst
&&
_videoSource
===
QGroundControl
.
settingsManager
.
videoSettings
.
udpVideoSource
property
bool
_isRTSP
:
_isGst
&&
_videoSource
===
QGroundControl
.
settingsManager
.
videoSettings
.
rtspVideoSource
property
bool
_isTCP
:
_isGst
&&
_videoSource
===
QGroundControl
.
settingsManager
.
videoSettings
.
tcpVideoSource
readonly
property
real
_internalWidthRatio
:
0.8
QGCPalette
{
id
:
qgcPal
}
QGCPalette
{
id
:
qgcPal
}
...
@@ -702,8 +709,8 @@ QGCView {
...
@@ -702,8 +709,8 @@ QGCView {
columns
:
2
columns
:
2
QGCLabel
{
QGCLabel
{
text
:
qsTr
(
"
Video Source
"
)
text
:
qsTr
(
"
Video Source
"
)
visible
:
QGroundControl
.
settingsManager
.
videoSettings
.
videoSource
.
visible
visible
:
QGroundControl
.
settingsManager
.
videoSettings
.
videoSource
.
visible
}
}
FactComboBox
{
FactComboBox
{
id
:
videoSource
id
:
videoSource
...
@@ -714,53 +721,52 @@ QGCView {
...
@@ -714,53 +721,52 @@ QGCView {
}
}
QGCLabel
{
QGCLabel
{
text
:
qsTr
(
"
UDP Port
"
)
text
:
qsTr
(
"
UDP Port
"
)
visible
:
QGroundControl
.
settingsManager
.
videoSettings
.
udpPort
.
visible
&&
QGroundControl
.
videoManager
.
isGStreamer
&&
videoSource
.
currentIndex
===
1
visible
:
_isUDP
&&
QGroundControl
.
settingsManager
.
videoSettings
.
udpPort
.
visible
}
}
FactTextField
{
FactTextField
{
Layout.preferredWidth
:
_comboFieldWidth
Layout.preferredWidth
:
_comboFieldWidth
fact
:
QGroundControl
.
settingsManager
.
videoSettings
.
udpPort
fact
:
QGroundControl
.
settingsManager
.
videoSettings
.
udpPort
visible
:
QGroundControl
.
settingsManager
.
videoSettings
.
udpPort
.
visible
&&
QGroundControl
.
videoManager
.
isGStreamer
&&
videoSource
.
currentIndex
===
1
visible
:
_isUDP
&&
QGroundControl
.
settingsManager
.
videoSettings
.
udpPort
.
visible
}
}
QGCLabel
{
QGCLabel
{
text
:
qsTr
(
"
RTSP URL
"
)
text
:
qsTr
(
"
RTSP URL
"
)
visible
:
QGroundControl
.
settingsManager
.
videoSettings
.
rtspUrl
.
visible
&&
QGroundControl
.
videoManager
.
isGStreamer
&&
videoSource
.
currentIndex
===
2
visible
:
_isRTSP
&&
QGroundControl
.
settingsManager
.
videoSettings
.
rtspUrl
.
visible
}
}
FactTextField
{
FactTextField
{
Layout.preferredWidth
:
_comboFieldWidth
Layout.preferredWidth
:
_comboFieldWidth
fact
:
QGroundControl
.
settingsManager
.
videoSettings
.
rtspUrl
fact
:
QGroundControl
.
settingsManager
.
videoSettings
.
rtspUrl
visible
:
QGroundControl
.
settingsManager
.
videoSettings
.
rtspUrl
.
visible
&&
QGroundControl
.
videoManager
.
isGStreamer
&&
videoSource
.
currentIndex
===
2
visible
:
_isRTSP
&&
QGroundControl
.
settingsManager
.
videoSettings
.
rtspUrl
.
visible
}
}
QGCLabel
{
QGCLabel
{
text
:
qsTr
(
"
TCP URL
"
)
text
:
qsTr
(
"
TCP URL
"
)
visible
:
QGroundControl
.
settingsManager
.
videoSettings
.
tcpUrl
.
visible
&&
QGroundControl
.
videoManager
.
isGStreamer
&&
videoSource
.
currentIndex
===
3
visible
:
_isTCP
&&
QGroundControl
.
settingsManager
.
videoSettings
.
tcpUrl
.
visible
}
}
FactTextField
{
FactTextField
{
Layout.preferredWidth
:
_comboFieldWidth
Layout.preferredWidth
:
_comboFieldWidth
fact
:
QGroundControl
.
settingsManager
.
videoSettings
.
tcpUrl
fact
:
QGroundControl
.
settingsManager
.
videoSettings
.
tcpUrl
visible
:
QGroundControl
.
settingsManager
.
videoSettings
.
tcpUrl
.
visible
&&
QGroundControl
.
videoManager
.
isGStreamer
&&
videoSource
.
currentIndex
===
3
visible
:
_isTCP
&&
QGroundControl
.
settingsManager
.
videoSettings
.
tcpUrl
.
visible
}
}
QGCLabel
{
QGCLabel
{
text
:
qsTr
(
"
Aspect Ratio
"
)
text
:
qsTr
(
"
Aspect Ratio
"
)
visible
:
QGroundControl
.
videoManager
.
isGStreamer
&&
videoSource
.
currentIndex
&&
videoSource
.
currentIndex
<
3
&&
QGroundControl
.
settingsManager
.
videoSettings
.
aspectRatio
.
visible
visible
:
!
_isAutoStream
&&
_isGst
&&
QGroundControl
.
settingsManager
.
videoSettings
.
aspectRatio
.
visible
}
}
FactTextField
{
FactTextField
{
Layout.preferredWidth
:
_comboFieldWidth
Layout.preferredWidth
:
_comboFieldWidth
fact
:
QGroundControl
.
settingsManager
.
videoSettings
.
aspectRatio
fact
:
QGroundControl
.
settingsManager
.
videoSettings
.
aspectRatio
visible
:
QGroundControl
.
videoManager
.
isGStreamer
&&
videoSource
.
currentIndex
&&
videoSource
.
currentIndex
<
3
&&
QGroundControl
.
settingsManager
.
videoSettings
.
aspectRatio
.
visible
visible
:
!
_isAutoStream
&&
_isGst
&&
QGroundControl
.
settingsManager
.
videoSettings
.
aspectRatio
.
visible
}
}
QGCLabel
{
QGCLabel
{
text
:
qsTr
(
"
Disable When Disarmed
"
)
text
:
qsTr
(
"
Disable When Disarmed
"
)
visible
:
QGroundControl
.
videoManager
.
isGStreamer
&&
videoSource
.
currentIndex
&&
videoSource
.
currentIndex
<
3
&&
QGroundControl
.
settingsManager
.
videoSettings
.
gridLines
.
visible
visible
:
_isGst
&&
QGroundControl
.
settingsManager
.
videoSettings
.
disableWhenDisarmed
.
visible
}
}
FactCheckBox
{
FactCheckBox
{
text
:
""
text
:
""
fact
:
QGroundControl
.
settingsManager
.
videoSettings
.
disableWhenDisarmed
fact
:
QGroundControl
.
settingsManager
.
videoSettings
.
disableWhenDisarmed
visible
:
QGroundControl
.
videoManager
.
isGStreamer
&&
videoSource
.
currentIndex
&&
videoSource
.
currentIndex
<
3
&&
QGroundControl
.
settingsManager
.
videoSettings
.
gridLines
.
visible
visible
:
_isGst
&&
QGroundControl
.
settingsManager
.
videoSettings
.
disableWhenDisarmed
.
visible
}
}
}
}
}
}
...
@@ -768,16 +774,16 @@ QGCView {
...
@@ -768,16 +774,16 @@ QGCView {
Item
{
width
:
1
;
height
:
_margins
}
Item
{
width
:
1
;
height
:
_margins
}
QGCLabel
{
QGCLabel
{
id
:
videoRecSectionLabel
id
:
videoRecSectionLabel
text
:
qsTr
(
"
Video Recording
"
)
text
:
qsTr
(
"
Video Recording
"
)
visible
:
QGroundControl
.
settingsManager
.
videoSettings
.
visible
&&
QGroundControl
.
videoManager
.
isGStreamer
&&
videoSource
.
currentIndex
&&
videoSource
.
currentIndex
<
4
visible
:
QGroundControl
.
settingsManager
.
videoSettings
.
visible
&&
_isGst
}
}
Rectangle
{
Rectangle
{
Layout.preferredWidth
:
videoRecCol
.
width
+
(
_margins
*
2
)
Layout.preferredWidth
:
videoRecCol
.
width
+
(
_margins
*
2
)
Layout.preferredHeight
:
videoRecCol
.
height
+
(
_margins
*
2
)
Layout.preferredHeight
:
videoRecCol
.
height
+
(
_margins
*
2
)
Layout.fillWidth
:
true
Layout.fillWidth
:
true
color
:
qgcPal
.
windowShade
color
:
qgcPal
.
windowShade
visible
:
videoRecSectionLabel
.
visible
visible
:
videoRecSectionLabel
.
visible
GridLayout
{
GridLayout
{
id
:
videoRecCol
id
:
videoRecCol
...
@@ -788,18 +794,18 @@ QGCView {
...
@@ -788,18 +794,18 @@ QGCView {
columns
:
2
columns
:
2
QGCLabel
{
QGCLabel
{
text
:
qsTr
(
"
Auto-Delete Files
"
)
text
:
qsTr
(
"
Auto-Delete Files
"
)
visible
:
QGroundControl
.
settingsManager
.
videoSettings
.
enableStorageLimit
.
visible
visible
:
QGroundControl
.
settingsManager
.
videoSettings
.
enableStorageLimit
.
visible
}
}
FactCheckBox
{
FactCheckBox
{
text
:
""
text
:
""
fact
:
QGroundControl
.
settingsManager
.
videoSettings
.
enableStorageLimit
fact
:
QGroundControl
.
settingsManager
.
videoSettings
.
enableStorageLimit
visible
:
QGroundControl
.
settingsManager
.
videoSettings
.
enableStorageLimit
.
visible
visible
:
QGroundControl
.
settingsManager
.
videoSettings
.
enableStorageLimit
.
visible
}
}
QGCLabel
{
QGCLabel
{
text
:
qsTr
(
"
Max Storage Usage
"
)
text
:
qsTr
(
"
Max Storage Usage
"
)
visible
:
QGroundControl
.
settingsManager
.
videoSettings
.
maxVideoSize
.
visible
&&
QGroundControl
.
settingsManager
.
videoSettings
.
enableStorageLimit
.
value
visible
:
QGroundControl
.
settingsManager
.
videoSettings
.
maxVideoSize
.
visible
&&
QGroundControl
.
settingsManager
.
videoSettings
.
enableStorageLimit
.
value
}
}
FactTextField
{
FactTextField
{
Layout.preferredWidth
:
_comboFieldWidth
Layout.preferredWidth
:
_comboFieldWidth
...
@@ -808,8 +814,8 @@ QGCView {
...
@@ -808,8 +814,8 @@ QGCView {
}
}
QGCLabel
{
QGCLabel
{
text
:
qsTr
(
"
Video File Format
"
)
text
:
qsTr
(
"
Video File Format
"
)
visible
:
QGroundControl
.
settingsManager
.
videoSettings
.
recordingFormat
.
visible
visible
:
QGroundControl
.
settingsManager
.
videoSettings
.
recordingFormat
.
visible
}
}
FactComboBox
{
FactComboBox
{
Layout.preferredWidth
:
_comboFieldWidth
Layout.preferredWidth
:
_comboFieldWidth
...
...
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