Commit f1559638 authored by dogmaphobic's avatar dogmaphobic

Work on RTSP Video Stream, x86 Android, etc.

parent 5fc24cfa
...@@ -30,12 +30,18 @@ linux { ...@@ -30,12 +30,18 @@ linux {
CONFIG += LinuxBuild CONFIG += LinuxBuild
DEFINES += __STDC_LIMIT_MACROS __rasp_pi2__ DEFINES += __STDC_LIMIT_MACROS __rasp_pi2__
} else : android-g++ { } else : android-g++ {
message("Android build")
CONFIG += AndroidBuild MobileBuild CONFIG += AndroidBuild MobileBuild
DEFINES += __android__ DEFINES += __android__
DEFINES += __STDC_LIMIT_MACROS DEFINES += __STDC_LIMIT_MACROS
DEFINES += QGC_ENABLE_BLUETOOTH DEFINES += QGC_ENABLE_BLUETOOTH
target.path = $$DESTDIR target.path = $$DESTDIR
equals(ANDROID_TARGET_ARCH, x86) {
CONFIG += Androidx86Build
DEFINES += __androidx86__
message("Android x86 build")
} else {
message("Android Arm build")
}
} else { } else {
error("Unsuported Linux toolchain, only GCC 32- or 64-bit is supported") error("Unsuported Linux toolchain, only GCC 32- or 64-bit is supported")
} }
...@@ -54,11 +60,11 @@ linux { ...@@ -54,11 +60,11 @@ linux {
DEFINES += __macos__ DEFINES += __macos__
CONFIG += x86_64 CONFIG += x86_64
CONFIG -= x86 CONFIG -= x86
equals(QT_MAJOR_VERSION, 5) | greaterThan(QT_MINOR_VERSION, 5) { equals(QT_MAJOR_VERSION, 5) | greaterThan(QT_MINOR_VERSION, 5) {
QMAKE_MACOSX_DEPLOYMENT_TARGET = 10.7 QMAKE_MACOSX_DEPLOYMENT_TARGET = 10.7
} else { } else {
QMAKE_MACOSX_DEPLOYMENT_TARGET = 10.6 QMAKE_MACOSX_DEPLOYMENT_TARGET = 10.6
} }
QMAKE_MAC_SDK = macosx10.11 QMAKE_MAC_SDK = macosx10.11
QMAKE_CXXFLAGS += -fvisibility=hidden QMAKE_CXXFLAGS += -fvisibility=hidden
} else { } else {
......
...@@ -46,6 +46,15 @@ contains (DEFINES, QGC_DISABLE_BLUETOOTH) { ...@@ -46,6 +46,15 @@ contains (DEFINES, QGC_DISABLE_BLUETOOTH) {
DEFINES += QGC_ENABLE_BLUETOOTH DEFINES += QGC_ENABLE_BLUETOOTH
} }
# USB Camera and UVC Video Sources
contains (DEFINES, QGC_DISABLE_UVC) {
message("Skipping support for UVC devices (manual override from command line)")
DEFINES -= QGC_DISABLE_UVC
} else:exists(user_config.pri):infile(user_config.pri, DEFINES, QGC_DISABLE_UVC) {
message("Skipping support for UVC devices (manual override from user_config.pri)")
DEFINES -= QGC_DISABLE_UVC
}
LinuxBuild { LinuxBuild {
CONFIG += link_pkgconfig CONFIG += link_pkgconfig
} }
......
...@@ -15,6 +15,8 @@ ...@@ -15,6 +15,8 @@
<file alias="LogDownload.qml">src/ViewWidgets/LogDownload.qml</file> <file alias="LogDownload.qml">src/ViewWidgets/LogDownload.qml</file>
<file alias="FirmwareUpgrade.qml">src/VehicleSetup/FirmwareUpgrade.qml</file> <file alias="FirmwareUpgrade.qml">src/VehicleSetup/FirmwareUpgrade.qml</file>
<file alias="FlightDisplayView.qml">src/FlightDisplay/FlightDisplayView.qml</file> <file alias="FlightDisplayView.qml">src/FlightDisplay/FlightDisplayView.qml</file>
<file alias="FlightDisplayViewUVC.qml">src/FlightDisplay/FlightDisplayViewUVC.qml</file>
<file alias="FlightDisplayViewDummy.qml">src/FlightDisplay/FlightDisplayViewDummy.qml</file>
<file alias="PX4FlightModes.qml">src/AutoPilotPlugins/PX4/PX4FlightModes.qml</file> <file alias="PX4FlightModes.qml">src/AutoPilotPlugins/PX4/PX4FlightModes.qml</file>
<file alias="PX4AdvancedFlightModes.qml">src/AutoPilotPlugins/PX4/PX4AdvancedFlightModes.qml</file> <file alias="PX4AdvancedFlightModes.qml">src/AutoPilotPlugins/PX4/PX4AdvancedFlightModes.qml</file>
<file alias="PX4SimpleFlightModes.qml">src/AutoPilotPlugins/PX4/PX4SimpleFlightModes.qml</file> <file alias="PX4SimpleFlightModes.qml">src/AutoPilotPlugins/PX4/PX4SimpleFlightModes.qml</file>
......
...@@ -184,34 +184,17 @@ QGCView { ...@@ -184,34 +184,17 @@ QGCView {
} }
} }
] ]
//-- UDP Video Streaming //-- Video Streaming
FlightDisplayViewVideo { FlightDisplayViewVideo {
anchors.fill: parent anchors.fill: parent
visible: QGroundControl.videoManager.isGStreamer visible: QGroundControl.videoManager.isGStreamer
} }
//-- UVC Video (USB Camera or Video Device) //-- UVC Video (USB Camera or Video Device)
Rectangle { Loader {
id: noVideo id: cameraLoader
anchors.fill: parent
color: Qt.rgba(0,0,0,0.75)
visible: !QGroundControl.videoManager.isGStreamer
Camera {
id: camera
deviceId: QGroundControl.videoManager.videoSourceID
captureMode: Camera.CaptureViewfinder
}
VideoOutput {
id: viewFinder
source: camera
anchors.fill: parent anchors.fill: parent
visible: !QGroundControl.videoManager.isGStreamer visible: !QGroundControl.videoManager.isGStreamer
} source: QGroundControl.videoManager.uvcEnabled ? "qrc:/qml/FlightDisplayViewUVC.qml" : "qrc:/qml/FlightDisplayViewDummy.qml"
onVisibleChanged: {
if(visible)
camera.start()
else
camera.stop()
}
} }
} }
......
/****************************************************************************
*
* (c) 2009-2016 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.
*
****************************************************************************/
import QtQuick 2.5
Rectangle {
anchors.fill: parent
color: Qt.rgba(0,0,0,0.75)
}
/****************************************************************************
*
* (c) 2009-2016 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.
*
****************************************************************************/
import QtQuick 2.5
import QtMultimedia 5.5
import QGroundControl 1.0
Rectangle {
anchors.fill: parent
color: Qt.rgba(0,0,0,0.75)
Camera {
id: camera
deviceId: QGroundControl.videoManager.videoSourceID
captureMode: Camera.CaptureViewfinder
}
VideoOutput {
source: camera
anchors.fill: parent
fillMode: VideoOutput.PreserveAspectCrop
visible: !QGroundControl.videoManager.isGStreamer
}
onVisibleChanged: {
if(visible)
camera.start()
else
camera.stop()
}
}
...@@ -41,7 +41,6 @@ Item { ...@@ -41,7 +41,6 @@ Item {
display: QGroundControl.videoManager.videoSurface display: QGroundControl.videoManager.videoSurface
receiver: QGroundControl.videoManager.videoReceiver receiver: QGroundControl.videoManager.videoReceiver
visible: QGroundControl.videoManager.videoRunning visible: QGroundControl.videoManager.videoRunning
runVideo: true
/* TODO: Come up with a way to make this an option /* TODO: Come up with a way to make this an option
QGCAttitudeHUD { QGCAttitudeHUD {
id: attitudeHUD id: attitudeHUD
......
...@@ -19,51 +19,33 @@ ...@@ -19,51 +19,33 @@
#include "VideoManager.h" #include "VideoManager.h"
static const char* kVideoSourceKey = "VideoSource"; static const char* kVideoSourceKey = "VideoSource";
static const char* kGStreamerSource = "UDP Video Stream"; static const char* kVideoUDPPortKey = "VideoUDPPort";
static const char* kVideoRTSPUrlKey = "VideoRTSPUrl";
static const char* kUDPStream = "UDP Video Stream";
static const char* kRTSPStream = "RTSP Video Stream";
QGC_LOGGING_CATEGORY(VideoManagerLog, "VideoManagerLog") QGC_LOGGING_CATEGORY(VideoManagerLog, "VideoManagerLog")
//----------------------------------------------------------------------------- //-----------------------------------------------------------------------------
VideoManager::VideoManager(QGCApplication* app) VideoManager::VideoManager(QGCApplication* app)
: QGCTool(app) : QGCTool(app)
, _videoSurface(NULL)
, _videoReceiver(NULL)
, _videoRunning(false) , _videoRunning(false)
, _udpPort(5600) //-- Defalut Port 5600 == Solo UDP Port
, _init(false)
{ {
/* //-- Get saved settings
* This is the receiving end of an UDP RTP stream. The sender can be setup with this command: QSettings settings;
* setVideoSource(settings.value(kVideoSourceKey, kUDPStream).toString());
* gst-launch-1.0 uvch264src initial-bitrate=1000000 average-bitrate=1000000 iframe-period=1000 name=src auto-start=true src.vidsrc ! \ setUdpPort(settings.value(kVideoUDPPortKey, 5600).toUInt());
* video/x-h264,width=1280,height=720,framerate=24/1 ! h264parse ! rtph264pay ! udpsink host=192.168.1.9 port=5600 setRtspURL(settings.value(kVideoRTSPUrlKey, "rtsp://192.168.42.1:554/live").toString()); //-- Example RTSP URL
* _init = true;
* Where the main parameters are:
*
* uvch264src: Your h264 video source (the example above uses a Logitech C920 on an Raspberry PI 2+ or Odroid C1
* host=192.168.1.9 This is the IP address of QGC. You can use Avahi/Zeroconf to find QGC using the "_qgroundcontrol._udp" service.
*
* Advanced settings (you should probably read the gstreamer documentation before changing these):
*
* initial-bitrate=1000000 average-bitrate=1000000
* The bit rate to use. The greater, the better quality at the cost of higher bandwidth.
*
* width=1280,height=720,framerate=24/1
* The video resolution and frame rate. This depends on the camera used.
*
* iframe-period=1000
* Interval between iFrames. The greater the interval the lesser bandwidth at the cost of a longer time to recover from lost packets.
*
* Do not change anything else unless you know what you are doing. Any other change will require a matching change on the receiving end.
*
*/
_videoSurface = new VideoSurface;
_videoReceiver = new VideoReceiver(this);
_videoReceiver->setUri(QLatin1Literal("udp://0.0.0.0:5600")); // Port 5600=Solo UDP port, if you change it, you will break Solo video support
#if defined(QGC_GST_STREAMING) #if defined(QGC_GST_STREAMING)
_videoReceiver->setVideoSink(_videoSurface->videoSink()); _updateVideo();
connect(&_frameTimer, &QTimer::timeout, this, &VideoManager::_updateTimer); connect(&_frameTimer, &QTimer::timeout, this, &VideoManager::_updateTimer);
_frameTimer.start(1000); _frameTimer.start(1000);
#endif #endif
//-- Get saved video source
QSettings settings;
setVideoSource(settings.value(kVideoSourceKey, kGStreamerSource).toString());
} }
//----------------------------------------------------------------------------- //-----------------------------------------------------------------------------
...@@ -96,12 +78,21 @@ bool ...@@ -96,12 +78,21 @@ bool
VideoManager::isGStreamer() VideoManager::isGStreamer()
{ {
#if defined(QGC_GST_STREAMING) #if defined(QGC_GST_STREAMING)
return _videoSource == kGStreamerSource; return _videoSource == kUDPStream || _videoSource == kRTSPStream;
#else #else
return false; return false;
#endif #endif
} }
//-----------------------------------------------------------------------------
#ifndef QGC_DISABLE_UVC
bool
VideoManager::uvcEnabled()
{
return QCameraInfo::availableCameras().count() > 0;
}
#endif
//----------------------------------------------------------------------------- //-----------------------------------------------------------------------------
void void
VideoManager::setVideoSource(QString vSource) VideoManager::setVideoSource(QString vSource)
...@@ -110,6 +101,7 @@ VideoManager::setVideoSource(QString vSource) ...@@ -110,6 +101,7 @@ VideoManager::setVideoSource(QString vSource)
QSettings settings; QSettings settings;
settings.setValue(kVideoSourceKey, vSource); settings.setValue(kVideoSourceKey, vSource);
emit videoSourceChanged(); emit videoSourceChanged();
#ifndef QGC_DISABLE_UVC
QList<QCameraInfo> cameras = QCameraInfo::availableCameras(); QList<QCameraInfo> cameras = QCameraInfo::availableCameras();
foreach (const QCameraInfo &cameraInfo, cameras) { foreach (const QCameraInfo &cameraInfo, cameras) {
if(cameraInfo.description() == vSource) { if(cameraInfo.description() == vSource) {
...@@ -119,8 +111,51 @@ VideoManager::setVideoSource(QString vSource) ...@@ -119,8 +111,51 @@ VideoManager::setVideoSource(QString vSource)
break; break;
} }
} }
#endif
emit isGStreamerChanged(); emit isGStreamerChanged();
qCDebug(VideoManagerLog) << "New Video Source:" << vSource; qCDebug(VideoManagerLog) << "New Video Source:" << vSource;
/*
* Not working. Requires restart for now
if(isGStreamer())
_updateVideo();
*/
if(_videoReceiver) {
if(isGStreamer()) {
_videoReceiver->start();
} else {
_videoReceiver->stop();
}
}
}
//-----------------------------------------------------------------------------
void
VideoManager::setUdpPort(quint16 port)
{
_udpPort = port;
QSettings settings;
settings.setValue(kVideoUDPPortKey, port);
emit udpPortChanged();
/*
* Not working. Requires restart for now
if(_videoSource == kUDPStream)
_updateVideo();
*/
}
//-----------------------------------------------------------------------------
void
VideoManager::setRtspURL(QString url)
{
_rtspURL = url;
QSettings settings;
settings.setValue(kVideoRTSPUrlKey, url);
emit rtspURLChanged();
/*
* Not working. Requires restart for now
if(_videoSource == kRTSPStream)
_updateVideo();
*/
} }
//----------------------------------------------------------------------------- //-----------------------------------------------------------------------------
...@@ -129,20 +164,23 @@ VideoManager::videoSourceList() ...@@ -129,20 +164,23 @@ VideoManager::videoSourceList()
{ {
_videoSourceList.clear(); _videoSourceList.clear();
#if defined(QGC_GST_STREAMING) #if defined(QGC_GST_STREAMING)
_videoSourceList.append(kGStreamerSource); _videoSourceList.append(kUDPStream);
_videoSourceList.append(kRTSPStream);
#endif #endif
#ifndef QGC_DISABLE_UVC
QList<QCameraInfo> cameras = QCameraInfo::availableCameras(); QList<QCameraInfo> cameras = QCameraInfo::availableCameras();
foreach (const QCameraInfo &cameraInfo, cameras) { foreach (const QCameraInfo &cameraInfo, cameras) {
qCDebug(VideoManagerLog) << "UVC Video source ID:" << cameraInfo.deviceName() << " Name:" << cameraInfo.description(); qCDebug(VideoManagerLog) << "UVC Video source ID:" << cameraInfo.deviceName() << " Name:" << cameraInfo.description();
_videoSourceList.append(cameraInfo.description()); _videoSourceList.append(cameraInfo.description());
} }
#endif
return _videoSourceList; return _videoSourceList;
} }
//----------------------------------------------------------------------------- //-----------------------------------------------------------------------------
#if defined(QGC_GST_STREAMING) void VideoManager::_updateTimer()
void VideoManager::_updateTimer(void)
{ {
#if defined(QGC_GST_STREAMING)
if(_videoRunning) if(_videoRunning)
{ {
time_t elapsed = 0; time_t elapsed = 0;
...@@ -150,7 +188,7 @@ void VideoManager::_updateTimer(void) ...@@ -150,7 +188,7 @@ void VideoManager::_updateTimer(void)
{ {
elapsed = time(0) - _videoSurface->lastFrame(); elapsed = time(0) - _videoSurface->lastFrame();
} }
if(elapsed > 2) if(elapsed > 2 && _videoSurface)
{ {
_videoRunning = false; _videoRunning = false;
_videoSurface->setLastFrame(0); _videoSurface->setLastFrame(0);
...@@ -167,5 +205,26 @@ void VideoManager::_updateTimer(void) ...@@ -167,5 +205,26 @@ void VideoManager::_updateTimer(void)
} }
} }
} }
}
#endif #endif
}
//-----------------------------------------------------------------------------
void VideoManager::_updateVideo()
{
if(_init) {
if(_videoReceiver)
delete _videoReceiver;
if(_videoSurface)
delete _videoSurface;
_videoSurface = new VideoSurface;
_videoReceiver = new VideoReceiver(this);
_videoReceiver->setVideoSink(_videoSurface->videoSink());
#if defined(QGC_GST_STREAMING)
if(_videoSource == kUDPStream)
_videoReceiver->setUri(QStringLiteral("udp://0.0.0.0:%1").arg(_udpPort));
else
_videoReceiver->setUri(_rtspURL);
#endif
_videoReceiver->start();
}
}
...@@ -35,6 +35,9 @@ public: ...@@ -35,6 +35,9 @@ public:
Q_PROPERTY(QString videoSource READ videoSource WRITE setVideoSource NOTIFY videoSourceChanged) Q_PROPERTY(QString videoSource READ videoSource WRITE setVideoSource NOTIFY videoSourceChanged)
Q_PROPERTY(QStringList videoSourceList READ videoSourceList NOTIFY videoSourceListChanged) Q_PROPERTY(QStringList videoSourceList READ videoSourceList NOTIFY videoSourceListChanged)
Q_PROPERTY(bool videoRunning READ videoRunning NOTIFY videoRunningChanged) Q_PROPERTY(bool videoRunning READ videoRunning NOTIFY videoRunningChanged)
Q_PROPERTY(quint16 udpPort READ udpPort WRITE setUdpPort NOTIFY udpPortChanged)
Q_PROPERTY(QString rtspURL READ rtspURL WRITE setRtspURL NOTIFY rtspURLChanged)
Q_PROPERTY(bool uvcEnabled READ uvcEnabled CONSTANT)
Q_PROPERTY(VideoSurface* videoSurface MEMBER _videoSurface CONSTANT) Q_PROPERTY(VideoSurface* videoSurface MEMBER _videoSurface CONSTANT)
Q_PROPERTY(VideoReceiver* videoReceiver MEMBER _videoReceiver CONSTANT) Q_PROPERTY(VideoReceiver* videoReceiver MEMBER _videoReceiver CONSTANT)
...@@ -44,7 +47,18 @@ public: ...@@ -44,7 +47,18 @@ public:
QString videoSourceID () { return _videoSourceID; } QString videoSourceID () { return _videoSourceID; }
QString videoSource () { return _videoSource; } QString videoSource () { return _videoSource; }
QStringList videoSourceList (); QStringList videoSourceList ();
quint16 udpPort () { return _udpPort; }
QString rtspURL () { return _rtspURL; }
#if defined(QGC_DISABLE_UVC)
bool uvcEnabled () { return false; }
#else
bool uvcEnabled ();
#endif
void setVideoSource (QString vSource); void setVideoSource (QString vSource);
void setUdpPort (quint16 port);
void setRtspURL (QString url);
// Override from QGCTool // Override from QGCTool
void setToolbox (QGCToolbox *toolbox); void setToolbox (QGCToolbox *toolbox);
...@@ -56,9 +70,12 @@ signals: ...@@ -56,9 +70,12 @@ signals:
void videoSourceListChanged (); void videoSourceListChanged ();
void isGStreamerChanged (); void isGStreamerChanged ();
void videoSourceIDChanged (); void videoSourceIDChanged ();
void udpPortChanged ();
void rtspURLChanged ();
private: private:
void _updateTimer(void); void _updateTimer ();
void _updateVideo ();
private: private:
VideoSurface* _videoSurface; VideoSurface* _videoSurface;
...@@ -70,6 +87,9 @@ private: ...@@ -70,6 +87,9 @@ private:
QString _videoSource; QString _videoSource;
QString _videoSourceID; QString _videoSourceID;
QStringList _videoSourceList; QStringList _videoSourceList;
quint16 _udpPort;
QString _rtspURL;
bool _init;
}; };
#endif #endif
...@@ -22,20 +22,5 @@ VideoItem { ...@@ -22,20 +22,5 @@ VideoItem {
id: videoBackground id: videoBackground
property var display property var display
property var receiver property var receiver
property var runVideo: false
surface: display surface: display
onRunVideoChanged: {
if(videoBackground.receiver && videoBackground.display) {
if(videoBackground.runVideo) {
videoBackground.receiver.start();
} else {
videoBackground.receiver.stop();
}
}
}
Component.onCompleted: {
if(videoBackground.runVideo && videoBackground.receiver) {
videoBackground.receiver.start();
}
}
} }
...@@ -49,6 +49,21 @@ void VideoReceiver::setVideoSink(GstElement* sink) ...@@ -49,6 +49,21 @@ void VideoReceiver::setVideoSink(GstElement* sink)
} }
#endif #endif
static void newPadCB(GstElement * element, GstPad* pad, gpointer data)
{
gchar *name;
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);
qDebug() << p_caps << ", " << description;
g_free(description);
GstElement * p_rtph264depay = GST_ELEMENT(data);
if(gst_element_link_pads(element, name, p_rtph264depay, "sink") == false)
qCritical() << "newPadCB : failed to link elements\n";
g_free(name);
}
void VideoReceiver::start() void VideoReceiver::start()
{ {
#if defined(QGC_GST_STREAMING) #if defined(QGC_GST_STREAMING)
...@@ -56,7 +71,6 @@ void VideoReceiver::start() ...@@ -56,7 +71,6 @@ void VideoReceiver::start()
qCritical() << "VideoReceiver::start() failed because URI is not specified"; qCritical() << "VideoReceiver::start() failed because URI is not specified";
return; return;
} }
if (_videoSink == NULL) { if (_videoSink == NULL) {
qCritical() << "VideoReceiver::start() failed because video sink is not set"; qCritical() << "VideoReceiver::start() failed because video sink is not set";
return; return;
...@@ -72,29 +86,44 @@ void VideoReceiver::start() ...@@ -72,29 +86,44 @@ void VideoReceiver::start()
GstElement* parser = NULL; GstElement* parser = NULL;
GstElement* decoder = NULL; GstElement* decoder = NULL;
bool isUdp = _uri.contains("udp://");
do { do {
if ((_pipeline = gst_pipeline_new("receiver")) == NULL) { if ((_pipeline = gst_pipeline_new("receiver")) == NULL) {
qCritical() << "VideoReceiver::start() failed. Error with gst_pipeline_new()"; qCritical() << "VideoReceiver::start() failed. Error with gst_pipeline_new()";
break; break;
} }
if ((dataSource = gst_element_factory_make("udpsrc", "udp-source")) == NULL) { if(isUdp) {
qCritical() << "VideoReceiver::start() failed. Error with gst_element_factory_make('udpsrc')"; dataSource = gst_element_factory_make("udpsrc", "udp-source");
} else {
dataSource = gst_element_factory_make("rtspsrc", "rtsp-source");
}
if (!dataSource) {
qCritical() << "VideoReceiver::start() failed. Error with data source for gst_element_factory_make()";
break; break;
} }
if(isUdp) {
if ((caps = gst_caps_from_string("application/x-rtp, media=(string)video, clock-rate=(int)90000, encoding-name=(string)H264")) == NULL) { if ((caps = gst_caps_from_string("application/x-rtp, media=(string)video, clock-rate=(int)90000, encoding-name=(string)H264")) == NULL) {
qCritical() << "VideoReceiver::start() failed. Error with gst_caps_from_string()"; qCritical() << "VideoReceiver::start() failed. Error with gst_caps_from_string()";
break; break;
} }
g_object_set(G_OBJECT(dataSource), "uri", qPrintable(_uri), "caps", caps, NULL); g_object_set(G_OBJECT(dataSource), "uri", qPrintable(_uri), "caps", caps, NULL);
} else {
g_object_set(G_OBJECT(dataSource), "location", qPrintable(_uri), "latency", 0, NULL);
}
if ((demux = gst_element_factory_make("rtph264depay", "rtp-h264-depacketizer")) == NULL) { if ((demux = gst_element_factory_make("rtph264depay", "rtp-h264-depacketizer")) == NULL) {
qCritical() << "VideoReceiver::start() failed. Error with gst_element_factory_make('rtph264depay')"; qCritical() << "VideoReceiver::start() failed. Error with gst_element_factory_make('rtph264depay')";
break; break;
} }
if(!isUdp) {
g_signal_connect(dataSource, "pad-added", G_CALLBACK(newPadCB), demux);
}
if ((parser = gst_element_factory_make("h264parse", "h264-parser")) == NULL) { if ((parser = gst_element_factory_make("h264parse", "h264-parser")) == NULL) {
qCritical() << "VideoReceiver::start() failed. Error with gst_element_factory_make('h264parse')"; qCritical() << "VideoReceiver::start() failed. Error with gst_element_factory_make('h264parse')";
break; break;
...@@ -107,7 +136,15 @@ void VideoReceiver::start() ...@@ -107,7 +136,15 @@ void VideoReceiver::start()
gst_bin_add_many(GST_BIN(_pipeline), dataSource, demux, parser, decoder, _videoSink, NULL); gst_bin_add_many(GST_BIN(_pipeline), dataSource, demux, parser, decoder, _videoSink, NULL);
if (gst_element_link_many(dataSource, demux, parser, decoder, _videoSink, NULL) != (gboolean)TRUE) { gboolean res = FALSE;
if(isUdp) {
res = gst_element_link_many(dataSource, demux, parser, decoder, _videoSink, NULL);
} else {
res = gst_element_link_many(demux, parser, decoder, _videoSink, NULL);
}
if (!res) {
qCritical() << "VideoReceiver::start() failed. Error with gst_element_link_many()"; qCritical() << "VideoReceiver::start() failed. Error with gst_element_link_many()";
break; break;
} }
......
...@@ -73,8 +73,12 @@ LinuxBuild { ...@@ -73,8 +73,12 @@ LinuxBuild {
QMAKE_POST_LINK += $$escape_expand(\\n) xcopy \"$$GST_ROOT_WIN\\lib\\gstreamer-1.0\\validate\\*.dll\" \"$$DESTDIR_WIN\\gstreamer-plugins\\validate\\\" /Y $$escape_expand(\\n) QMAKE_POST_LINK += $$escape_expand(\\n) xcopy \"$$GST_ROOT_WIN\\lib\\gstreamer-1.0\\validate\\*.dll\" \"$$DESTDIR_WIN\\gstreamer-plugins\\validate\\\" /Y $$escape_expand(\\n)
} }
} else:AndroidBuild { } else:AndroidBuild {
#- gstreamer assumed to be installed in $$PWD/../../android/gstreamer-1.0-android-armv7-1.5.2 #- gstreamer assumed to be installed in $$PWD/../../android/gstreamer-1.0-android-armv7-1.5.2 (or x86)
Androidx86Build {
GST_ROOT = $$PWD/../../gstreamer-1.0-android-x86-1.5.2
} else {
GST_ROOT = $$PWD/../../gstreamer-1.0-android-armv7-1.5.2 GST_ROOT = $$PWD/../../gstreamer-1.0-android-armv7-1.5.2
}
exists($$GST_ROOT) { exists($$GST_ROOT) {
QMAKE_CXXFLAGS += -pthread QMAKE_CXXFLAGS += -pthread
CONFIG += VideoEnabled CONFIG += VideoEnabled
......
...@@ -27,6 +27,7 @@ VideoSurface::VideoSurface(QObject *parent) ...@@ -27,6 +27,7 @@ VideoSurface::VideoSurface(QObject *parent)
#if defined(QGC_GST_STREAMING) #if defined(QGC_GST_STREAMING)
, _data(new VideoSurfacePrivate) , _data(new VideoSurfacePrivate)
, _lastFrame(0) , _lastFrame(0)
, _refed(false)
#endif #endif
{ {
} }
...@@ -34,7 +35,7 @@ VideoSurface::VideoSurface(QObject *parent) ...@@ -34,7 +35,7 @@ VideoSurface::VideoSurface(QObject *parent)
VideoSurface::~VideoSurface() VideoSurface::~VideoSurface()
{ {
#if defined(QGC_GST_STREAMING) #if defined(QGC_GST_STREAMING)
if (_data->videoSink != NULL) { if (!_refed && _data->videoSink != NULL) {
gst_element_set_state(_data->videoSink, GST_STATE_NULL); gst_element_set_state(_data->videoSink, GST_STATE_NULL);
} }
delete _data; delete _data;
...@@ -42,7 +43,7 @@ VideoSurface::~VideoSurface() ...@@ -42,7 +43,7 @@ VideoSurface::~VideoSurface()
} }
#if defined(QGC_GST_STREAMING) #if defined(QGC_GST_STREAMING)
GstElement* VideoSurface::videoSink() const GstElement* VideoSurface::videoSink()
{ {
if (_data->videoSink == NULL) { if (_data->videoSink == NULL) {
if ((_data->videoSink = gst_element_factory_make("qtquick2videosink", NULL)) == NULL) { if ((_data->videoSink = gst_element_factory_make("qtquick2videosink", NULL)) == NULL) {
...@@ -50,6 +51,7 @@ GstElement* VideoSurface::videoSink() const ...@@ -50,6 +51,7 @@ GstElement* VideoSurface::videoSink() const
return NULL; return NULL;
} }
g_signal_connect(_data->videoSink, "update", G_CALLBACK(onUpdateThunk), (void* )this); g_signal_connect(_data->videoSink, "update", G_CALLBACK(onUpdateThunk), (void* )this);
_refed = true;
} }
return _data->videoSink; return _data->videoSink;
} }
......
...@@ -40,7 +40,7 @@ public: ...@@ -40,7 +40,7 @@ public:
* is called. The surface will always keep a reference to this element. * is called. The surface will always keep a reference to this element.
*/ */
#if defined(QGC_GST_STREAMING) #if defined(QGC_GST_STREAMING)
GstElement* videoSink() const; GstElement* videoSink();
time_t lastFrame() { return _lastFrame; } time_t lastFrame() { return _lastFrame; }
void setLastFrame(time_t t) { _lastFrame = t; } void setLastFrame(time_t t) { _lastFrame = t; }
#endif #endif
...@@ -56,6 +56,7 @@ private: ...@@ -56,6 +56,7 @@ private:
#if defined(QGC_GST_STREAMING) #if defined(QGC_GST_STREAMING)
VideoSurfacePrivate * const _data; VideoSurfacePrivate * const _data;
time_t _lastFrame; time_t _lastFrame;
bool _refed;
#endif #endif
}; };
......
This diff is collapsed.
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