Skip to content
GitLab
Projects
Groups
Snippets
/
Help
Help
Support
Community forum
Keyboard shortcuts
?
Submit feedback
Contribute to GitLab
Sign in
Toggle navigation
Menu
Open sidebar
Valentin Platzgummer
qgroundcontrol
Commits
ace5e73b
Unverified
Commit
ace5e73b
authored
May 16, 2019
by
Gus Grubba
Committed by
GitHub
May 16, 2019
Browse files
Merge pull request #7435 from MatejFranceskin/pr-restart-video-stream-after-change
Restart video stream after change
parents
a6a161ca
f8182edd
Changes
6
Show whitespace changes
Inline
Side-by-side
src/Camera/QGCCameraControl.cc
View file @
ace5e73b
...
...
@@ -70,6 +70,9 @@ const char* QGCCameraControl::kCAM_SHUTTERSPD = "CAM_SHUTTERSPD";
const
char
*
QGCCameraControl
::
kCAM_APERTURE
=
"CAM_APERTURE"
;
const
char
*
QGCCameraControl
::
kCAM_WBMODE
=
"CAM_WBMODE"
;
const
char
*
QGCCameraControl
::
kCAM_MODE
=
"CAM_MODE"
;
const
char
*
QGCCameraControl
::
kCAM_BITRATE
=
"CAM_BITRATE"
;
const
char
*
QGCCameraControl
::
kCAM_FPS
=
"CAM_FPS"
;
const
char
*
QGCCameraControl
::
kCAM_ENC
=
"CAM_ENC"
;
//-----------------------------------------------------------------------------
QGCCameraOptionExclusion
::
QGCCameraOptionExclusion
(
QObject
*
parent
,
QString
param_
,
QString
value_
,
QStringList
exclusions_
)
...
...
@@ -2105,6 +2108,27 @@ QGCCameraControl::mode()
return
_paramComplete
?
getFact
(
kCAM_MODE
)
:
nullptr
;
}
//-----------------------------------------------------------------------------
Fact
*
QGCCameraControl
::
bitRate
()
{
return
_paramComplete
?
getFact
(
kCAM_BITRATE
)
:
nullptr
;
}
//-----------------------------------------------------------------------------
Fact
*
QGCCameraControl
::
frameRate
()
{
return
_paramComplete
?
getFact
(
kCAM_FPS
)
:
nullptr
;
}
//-----------------------------------------------------------------------------
Fact
*
QGCCameraControl
::
videoEncoding
()
{
return
_paramComplete
?
getFact
(
kCAM_ENC
)
:
nullptr
;
}
//-----------------------------------------------------------------------------
QGCVideoStreamInfo
::
QGCVideoStreamInfo
(
QObject
*
parent
,
const
mavlink_video_stream_information_t
*
si
)
:
QObject
(
parent
)
...
...
src/Camera/QGCCameraControl.h
View file @
ace5e73b
...
...
@@ -167,6 +167,9 @@ public:
Q_PROPERTY
(
Fact
*
aperture
READ
aperture
NOTIFY
parametersReady
)
Q_PROPERTY
(
Fact
*
wb
READ
wb
NOTIFY
parametersReady
)
Q_PROPERTY
(
Fact
*
mode
READ
mode
NOTIFY
parametersReady
)
Q_PROPERTY
(
Fact
*
bitRate
READ
bitRate
NOTIFY
parametersReady
)
Q_PROPERTY
(
Fact
*
frameRate
READ
frameRate
NOTIFY
parametersReady
)
Q_PROPERTY
(
Fact
*
videoEncoding
READ
videoEncoding
NOTIFY
parametersReady
)
Q_PROPERTY
(
QStringList
activeSettings
READ
activeSettings
NOTIFY
activeSettingsChanged
)
Q_PROPERTY
(
VideoStatus
videoStatus
READ
videoStatus
NOTIFY
videoStatusChanged
)
...
...
@@ -252,6 +255,9 @@ public:
virtual
Fact
*
aperture
();
virtual
Fact
*
wb
();
virtual
Fact
*
mode
();
virtual
Fact
*
bitRate
();
virtual
Fact
*
frameRate
();
virtual
Fact
*
videoEncoding
();
//-- Stream names to show the user (for selection)
virtual
QStringList
streamLabels
()
{
return
_streamLabels
;
}
...
...
@@ -292,6 +298,9 @@ public:
static
const
char
*
kCAM_APERTURE
;
static
const
char
*
kCAM_WBMODE
;
static
const
char
*
kCAM_MODE
;
static
const
char
*
kCAM_BITRATE
;
static
const
char
*
kCAM_FPS
;
static
const
char
*
kCAM_ENC
;
signals:
void
infoChanged
();
...
...
src/FlightDisplay/VideoManager.cc
View file @
ace5e73b
/****************************************************************************
*
* (c) 2009-201
6
QGROUNDCONTROL PROJECT <http://www.qgroundcontrol.org>
* (c) 2009-201
9
QGROUNDCONTROL PROJECT <http://www.qgroundcontrol.org>
*
* QGroundControl is licensed according to the terms in the file
* COPYING.md in the root of the source code directory.
...
...
@@ -206,28 +206,28 @@ VideoManager::_videoSourceChanged()
emit
hasVideoChanged
();
emit
isGStreamerChanged
();
emit
isAutoStreamChanged
();
_
restartVideo
();
restartVideo
();
}
//-----------------------------------------------------------------------------
void
VideoManager
::
_udpPortChanged
()
{
_
restartVideo
();
restartVideo
();
}
//-----------------------------------------------------------------------------
void
VideoManager
::
_rtspUrlChanged
()
{
_
restartVideo
();
restartVideo
();
}
//-----------------------------------------------------------------------------
void
VideoManager
::
_tcpUrlChanged
()
{
_
restartVideo
();
restartVideo
();
}
//-----------------------------------------------------------------------------
...
...
@@ -275,6 +275,13 @@ VideoManager::_updateSettings()
return
;
//-- Auto discovery
if
(
_activeVehicle
&&
_activeVehicle
->
dynamicCameras
())
{
QGCCameraControl
*
pCamera
=
_activeVehicle
->
dynamicCameras
()
->
currentCameraInstance
();
if
(
pCamera
)
{
Fact
*
fact
=
pCamera
->
videoEncoding
();
if
(
fact
)
{
_videoReceiver
->
setVideoDecoder
(
static_cast
<
VideoReceiver
::
VideoEncoding
>
(
fact
->
rawValue
().
toInt
()));
}
}
QGCVideoStreamInfo
*
pInfo
=
_activeVehicle
->
dynamicCameras
()
->
currentStreamInstance
();
if
(
pInfo
)
{
qCDebug
(
VideoManagerLog
)
<<
"Configure primary stream: "
<<
pInfo
->
uri
();
...
...
@@ -329,7 +336,7 @@ VideoManager::_updateSettings()
//-----------------------------------------------------------------------------
void
VideoManager
::
_
restartVideo
()
VideoManager
::
restartVideo
()
{
#if defined(QGC_GST_STREAMING)
qCDebug
(
VideoManagerLog
)
<<
"Restart video streaming"
;
...
...
@@ -350,13 +357,13 @@ VideoManager::_setActiveVehicle(Vehicle* vehicle)
if
(
pCamera
)
{
pCamera
->
stopStream
();
}
disconnect
(
_activeVehicle
->
dynamicCameras
(),
&
QGCCameraManager
::
streamChanged
,
this
,
&
VideoManager
::
_
restartVideo
);
disconnect
(
_activeVehicle
->
dynamicCameras
(),
&
QGCCameraManager
::
streamChanged
,
this
,
&
VideoManager
::
restartVideo
);
}
}
_activeVehicle
=
vehicle
;
if
(
_activeVehicle
)
{
if
(
_activeVehicle
->
dynamicCameras
())
{
connect
(
_activeVehicle
->
dynamicCameras
(),
&
QGCCameraManager
::
streamChanged
,
this
,
&
VideoManager
::
_
restartVideo
);
connect
(
_activeVehicle
->
dynamicCameras
(),
&
QGCCameraManager
::
streamChanged
,
this
,
&
VideoManager
::
restartVideo
);
QGCCameraControl
*
pCamera
=
_activeVehicle
->
dynamicCameras
()
->
currentCameraInstance
();
if
(
pCamera
)
{
pCamera
->
resumeStream
();
...
...
@@ -364,7 +371,7 @@ VideoManager::_setActiveVehicle(Vehicle* vehicle)
}
}
emit
autoStreamConfiguredChanged
();
_
restartVideo
();
restartVideo
();
}
//----------------------------------------------------------------------------------------
...
...
src/FlightDisplay/VideoManager.h
View file @
ace5e73b
/****************************************************************************
*
* (c) 2009-201
6
QGROUNDCONTROL PROJECT <http://www.qgroundcontrol.org>
* (c) 2009-201
9
QGROUNDCONTROL PROJECT <http://www.qgroundcontrol.org>
*
* QGroundControl is licensed according to the terms in the file
* COPYING.md in the root of the source code directory.
...
...
@@ -62,6 +62,7 @@ public:
double
thermalHfov
();
bool
autoStreamConfigured
();
bool
hasThermal
();
void
restartVideo
();
VideoReceiver
*
videoReceiver
()
{
return
_videoReceiver
;
}
VideoReceiver
*
thermalVideoReceiver
()
{
return
_thermalVideoReceiver
;
}
...
...
@@ -99,7 +100,6 @@ private slots:
void
_updateUVC
();
void
_setActiveVehicle
(
Vehicle
*
vehicle
);
void
_aspectRatioChanged
();
void
_restartVideo
();
private:
void
_updateSettings
();
...
...
src/VideoStreaming/VideoReceiver.cc
View file @
ace5e73b
/****************************************************************************
*
* (c) 2009-201
6
QGROUNDCONTROL PROJECT <http://www.qgroundcontrol.org>
* (c) 2009-201
9
QGROUNDCONTROL PROJECT <http://www.qgroundcontrol.org>
*
* QGroundControl is licensed according to the terms in the file
* COPYING.md in the root of the source code directory.
...
...
@@ -58,14 +58,13 @@ VideoReceiver::VideoReceiver(QObject* parent)
,
_streaming
(
false
)
,
_starting
(
false
)
,
_stopping
(
false
)
,
_stop
(
true
)
,
_sink
(
nullptr
)
,
_tee
(
nullptr
)
,
_pipeline
(
nullptr
)
,
_pipelineStopRec
(
nullptr
)
,
_videoSink
(
nullptr
)
,
_socket
(
nullptr
)
,
_serverPresent
(
false
)
,
_rtspTestInterval_ms
(
5000
)
,
_restart_time_ms
(
1389
)
,
_udpReconnect_us
(
5000000
)
#endif
,
_videoSurface
(
nullptr
)
...
...
@@ -76,9 +75,10 @@ VideoReceiver::VideoReceiver(QObject* parent)
_videoSurface
=
new
VideoSurface
;
_videoSettings
=
qgcApp
()
->
toolbox
()
->
settingsManager
()
->
videoSettings
();
#if defined(QGC_GST_STREAMING)
setVideoDecoder
(
H264_SW
);
_setVideoSink
(
_videoSurface
->
videoSink
());
_timer
.
setSingleShot
(
true
);
connect
(
&
_timer
,
&
QTimer
::
timeout
,
this
,
&
VideoReceiver
::
_timeout
);
_restart
_timer
.
setSingleShot
(
true
);
connect
(
&
_
restart_
timer
,
&
QTimer
::
timeout
,
this
,
&
VideoReceiver
::
_
restart_
timeout
);
connect
(
this
,
&
VideoReceiver
::
msgErrorReceived
,
this
,
&
VideoReceiver
::
_handleError
);
connect
(
this
,
&
VideoReceiver
::
msgEOSReceived
,
this
,
&
VideoReceiver
::
_handleEOS
);
connect
(
this
,
&
VideoReceiver
::
msgStateChangedReceived
,
this
,
&
VideoReceiver
::
_handleStateChanged
);
...
...
@@ -91,9 +91,6 @@ VideoReceiver::~VideoReceiver()
{
#if defined(QGC_GST_STREAMING)
stop
();
if
(
_socket
)
{
delete
_socket
;
}
if
(
_videoSink
)
{
gst_object_unref
(
_videoSink
);
}
...
...
@@ -130,8 +127,7 @@ VideoReceiver::grabImage(QString imageFile)
static
void
newPadCB
(
GstElement
*
element
,
GstPad
*
pad
,
gpointer
data
)
{
gchar
*
name
;
name
=
gst_pad_get_name
(
pad
);
gchar
*
name
=
gst_pad_get_name
(
pad
);
//g_print("A new pad %s was created\n", name);
GstCaps
*
p_caps
=
gst_pad_get_pad_template_caps
(
pad
);
gchar
*
description
=
gst_caps_to_string
(
p_caps
);
...
...
@@ -142,68 +138,12 @@ newPadCB(GstElement* element, GstPad* pad, gpointer data)
qCritical
()
<<
"newPadCB : failed to link elements
\n
"
;
g_free
(
name
);
}
#endif
//-----------------------------------------------------------------------------
#if defined(QGC_GST_STREAMING)
void
VideoReceiver
::
_connected
()
{
//-- Server showed up. Now we start the stream.
_timer
.
stop
();
_socket
->
deleteLater
();
_socket
=
nullptr
;
if
(
_videoSettings
->
streamEnabled
()
->
rawValue
().
toBool
())
{
_serverPresent
=
true
;
start
();
}
}
#endif
//-----------------------------------------------------------------------------
#if defined(QGC_GST_STREAMING)
void
VideoReceiver
::
_
socketError
(
QAbstractSocket
::
SocketError
socketError
)
VideoReceiver
::
_
restart_timeout
(
)
{
Q_UNUSED
(
socketError
);
_socket
->
deleteLater
();
_socket
=
nullptr
;
//-- Try again in a while
if
(
_videoSettings
->
streamEnabled
()
->
rawValue
().
toBool
())
{
_timer
.
start
(
_rtspTestInterval_ms
);
}
}
#endif
//-----------------------------------------------------------------------------
#if defined(QGC_GST_STREAMING)
void
VideoReceiver
::
_timeout
()
{
//-- If socket is live, we got no connection nor a socket error
if
(
_socket
)
{
delete
_socket
;
_socket
=
nullptr
;
}
if
(
_videoSettings
->
streamEnabled
()
->
rawValue
().
toBool
())
{
//-- RTSP will try to connect to the server. If it cannot connect,
// it will simply give up and never try again. Instead, we keep
// attempting a connection on this timer. Once a connection is
// found to be working, only then we actually start the stream.
QUrl
url
(
_uri
);
//-- If RTSP and no port is defined, set default RTSP port (554)
if
(
_uri
.
contains
(
"rtsp://"
)
&&
url
.
port
()
<=
0
)
{
url
.
setPort
(
554
);
}
_socket
=
new
QTcpSocket
;
QNetworkProxy
tempProxy
;
tempProxy
.
setType
(
QNetworkProxy
::
DefaultProxy
);
_socket
->
setProxy
(
tempProxy
);
connect
(
_socket
,
static_cast
<
void
(
QTcpSocket
::*
)(
QAbstractSocket
::
SocketError
)
>
(
&
QTcpSocket
::
error
),
this
,
&
VideoReceiver
::
_socketError
);
connect
(
_socket
,
&
QTcpSocket
::
connected
,
this
,
&
VideoReceiver
::
_connected
);
_socket
->
connectToHost
(
url
.
host
(),
static_cast
<
uint16_t
>
(
url
.
port
()));
_timer
.
start
(
_rtspTestInterval_ms
);
}
qgcApp
()
->
toolbox
()
->
videoManager
()
->
restartVideo
();
}
#endif
...
...
@@ -213,14 +153,12 @@ VideoReceiver::_timeout()
// +-->queue-->decoder-->_videosink
// |
// datasource-->demux-->parser-->tee
//
// ^
// |
// +-Here we will later link elements for recording
void
VideoReceiver
::
start
()
{
qCDebug
(
VideoReceiverLog
)
<<
"start():"
<<
_uri
;
if
(
qgcApp
()
->
runningUnitTests
())
{
return
;
}
...
...
@@ -229,9 +167,10 @@ VideoReceiver::start()
qCDebug
(
VideoReceiverLog
)
<<
"start() but not enabled/configured"
;
return
;
}
#if defined(QGC_GST_STREAMING)
_stop
=
false
;
qCDebug
(
VideoReceiverLog
)
<<
"start()
"
;
qCDebug
(
VideoReceiverLog
)
<<
"start()
:"
<<
_uri
;
#if defined(QGC_GST_TAISYNC_ENABLED) && (defined(__android__) || defined(__ios__))
//-- Taisync on iOS or Android sends a raw h.264 stream
...
...
@@ -240,7 +179,6 @@ VideoReceiver::start()
bool
isTaisyncUSB
=
false
;
#endif
bool
isUdp
=
_uri
.
contains
(
"udp://"
)
&&
!
isTaisyncUSB
;
bool
isRtsp
=
_uri
.
contains
(
"rtsp://"
)
&&
!
isTaisyncUSB
;
bool
isTCP
=
_uri
.
contains
(
"tcp://"
)
&&
!
isTaisyncUSB
;
bool
isMPEGTS
=
_uri
.
contains
(
"mpegts://"
)
&&
!
isTaisyncUSB
;
...
...
@@ -259,12 +197,6 @@ VideoReceiver::start()
_starting
=
true
;
//-- 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
;
...
...
@@ -324,15 +256,15 @@ VideoReceiver::start()
}
}
else
{
if
(
!
isTaisyncUSB
)
{
if
((
demux
=
gst_element_factory_make
(
"rtph264
depay
"
,
"rtp-
h264-
depacketizer"
))
==
nullptr
)
{
qCritical
()
<<
"VideoReceiver::start() failed. Error with gst_element_factory_make('
rtph264depay
')"
;
if
((
demux
=
gst_element_factory_make
(
_
depay
Name
,
"rtp-depacketizer"
))
==
nullptr
)
{
qCritical
()
<<
"VideoReceiver::start() failed. Error with gst_element_factory_make('
"
<<
_depayName
<<
"
')"
;
break
;
}
}
}
if
((
parser
=
gst_element_factory_make
(
"h264parse"
,
"h264-
parser"
))
==
nullptr
)
{
qCritical
()
<<
"VideoReceiver::start() failed. Error with gst_element_factory_make('
h264parse
')"
;
if
((
parser
=
gst_element_factory_make
(
_parserName
,
"
parser"
))
==
nullptr
)
{
qCritical
()
<<
"VideoReceiver::start() failed. Error with gst_element_factory_make('
"
<<
_parserName
<<
"
')"
;
break
;
}
...
...
@@ -348,8 +280,8 @@ VideoReceiver::start()
break
;
}
if
((
decoder
=
gst_element_factory_make
(
"avdec_h264"
,
"h264-
decoder"
))
==
nullptr
)
{
qCritical
()
<<
"VideoReceiver::start() failed. Error with gst_element_factory_make('
avdec_h264
')"
;
if
((
decoder
=
gst_element_factory_make
(
_decoderName
,
"
decoder"
))
==
nullptr
)
{
qCritical
()
<<
"VideoReceiver::start() failed. Error with gst_element_factory_make('
"
<<
_decoderName
<<
"
')"
;
break
;
}
...
...
@@ -525,7 +457,6 @@ VideoReceiver::_shutdownPipeline() {
_pipeline
=
nullptr
;
delete
_sink
;
_sink
=
nullptr
;
_serverPresent
=
false
;
_streaming
=
false
;
_recording
=
false
;
_stopping
=
false
;
...
...
@@ -540,7 +471,7 @@ void
VideoReceiver
::
_handleError
()
{
qCDebug
(
VideoReceiverLog
)
<<
"Gstreamer error!"
;
stop
();
start
(
);
_restart_timer
.
start
(
_restart_time_ms
);
}
#endif
...
...
@@ -555,8 +486,7 @@ VideoReceiver::_handleEOS() {
_shutdownRecordingBranch
();
}
else
{
qWarning
()
<<
"VideoReceiver: Unexpected EOS!"
;
stop
();
start
();
_handleError
();
}
}
#endif
...
...
@@ -646,6 +576,21 @@ VideoReceiver::_cleanupOldVideos()
}
#endif
//-----------------------------------------------------------------------------
void
VideoReceiver
::
setVideoDecoder
(
VideoEncoding
encoding
)
{
if
(
encoding
==
H265_HW
||
encoding
==
H265_SW
)
{
_depayName
=
"rtph265depay"
;
_parserName
=
"h265parse"
;
_decoderName
=
"avdec_h265"
;
}
else
{
_depayName
=
"rtph264depay"
;
_parserName
=
"h264parse"
;
_decoderName
=
"avdec_h264"
;
}
}
//-----------------------------------------------------------------------------
// When we finish our pipeline will look like this:
//
...
...
@@ -682,7 +627,7 @@ VideoReceiver::startRecording(const QString &videoFile)
_sink
=
new
Sink
();
_sink
->
teepad
=
gst_element_get_request_pad
(
_tee
,
"src_%u"
);
_sink
->
queue
=
gst_element_factory_make
(
"queue"
,
nullptr
);
_sink
->
parse
=
gst_element_factory_make
(
"h264parse"
,
nullptr
);
_sink
->
parse
=
gst_element_factory_make
(
_parserName
,
nullptr
);
_sink
->
mux
=
gst_element_factory_make
(
kVideoMuxes
[
muxIdx
],
nullptr
);
_sink
->
filesink
=
gst_element_factory_make
(
"filesink"
,
nullptr
);
_sink
->
removing
=
false
;
...
...
@@ -896,10 +841,10 @@ VideoReceiver::_updateTimer()
{
#if defined(QGC_GST_STREAMING)
if
(
_videoSurface
)
{
if
(
stopping
()
||
starting
()
)
{
if
(
_
stopping
||
_
starting
)
{
return
;
}
if
(
streaming
()
)
{
if
(
_
streaming
)
{
if
(
!
_videoRunning
)
{
_videoSurface
->
setLastFrame
(
0
);
_videoRunning
=
true
;
...
...
@@ -927,7 +872,7 @@ VideoReceiver::_updateTimer()
_stop
=
false
;
}
}
else
{
if
(
!
_stop
&&
!
running
()
&&
!
_uri
.
isEmpty
()
&&
_videoSettings
->
streamEnabled
()
->
rawValue
().
toBool
())
{
if
(
!
_stop
&&
_
running
&&
!
_uri
.
isEmpty
()
&&
_videoSettings
->
streamEnabled
()
->
rawValue
().
toBool
())
{
start
();
}
}
...
...
src/VideoStreaming/VideoReceiver.h
View file @
ace5e73b
/****************************************************************************
*
* (c) 2009-201
8
QGROUNDCONTROL PROJECT <http://www.qgroundcontrol.org>
* (c) 2009-201
9
QGROUNDCONTROL PROJECT <http://www.qgroundcontrol.org>
*
* QGroundControl is licensed according to the terms in the file
* COPYING.md in the root of the source code directory.
...
...
@@ -34,6 +34,13 @@ class VideoReceiver : public QObject
{
Q_OBJECT
public:
enum
VideoEncoding
{
H264_SW
=
1
,
H264_HW
=
2
,
H265_SW
=
3
,
H265_HW
=
4
};
#if defined(QGC_GST_STREAMING)
Q_PROPERTY
(
bool
recording
READ
recording
NOTIFY
recordingChanged
)
#endif
...
...
@@ -47,11 +54,7 @@ public:
~
VideoReceiver
();
#if defined(QGC_GST_STREAMING)
virtual
bool
running
()
{
return
_running
;
}
virtual
bool
recording
()
{
return
_recording
;
}
virtual
bool
streaming
()
{
return
_streaming
;
}
virtual
bool
starting
()
{
return
_starting
;
}
virtual
bool
stopping
()
{
return
_stopping
;
}
#endif
virtual
VideoSurface
*
videoSurface
()
{
return
_videoSurface
;
}
...
...
@@ -64,6 +67,8 @@ public:
virtual
void
setShowFullScreen
(
bool
show
)
{
_showFullScreen
=
show
;
emit
showFullScreenChanged
();
}
void
setVideoDecoder
(
VideoEncoding
encoding
);
signals:
void
videoRunningChanged
();
void
imageFileChanged
();
...
...
@@ -86,9 +91,7 @@ public slots:
protected
slots
:
virtual
void
_updateTimer
();
#if defined(QGC_GST_STREAMING)
virtual
void
_timeout
();
virtual
void
_connected
();
virtual
void
_socketError
(
QAbstractSocket
::
SocketError
socketError
);
virtual
void
_restart_timeout
();
virtual
void
_handleError
();
virtual
void
_handleEOS
();
virtual
void
_handleStateChanged
();
...
...
@@ -132,14 +135,11 @@ protected:
//-- Wait for Video Server to show up before starting
QTimer
_frameTimer
;
QTimer
_timer
;
QTcpSocket
*
_socket
;
bool
_serverPresent
;
int
_rtspTestInterval_ms
;
QTimer
_restart_timer
;
int
_restart_time_ms
;
//-- RTSP UDP reconnect timeout
uint64_t
_udpReconnect_us
;
#endif
QString
_uri
;
...
...
@@ -149,5 +149,8 @@ protected:
bool
_videoRunning
;
bool
_showFullScreen
;
VideoSettings
*
_videoSettings
;
const
char
*
_depayName
;
const
char
*
_parserName
;
const
char
*
_decoderName
;
};
Write
Preview
Supports
Markdown
0%
Try again
or
attach a new 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