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
f9a99f80
Commit
f9a99f80
authored
Jul 30, 2017
by
Don Gagne
Committed by
GitHub
Jul 30, 2017
Browse files
Options
Browse Files
Download
Plain Diff
Merge pull request #5461 from zthorson/feature/tcp_mpeg2ts_video
Add TCP-Mpeg2TS support to available video feeds
parents
7ae2f7a4
1b3ed8f0
Changes
7
Hide whitespace changes
Inline
Side-by-side
Showing
7 changed files
with
123 additions
and
44 deletions
+123
-44
VideoManager.cc
src/FlightDisplay/VideoManager.cc
+11
-1
VideoManager.h
src/FlightDisplay/VideoManager.h
+1
-0
Video.SettingsGroup.json
src/Settings/Video.SettingsGroup.json
+8
-1
VideoSettings.cc
src/Settings/VideoSettings.cc
+13
-0
VideoSettings.h
src/Settings/VideoSettings.h
+5
-0
VideoReceiver.cc
src/VideoStreaming/VideoReceiver.cc
+69
-40
GeneralSettings.qml
src/ui/preferences/GeneralSettings.qml
+16
-2
No files found.
src/FlightDisplay/VideoManager.cc
View file @
f9a99f80
...
...
@@ -59,6 +59,7 @@ VideoManager::setToolbox(QGCToolbox *toolbox)
connect
(
_videoSettings
->
videoSource
(),
&
Fact
::
rawValueChanged
,
this
,
&
VideoManager
::
_videoSourceChanged
);
connect
(
_videoSettings
->
udpPort
(),
&
Fact
::
rawValueChanged
,
this
,
&
VideoManager
::
_udpPortChanged
);
connect
(
_videoSettings
->
rtspUrl
(),
&
Fact
::
rawValueChanged
,
this
,
&
VideoManager
::
_rtspUrlChanged
);
connect
(
_videoSettings
->
tcpUrl
(),
&
Fact
::
rawValueChanged
,
this
,
&
VideoManager
::
_tcpUrlChanged
);
#if defined(QGC_GST_STREAMING)
#ifndef QGC_DISABLE_UVC
...
...
@@ -110,6 +111,13 @@ VideoManager::_rtspUrlChanged()
_restartVideo
();
}
//-----------------------------------------------------------------------------
void
VideoManager
::
_tcpUrlChanged
()
{
_restartVideo
();
}
//-----------------------------------------------------------------------------
bool
VideoManager
::
hasVideo
()
...
...
@@ -124,7 +132,7 @@ VideoManager::isGStreamer()
{
#if defined(QGC_GST_STREAMING)
QString
videoSource
=
_videoSettings
->
videoSource
()
->
rawValue
().
toString
();
return
videoSource
==
VideoSettings
::
videoSourceUDP
||
videoSource
==
VideoSettings
::
videoSourceRTSP
;
return
videoSource
==
VideoSettings
::
videoSourceUDP
||
videoSource
==
VideoSettings
::
videoSourceRTSP
||
videoSource
==
VideoSettings
::
videoSourceTCP
;
#else
return
false
;
#endif
...
...
@@ -149,6 +157,8 @@ VideoManager::_updateSettings()
_videoReceiver
->
setUri
(
QStringLiteral
(
"udp://0.0.0.0:%1"
).
arg
(
_videoSettings
->
udpPort
()
->
rawValue
().
toInt
()));
else
if
(
_videoSettings
->
videoSource
()
->
rawValue
().
toString
()
==
VideoSettings
::
videoSourceRTSP
)
_videoReceiver
->
setUri
(
_videoSettings
->
rtspUrl
()
->
rawValue
().
toString
());
else
if
(
_videoSettings
->
videoSource
()
->
rawValue
().
toString
()
==
VideoSettings
::
videoSourceTCP
)
_videoReceiver
->
setUri
(
QStringLiteral
(
"tcp://%1"
).
arg
(
_videoSettings
->
tcpUrl
()
->
rawValue
().
toString
()));
}
//-----------------------------------------------------------------------------
...
...
src/FlightDisplay/VideoManager.h
View file @
f9a99f80
...
...
@@ -61,6 +61,7 @@ private slots:
void
_videoSourceChanged
();
void
_udpPortChanged
();
void
_rtspUrlChanged
();
void
_tcpUrlChanged
();
private:
void
_updateSettings
();
...
...
src/Settings/Video.SettingsGroup.json
View file @
f9a99f80
...
...
@@ -2,7 +2,7 @@
{
"name"
:
"VideoSource"
,
"shortDescription"
:
"Video source"
,
"longDescription"
:
"Source for video. UDP, RTSP and UVC Cameras may be supported depending on Vehicle and ground station version."
,
"longDescription"
:
"Source for video. UDP,
TCP,
RTSP and UVC Cameras may be supported depending on Vehicle and ground station version."
,
"type"
:
"string"
,
"defaultValue"
:
""
},
...
...
@@ -21,6 +21,13 @@
"type"
:
"string"
,
"defaultValue"
:
""
},
{
"name"
:
"VideoTCPUrl"
,
"shortDescription"
:
"Video TCP Url"
,
"longDescription"
:
"TCP url address and port to bind to for video stream. Example: 192.168.143.200:3001"
,
"type"
:
"string"
,
"defaultValue"
:
""
},
{
"name"
:
"VideoSavePath"
,
"shortDescription"
:
"Video save directory"
,
...
...
src/Settings/VideoSettings.cc
View file @
f9a99f80
...
...
@@ -22,6 +22,7 @@ const char* VideoSettings::videoSettingsGroupName = "Video";
const
char
*
VideoSettings
::
videoSourceName
=
"VideoSource"
;
const
char
*
VideoSettings
::
udpPortName
=
"VideoUDPPort"
;
const
char
*
VideoSettings
::
rtspUrlName
=
"VideoRTSPUrl"
;
const
char
*
VideoSettings
::
tcpUrlName
=
"VideoTCPUrl"
;
const
char
*
VideoSettings
::
videoAspectRatioName
=
"VideoAspectRatio"
;
const
char
*
VideoSettings
::
videoGridLinesName
=
"VideoGridLines"
;
const
char
*
VideoSettings
::
showRecControlName
=
"ShowRecControl"
;
...
...
@@ -32,11 +33,13 @@ const char* VideoSettings::videoSourceNoVideo = "No Video Available";
const
char
*
VideoSettings
::
videoDisabled
=
"Video Stream Disabled"
;
const
char
*
VideoSettings
::
videoSourceUDP
=
"UDP Video Stream"
;
const
char
*
VideoSettings
::
videoSourceRTSP
=
"RTSP Video Stream"
;
const
char
*
VideoSettings
::
videoSourceTCP
=
"TCP-MPEG2 Video Stream"
;
VideoSettings
::
VideoSettings
(
QObject
*
parent
)
:
SettingsGroup
(
videoSettingsGroupName
,
QString
()
/* root settings group */
,
parent
)
,
_videoSourceFact
(
NULL
)
,
_udpPortFact
(
NULL
)
,
_tcpUrlFact
(
NULL
)
,
_rtspUrlFact
(
NULL
)
,
_videoAspectRatioFact
(
NULL
)
,
_gridLinesFact
(
NULL
)
...
...
@@ -55,6 +58,7 @@ VideoSettings::VideoSettings(QObject* parent)
videoSourceList
.
append
(
videoSourceUDP
);
#endif
videoSourceList
.
append
(
videoSourceRTSP
);
videoSourceList
.
append
(
videoSourceTCP
);
#endif
#ifndef QGC_DISABLE_UVC
QList
<
QCameraInfo
>
cameras
=
QCameraInfo
::
availableCameras
();
...
...
@@ -109,6 +113,15 @@ Fact* VideoSettings::rtspUrl(void)
return
_rtspUrlFact
;
}
Fact
*
VideoSettings
::
tcpUrl
(
void
)
{
if
(
!
_tcpUrlFact
)
{
_tcpUrlFact
=
_createSettingsFact
(
tcpUrlName
);
}
return
_tcpUrlFact
;
}
Fact
*
VideoSettings
::
aspectRatio
(
void
)
{
if
(
!
_videoAspectRatioFact
)
{
...
...
src/Settings/VideoSettings.h
View file @
f9a99f80
...
...
@@ -21,6 +21,7 @@ public:
Q_PROPERTY
(
Fact
*
videoSource
READ
videoSource
CONSTANT
)
Q_PROPERTY
(
Fact
*
udpPort
READ
udpPort
CONSTANT
)
Q_PROPERTY
(
Fact
*
tcpUrl
READ
tcpUrl
CONSTANT
)
Q_PROPERTY
(
Fact
*
rtspUrl
READ
rtspUrl
CONSTANT
)
Q_PROPERTY
(
Fact
*
aspectRatio
READ
aspectRatio
CONSTANT
)
Q_PROPERTY
(
Fact
*
gridLines
READ
gridLines
CONSTANT
)
...
...
@@ -31,6 +32,7 @@ public:
Fact
*
videoSource
(
void
);
Fact
*
udpPort
(
void
);
Fact
*
rtspUrl
(
void
);
Fact
*
tcpUrl
(
void
);
Fact
*
aspectRatio
(
void
);
Fact
*
gridLines
(
void
);
Fact
*
showRecControl
(
void
);
...
...
@@ -42,6 +44,7 @@ public:
static
const
char
*
videoSourceName
;
static
const
char
*
udpPortName
;
static
const
char
*
rtspUrlName
;
static
const
char
*
tcpUrlName
;
static
const
char
*
videoAspectRatioName
;
static
const
char
*
videoGridLinesName
;
static
const
char
*
showRecControlName
;
...
...
@@ -52,10 +55,12 @@ public:
static
const
char
*
videoDisabled
;
static
const
char
*
videoSourceUDP
;
static
const
char
*
videoSourceRTSP
;
static
const
char
*
videoSourceTCP
;
private:
SettingsFact
*
_videoSourceFact
;
SettingsFact
*
_udpPortFact
;
SettingsFact
*
_tcpUrlFact
;
SettingsFact
*
_rtspUrlFact
;
SettingsFact
*
_videoAspectRatioFact
;
SettingsFact
*
_gridLinesFact
;
...
...
src/VideoStreaming/VideoReceiver.cc
View file @
f9a99f80
...
...
@@ -131,8 +131,8 @@ newPadCB(GstElement* element, GstPad* pad, gpointer data)
gchar
*
description
=
gst_caps_to_string
(
p_caps
);
qCDebug
(
VideoReceiverLog
)
<<
p_caps
<<
", "
<<
description
;
g_free
(
description
);
GstElement
*
p_rtph264depay
=
GST_ELEMENT
(
data
);
if
(
gst_element_link_pads
(
element
,
name
,
p_rtph264depay
,
"sink"
)
==
false
)
GstElement
*
sink
=
GST_ELEMENT
(
data
);
if
(
gst_element_link_pads
(
element
,
name
,
sink
,
"sink"
)
==
false
)
qCritical
()
<<
"newPadCB : failed to link elements
\n
"
;
g_free
(
name
);
}
...
...
@@ -222,14 +222,16 @@ VideoReceiver::start()
bool
isUdp
=
_uri
.
contains
(
"udp://"
);
bool
isRtsp
=
_uri
.
contains
(
"rtsp://"
);
bool
isTCP
=
_uri
.
contains
(
"tcp://"
);
//-- For RTSP, check to see if server is there first
if
(
!
_serverPresent
&&
isRtsp
)
{
//-- For RTSP
and TCP
, check to see if server is there first
if
(
!
_serverPresent
&&
(
isRtsp
||
isTCP
)
)
{
_timer
.
start
(
100
);
return
;
}
bool
running
=
false
;
bool
pipelineUp
=
false
;
GstElement
*
dataSource
=
NULL
;
GstCaps
*
caps
=
NULL
;
...
...
@@ -247,6 +249,8 @@ VideoReceiver::start()
if
(
isUdp
)
{
dataSource
=
gst_element_factory_make
(
"udpsrc"
,
"udp-source"
);
}
else
if
(
isTCP
)
{
dataSource
=
gst_element_factory_make
(
"tcpclientsrc"
,
"tcpclient-source"
);
}
else
{
dataSource
=
gst_element_factory_make
(
"rtspsrc"
,
"rtsp-source"
);
}
...
...
@@ -262,17 +266,24 @@ VideoReceiver::start()
break
;
}
g_object_set
(
G_OBJECT
(
dataSource
),
"uri"
,
qPrintable
(
_uri
),
"caps"
,
caps
,
NULL
);
}
else
if
(
isTCP
)
{
QUrl
url
(
_uri
);
g_object_set
(
G_OBJECT
(
dataSource
),
"host"
,
qPrintable
(
url
.
host
()),
"port"
,
url
.
port
(),
NULL
);
}
else
{
g_object_set
(
G_OBJECT
(
dataSource
),
"location"
,
qPrintable
(
_uri
),
"latency"
,
17
,
"udp-reconnect"
,
1
,
"timeout"
,
static_cast
<
guint64
>
(
5000000
),
NULL
);
}
if
((
demux
=
gst_element_factory_make
(
"rtph264depay"
,
"rtp-h264-depacketizer"
))
==
NULL
)
{
qCritical
()
<<
"VideoReceiver::start() failed. Error with gst_element_factory_make('rtph264depay')"
;
break
;
}
if
(
!
isUdp
)
{
g_signal_connect
(
dataSource
,
"pad-added"
,
G_CALLBACK
(
newPadCB
),
demux
);
// Currently, we expect H264 when using anything except for TCP. Long term we may want this to be settable
if
(
isTCP
)
{
if
((
demux
=
gst_element_factory_make
(
"tsdemux"
,
"mpeg2-ts-demuxer"
))
==
NULL
)
{
qCritical
()
<<
"VideoReceiver::start() failed. Error with gst_element_factory_make('tsdemux')"
;
break
;
}
}
else
{
if
((
demux
=
gst_element_factory_make
(
"rtph264depay"
,
"rtp-h264-depacketizer"
))
==
NULL
)
{
qCritical
()
<<
"VideoReceiver::start() failed. Error with gst_element_factory_make('rtph264depay')"
;
break
;
}
}
if
((
parser
=
gst_element_factory_make
(
"h264parse"
,
"h264-parser"
))
==
NULL
)
{
...
...
@@ -286,6 +297,8 @@ VideoReceiver::start()
}
if
((
queue
=
gst_element_factory_make
(
"queue"
,
NULL
))
==
NULL
)
{
// TODO: We may want to add queue2 max-size-buffers=1 to get lower latency
// We should compare gstreamer scripts to QGroundControl to determine the need
qCritical
()
<<
"VideoReceiver::start() failed. Error with gst_element_factory_make('queue')"
;
break
;
}
...
...
@@ -301,21 +314,33 @@ VideoReceiver::start()
}
gst_bin_add_many
(
GST_BIN
(
_pipeline
),
dataSource
,
demux
,
parser
,
_tee
,
queue
,
decoder
,
queue1
,
_videoSink
,
NULL
);
pipelineUp
=
true
;
if
(
isUdp
)
{
// Link the pipeline in front of the tee
if
(
!
gst_element_link_many
(
dataSource
,
demux
,
parser
,
_tee
,
queue
,
decoder
,
queue1
,
_videoSink
,
NULL
))
{
qCritical
()
<<
"Unable to link elements."
;
qCritical
()
<<
"Unable to link UDP elements."
;
break
;
}
}
else
if
(
isTCP
)
{
if
(
!
gst_element_link
(
dataSource
,
demux
))
{
qCritical
()
<<
"Unable to link TCP dataSource to Demux."
;
break
;
}
if
(
!
gst_element_link_many
(
parser
,
_tee
,
queue
,
decoder
,
queue1
,
_videoSink
,
NULL
))
{
qCritical
()
<<
"Unable to link TCP pipline to parser."
;
break
;
}
g_signal_connect
(
demux
,
"pad-added"
,
G_CALLBACK
(
newPadCB
),
parser
);
}
else
{
g_signal_connect
(
dataSource
,
"pad-added"
,
G_CALLBACK
(
newPadCB
),
demux
);
if
(
!
gst_element_link_many
(
demux
,
parser
,
_tee
,
queue
,
decoder
,
_videoSink
,
NULL
))
{
qCritical
()
<<
"Unable to link elements."
;
qCritical
()
<<
"Unable to link
RTSP
elements."
;
break
;
}
}
dataSource
=
demux
=
parser
=
queue
=
decoder
=
NULL
;
dataSource
=
demux
=
parser
=
queue
=
decoder
=
queue1
=
NULL
;
GstBus
*
bus
=
NULL
;
...
...
@@ -338,39 +363,43 @@ VideoReceiver::start()
if
(
!
running
)
{
qCritical
()
<<
"VideoReceiver::start() failed"
;
if
(
decoder
!=
NULL
)
{
gst_object_unref
(
decoder
);
decoder
=
NULL
;
// In newer versions, the pipeline will clean up all references that are added to it
if
(
_pipeline
!=
NULL
)
{
gst_object_unref
(
_pipeline
);
_pipeline
=
NULL
;
}
if
(
parser
!=
NULL
)
{
gst_object_unref
(
parser
);
parser
=
NULL
;
}
// If we failed before adding items to the pipeline, then clean up
if
(
!
pipelineUp
)
{
if
(
decoder
!=
NULL
)
{
gst_object_unref
(
decoder
);
decoder
=
NULL
;
}
if
(
demux
!=
NULL
)
{
gst_object_unref
(
demux
);
demux
=
NULL
;
}
if
(
parser
!=
NULL
)
{
gst_object_unref
(
parser
);
parser
=
NULL
;
}
if
(
dataSource
!=
NULL
)
{
gst_object_unref
(
dataSource
);
dataSource
=
NULL
;
}
if
(
demux
!=
NULL
)
{
gst_object_unref
(
demux
);
demux
=
NULL
;
}
if
(
_te
e
!=
NULL
)
{
gst_object_unref
(
_te
e
);
dataSource
=
NULL
;
}
if
(
dataSourc
e
!=
NULL
)
{
gst_object_unref
(
dataSourc
e
);
dataSource
=
NULL
;
}
if
(
queu
e
!=
NULL
)
{
gst_object_unref
(
queu
e
);
dataSource
=
NULL
;
}
if
(
_te
e
!=
NULL
)
{
gst_object_unref
(
_te
e
);
dataSource
=
NULL
;
}
if
(
_pipeline
!=
NULL
)
{
gst_object_unref
(
_pipeline
);
_pipeline
=
NULL
;
if
(
queue
!=
NULL
)
{
gst_object_unref
(
queue
);
dataSource
=
NULL
;
}
}
_running
=
false
;
...
...
src/ui/preferences/GeneralSettings.qml
View file @
f9a99f80
...
...
@@ -555,6 +555,20 @@ QGCView {
anchors.verticalCenter
:
parent
.
verticalCenter
}
}
Row
{
spacing
:
ScreenTools
.
defaultFontPixelWidth
visible
:
QGroundControl
.
settingsManager
.
videoSettings
.
tcpUrl
.
visible
&&
QGroundControl
.
videoManager
.
isGStreamer
&&
videoSource
.
currentIndex
===
3
QGCLabel
{
text
:
qsTr
(
"
TCP URL:
"
)
width
:
_labelWidth
anchors.verticalCenter
:
parent
.
verticalCenter
}
FactTextField
{
width
:
_editFieldWidth
fact
:
QGroundControl
.
settingsManager
.
videoSettings
.
tcpUrl
anchors.verticalCenter
:
parent
.
verticalCenter
}
}
Row
{
spacing
:
ScreenTools
.
defaultFontPixelWidth
visible
:
QGroundControl
.
videoManager
.
isGStreamer
&&
videoSource
.
currentIndex
&&
videoSource
.
currentIndex
<
3
&&
QGroundControl
.
settingsManager
.
videoSettings
.
aspectRatio
.
visible
...
...
@@ -613,7 +627,7 @@ QGCView {
anchors.centerIn
:
parent
Row
{
spacing
:
ScreenTools
.
defaultFontPixelWidth
visible
:
QGroundControl
.
videoManager
.
isGStreamer
&&
videoSource
.
currentIndex
&&
videoSource
.
currentIndex
<
3
&&
QGroundControl
.
settingsManager
.
videoSettings
.
maxVideoSize
.
visible
visible
:
QGroundControl
.
videoManager
.
isGStreamer
&&
videoSource
.
currentIndex
&&
videoSource
.
currentIndex
<
4
&&
QGroundControl
.
settingsManager
.
videoSettings
.
maxVideoSize
.
visible
QGCLabel
{
text
:
qsTr
(
"
Max Storage Usage:
"
)
width
:
_labelWidth
...
...
@@ -627,7 +641,7 @@ QGCView {
}
Row
{
spacing
:
ScreenTools
.
defaultFontPixelWidth
visible
:
QGroundControl
.
videoManager
.
isGStreamer
&&
videoSource
.
currentIndex
&&
videoSource
.
currentIndex
<
3
&&
QGroundControl
.
settingsManager
.
videoSettings
.
recordingFormat
.
visible
visible
:
QGroundControl
.
videoManager
.
isGStreamer
&&
videoSource
.
currentIndex
&&
videoSource
.
currentIndex
<
4
&&
QGroundControl
.
settingsManager
.
videoSettings
.
recordingFormat
.
visible
QGCLabel
{
text
:
qsTr
(
"
Video File Format:
"
)
width
:
_labelWidth
...
...
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