Commit 62a4ba77 authored by Jacob Walser's avatar Jacob Walser

Always shutdown streaming pipeline correctly, and call VideoReceiver start/stop appropriately

parent 4fb068fc
...@@ -224,38 +224,37 @@ VideoManager::videoSourceList() ...@@ -224,38 +224,37 @@ VideoManager::videoSourceList()
void VideoManager::_updateTimer() void VideoManager::_updateTimer()
{ {
#if defined(QGC_GST_STREAMING) #if defined(QGC_GST_STREAMING)
if(_videoRunning) if(_videoReceiver && _videoSurface) {
{ if(_videoReceiver->stopping() || _videoReceiver->starting()) {
time_t elapsed = 0; return;
if(_videoSurface)
{
elapsed = time(0) - _videoSurface->lastFrame();
}
if(elapsed > 2 && _videoSurface)
{
_videoRunning = false;
_videoSurface->setLastFrame(0);
emit videoRunningChanged();
if(_videoReceiver) {
if(isGStreamer()) {
//-- Stop it
_videoReceiver->stop();
QThread::msleep(100);
//-- And start over
_videoReceiver->start();
}
}
} }
}
else if(_videoReceiver->streaming()) {
{ if(!_videoRunning) {
if(_videoSurface && _videoReceiver->streaming()) { _videoSurface->setLastFrame(0);
qDebug() << _videoSurface->lastFrame();
if(!_videoRunning)
{
_videoRunning = true; _videoRunning = true;
emit videoRunningChanged(); emit videoRunningChanged();
} }
} else {
if(_videoRunning) {
_videoRunning = false;
emit videoRunningChanged();
}
}
if(_videoRunning) {
time_t elapsed = 0;
time_t lastFrame = _videoSurface->lastFrame();
if(lastFrame != 0) {
elapsed = time(0) - _videoSurface->lastFrame();
}
if(elapsed > 2 && _videoSurface) {
_videoReceiver->stop();
}
} else {
if(!_videoReceiver->running()) {
_videoReceiver->start();
}
} }
} }
#endif #endif
......
...@@ -31,12 +31,12 @@ void VideoReceiver::_eosCB(GstMessage* message) ...@@ -31,12 +31,12 @@ void VideoReceiver::_eosCB(GstMessage* message)
{ {
Q_UNUSED(message) Q_UNUSED(message)
gst_bin_remove(GST_BIN(_pipeline2), _sink->queue); gst_bin_remove(GST_BIN(_pipelineStopRec), _sink->queue);
gst_bin_remove(GST_BIN(_pipeline2), _sink->mux); gst_bin_remove(GST_BIN(_pipelineStopRec), _sink->mux);
gst_bin_remove(GST_BIN(_pipeline2), _sink->filesink); gst_bin_remove(GST_BIN(_pipelineStopRec), _sink->filesink);
gst_element_set_state(_pipeline2, GST_STATE_NULL); gst_element_set_state(_pipelineStopRec, GST_STATE_NULL);
gst_object_unref(_pipeline2); gst_object_unref(_pipelineStopRec);
gst_element_set_state(_sink->filesink, GST_STATE_NULL); gst_element_set_state(_sink->filesink, GST_STATE_NULL);
gst_element_set_state(_sink->mux, GST_STATE_NULL); gst_element_set_state(_sink->mux, GST_STATE_NULL);
...@@ -51,6 +51,7 @@ void VideoReceiver::_eosCB(GstMessage* message) ...@@ -51,6 +51,7 @@ void VideoReceiver::_eosCB(GstMessage* message)
_recording = false; _recording = false;
emit recordingChanged(); emit recordingChanged();
qCDebug(VideoReceiverLog) << "Recording Stopped";
} }
#endif #endif
...@@ -71,27 +72,27 @@ void VideoReceiver::_unlinkCB(GstPadProbeInfo* info) ...@@ -71,27 +72,27 @@ void VideoReceiver::_unlinkCB(GstPadProbeInfo* info)
gst_object_unref(_sink->teepad); gst_object_unref(_sink->teepad);
// Create temporary pipeline // Create temporary pipeline
_pipeline2 = gst_pipeline_new("pipe2"); _pipelineStopRec = gst_pipeline_new("pipeStopRec");
// Put our elements from the recording branch into the temporary pipeline // Put our elements from the recording branch into the temporary pipeline
gst_bin_add_many(GST_BIN(_pipeline2), _sink->queue, _sink->mux, _sink->filesink, NULL); gst_bin_add_many(GST_BIN(_pipelineStopRec), _sink->queue, _sink->mux, _sink->filesink, NULL);
gst_element_link_many(_sink->queue, _sink->mux, _sink->filesink, NULL); gst_element_link_many(_sink->queue, _sink->mux, _sink->filesink, NULL);
// Add watch for EOS event // Add watch for EOS event
GstBus* bus = gst_pipeline_get_bus(GST_PIPELINE(_pipeline2)); GstBus* bus = gst_pipeline_get_bus(GST_PIPELINE(_pipelineStopRec));
gst_bus_add_signal_watch(bus); gst_bus_add_signal_watch(bus);
g_signal_connect(bus, "message::eos", G_CALLBACK(_eosCallBack), this); g_signal_connect(bus, "message::eos", G_CALLBACK(_eosCallBack), this);
gst_object_unref(bus); gst_object_unref(bus);
if(gst_element_set_state(_pipeline2, GST_STATE_PLAYING) == GST_STATE_CHANGE_FAILURE) { if(gst_element_set_state(_pipelineStopRec, GST_STATE_PLAYING) == GST_STATE_CHANGE_FAILURE) {
qCDebug(VideoReceiverLog) << "problem starting pipeline2"; qCDebug(VideoReceiverLog) << "problem starting _pipelineStopRec";
} }
// Send EOS at the beginning of the pipeline // Send EOS at the beginning of the pipeline
GstPad* sinkpad = gst_element_get_static_pad(_sink->queue, "sink"); GstPad* sinkpad = gst_element_get_static_pad(_sink->queue, "sink");
gst_pad_send_event(sinkpad, gst_event_new_eos()); gst_pad_send_event(sinkpad, gst_event_new_eos());
gst_object_unref(sinkpad); gst_object_unref(sinkpad);
qCDebug(VideoReceiverLog) << "Recording branch unlinked";
} }
#endif #endif
...@@ -135,8 +136,10 @@ GstPadProbeReturn VideoReceiver::_unlinkCallBack(GstPad* pad, GstPadProbeInfo* i ...@@ -135,8 +136,10 @@ GstPadProbeReturn VideoReceiver::_unlinkCallBack(GstPad* pad, GstPadProbeInfo* i
void VideoReceiver::startRecording(void) void VideoReceiver::startRecording(void)
{ {
#if defined(QGC_GST_STREAMING) #if defined(QGC_GST_STREAMING)
qCDebug(VideoReceiverLog) << "startRecording()";
// exit immediately if we are already recording // exit immediately if we are already recording
if(_pipeline == NULL || _recording) { if(_pipeline == NULL || _recording) {
qCDebug(VideoReceiverLog) << "Already recording!";
return; return;
} }
...@@ -174,17 +177,19 @@ void VideoReceiver::startRecording(void) ...@@ -174,17 +177,19 @@ void VideoReceiver::startRecording(void)
_recording = true; _recording = true;
emit recordingChanged(); emit recordingChanged();
qCDebug(VideoReceiverLog) << "Recording started";
#endif #endif
} }
void VideoReceiver::stopRecording(void) void VideoReceiver::stopRecording(void)
{ {
#if defined(QGC_GST_STREAMING) #if defined(QGC_GST_STREAMING)
qCDebug(VideoReceiverLog) << "stopRecording()";
// exit immediately if we are not recording // exit immediately if we are not recording
if(_pipeline == NULL || !_recording) { if(_pipeline == NULL || !_recording) {
qCDebug(VideoReceiverLog) << "Not recording!";
return; return;
} }
// Wait for data block before unlinking // Wait for data block before unlinking
gst_pad_add_probe(_sink->teepad, GST_PAD_PROBE_TYPE_IDLE, _unlinkCallBack, this, NULL); gst_pad_add_probe(_sink->teepad, GST_PAD_PROBE_TYPE_IDLE, _unlinkCallBack, this, NULL);
#endif #endif
...@@ -192,13 +197,16 @@ void VideoReceiver::stopRecording(void) ...@@ -192,13 +197,16 @@ void VideoReceiver::stopRecording(void)
VideoReceiver::VideoReceiver(QObject* parent) VideoReceiver::VideoReceiver(QObject* parent)
: QObject(parent) : QObject(parent)
, _running(false)
, _recording(false) , _recording(false)
, _streaming(false) , _streaming(false)
, _starting(false)
, _stopping(false)
#if defined(QGC_GST_STREAMING) #if defined(QGC_GST_STREAMING)
, _sink(NULL) , _sink(NULL)
, _tee(NULL) , _tee(NULL)
, _pipeline(NULL) , _pipeline(NULL)
, _pipeline2(NULL) , _pipelineStopRec(NULL)
, _videoSink(NULL) , _videoSink(NULL)
, _socket(NULL) , _socket(NULL)
, _serverPresent(false) , _serverPresent(false)
...@@ -214,7 +222,6 @@ VideoReceiver::~VideoReceiver() ...@@ -214,7 +222,6 @@ VideoReceiver::~VideoReceiver()
{ {
#if defined(QGC_GST_STREAMING) #if defined(QGC_GST_STREAMING)
stop(); stop();
setVideoSink(NULL);
if(_socket) { if(_socket) {
delete _socket; delete _socket;
} }
...@@ -309,6 +316,8 @@ void VideoReceiver::_timeout() ...@@ -309,6 +316,8 @@ void VideoReceiver::_timeout()
void VideoReceiver::start() void VideoReceiver::start()
{ {
#if defined(QGC_GST_STREAMING) #if defined(QGC_GST_STREAMING)
qCDebug(VideoReceiverLog) << "start()";
if (_uri.isEmpty()) { if (_uri.isEmpty()) {
qCritical() << "VideoReceiver::start() failed because URI is not specified"; qCritical() << "VideoReceiver::start() failed because URI is not specified";
return; return;
...@@ -317,10 +326,14 @@ void VideoReceiver::start() ...@@ -317,10 +326,14 @@ void VideoReceiver::start()
qCritical() << "VideoReceiver::start() failed because video sink is not set"; qCritical() << "VideoReceiver::start() failed because video sink is not set";
return; return;
} }
if(_running) {
qCDebug(VideoReceiverLog) << "Already running!";
return;
}
bool isUdp = _uri.contains("udp://"); _starting = true;
stop(); bool isUdp = _uri.contains("udp://");
//-- For RTSP, check to see if server is there first //-- For RTSP, check to see if server is there first
if(!_serverPresent && !isUdp) { if(!_serverPresent && !isUdp) {
...@@ -334,7 +347,7 @@ void VideoReceiver::start() ...@@ -334,7 +347,7 @@ void VideoReceiver::start()
GstCaps* caps = NULL; GstCaps* caps = NULL;
GstElement* demux = NULL; GstElement* demux = NULL;
GstElement* parser = NULL; GstElement* parser = NULL;
GstElement* queue = NULL; GstElement* queue = NULL;
GstElement* decoder = NULL; GstElement* decoder = NULL;
do { do {
...@@ -389,7 +402,7 @@ void VideoReceiver::start() ...@@ -389,7 +402,7 @@ void VideoReceiver::start()
} }
if((queue = gst_element_factory_make("queue", NULL)) == NULL) { if((queue = gst_element_factory_make("queue", NULL)) == NULL) {
qCritical() << "VideoReceiver::start() failed. Error with gst_element_factory_make('queue1')"; qCritical() << "VideoReceiver::start() failed. Error with gst_element_factory_make('queue')";
break; break;
} }
...@@ -465,28 +478,30 @@ void VideoReceiver::start() ...@@ -465,28 +478,30 @@ void VideoReceiver::start()
_pipeline = NULL; _pipeline = NULL;
} }
} }
qCDebug(VideoReceiverLog) << "Video Receiver started."; _starting = false;
_running = true;
qCDebug(VideoReceiverLog) << "Running";
#endif #endif
} }
void VideoReceiver::stop() void VideoReceiver::stop()
{ {
#if defined(QGC_GST_STREAMING) #if defined(QGC_GST_STREAMING)
if (_pipeline != NULL) { qCDebug(VideoReceiverLog) << "stop()";
qCDebug(VideoReceiverLog) << "Stopping pipeline"; if (_pipeline != NULL && !_stopping) {
stopRecording(); qCDebug(VideoReceiverLog) << "Stopping _pipeline";
gst_element_set_state(_pipeline, GST_STATE_NULL); gst_element_send_event(_pipeline, gst_event_new_eos());
gst_object_unref(_pipeline); _stopping = true;
_pipeline = NULL; GstBus* bus = gst_pipeline_get_bus(GST_PIPELINE(_pipeline));
_serverPresent = false; GstMessage* message = gst_bus_timed_pop_filtered(bus, GST_CLOCK_TIME_NONE, GST_MESSAGE_EOS);
_streaming = false; gst_object_unref(bus);
_onBusMessage(message);
} }
#endif #endif
} }
void VideoReceiver::setUri(const QString & uri) void VideoReceiver::setUri(const QString & uri)
{ {
stop();
_uri = uri; _uri = uri;
} }
...@@ -501,7 +516,18 @@ void VideoReceiver::_onBusMessage(GstMessage* msg) ...@@ -501,7 +516,18 @@ void VideoReceiver::_onBusMessage(GstMessage* msg)
{ {
switch (GST_MESSAGE_TYPE(msg)) { switch (GST_MESSAGE_TYPE(msg)) {
case GST_MESSAGE_EOS: case GST_MESSAGE_EOS:
stop(); gst_element_set_state(_pipeline, GST_STATE_NULL);
gst_bin_remove(GST_BIN(_pipeline), _videoSink);
gst_object_unref(_pipeline);
_pipeline = NULL;
_serverPresent = false;
_streaming = false;
_recording = false;
_stopping = false;
_running = false;
emit recordingChanged();
emit streamingChanged();
qCDebug(VideoReceiverLog) << "Stopped";
break; break;
case GST_MESSAGE_ERROR: case GST_MESSAGE_ERROR:
do { do {
......
...@@ -42,8 +42,11 @@ public: ...@@ -42,8 +42,11 @@ public:
void setVideoSink(GstElement* _sink); void setVideoSink(GstElement* _sink);
#endif #endif
bool running() { return _running; }
bool recording() { return _recording; } bool recording() { return _recording; }
bool streaming() { return _streaming; } bool streaming() { return _streaming; }
bool starting() { return _starting; }
bool stopping() { return _stopping; }
signals: signals:
void recordingChanged(); void recordingChanged();
...@@ -76,8 +79,11 @@ private: ...@@ -76,8 +79,11 @@ private:
gboolean removing; gboolean removing;
} Sink; } Sink;
bool _running;
bool _recording; bool _recording;
bool _streaming; bool _streaming;
bool _starting;
bool _stopping;
Sink* _sink; Sink* _sink;
GstElement* _tee; GstElement* _tee;
...@@ -95,7 +101,7 @@ private: ...@@ -95,7 +101,7 @@ private:
#if defined(QGC_GST_STREAMING) #if defined(QGC_GST_STREAMING)
GstElement* _pipeline; GstElement* _pipeline;
GstElement* _pipeline2; GstElement* _pipelineStopRec;
GstElement* _videoSink; GstElement* _videoSink;
#endif #endif
......
Markdown is supported
0% or
You are about to add 0 people to the discussion. Proceed with caution.
Finish editing this message first!
Please register or to comment