Commit ba1378fa authored by Gus Grubba's avatar Gus Grubba

Added h.264 on MPEG TS (over UDP)

Updated MAVLink to handle video stream types (auto discovery)
parent e62a771c
...@@ -35,6 +35,7 @@ QGC_LOGGING_CATEGORY(VideoManagerLog, "VideoManagerLog") ...@@ -35,6 +35,7 @@ QGC_LOGGING_CATEGORY(VideoManagerLog, "VideoManagerLog")
VideoManager::VideoManager(QGCApplication* app, QGCToolbox* toolbox) VideoManager::VideoManager(QGCApplication* app, QGCToolbox* toolbox)
: QGCTool(app, toolbox) : QGCTool(app, toolbox)
{ {
_streamInfo = {};
} }
//----------------------------------------------------------------------------- //-----------------------------------------------------------------------------
...@@ -164,7 +165,8 @@ VideoManager::isGStreamer() ...@@ -164,7 +165,8 @@ VideoManager::isGStreamer()
videoSource == VideoSettings::videoSourceUDP || videoSource == VideoSettings::videoSourceUDP ||
videoSource == VideoSettings::videoSourceRTSP || videoSource == VideoSettings::videoSourceRTSP ||
videoSource == VideoSettings::videoSourceAuto || videoSource == VideoSettings::videoSourceAuto ||
videoSource == VideoSettings::videoSourceTCP; videoSource == VideoSettings::videoSourceTCP ||
videoSource == VideoSettings::videoSourceMPEGTS;
#else #else
return false; return false;
#endif #endif
...@@ -197,14 +199,33 @@ VideoManager::_updateSettings() ...@@ -197,14 +199,33 @@ VideoManager::_updateSettings()
{ {
if(!_videoSettings || !_videoReceiver) if(!_videoSettings || !_videoReceiver)
return; return;
if (_videoSettings->videoSource()->rawValue().toString() == VideoSettings::videoSourceUDP) QString source = _videoSettings->videoSource()->rawValue().toString();
if (source == VideoSettings::videoSourceUDP)
_videoReceiver->setUri(QStringLiteral("udp://0.0.0.0:%1").arg(_videoSettings->udpPort()->rawValue().toInt())); _videoReceiver->setUri(QStringLiteral("udp://0.0.0.0:%1").arg(_videoSettings->udpPort()->rawValue().toInt()));
else if (_videoSettings->videoSource()->rawValue().toString() == VideoSettings::videoSourceRTSP) else if (source == VideoSettings::videoSourceMPEGTS)
_videoReceiver->setUri(QStringLiteral("mpegts://0.0.0.0:%1").arg(_videoSettings->udpPort()->rawValue().toInt()));
else if (source == VideoSettings::videoSourceRTSP)
_videoReceiver->setUri(_videoSettings->rtspUrl()->rawValue().toString()); _videoReceiver->setUri(_videoSettings->rtspUrl()->rawValue().toString());
else if (_videoSettings->videoSource()->rawValue().toString() == VideoSettings::videoSourceTCP) else if (source == 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()) //-- Auto discovery
_videoReceiver->setUri(QString(_streamInfo.uri)); else if (isAutoStream()) {
switch(_streamInfo.type) {
case VIDEO_STREAM_TYPE_RTSP:
case VIDEO_STREAM_TYPE_TCP_MPEG:
_videoReceiver->setUri(QString(_streamInfo.uri));
break;
case VIDEO_STREAM_TYPE_RTPUDP:
_videoReceiver->setUri(QStringLiteral("udp://0.0.0.0:%1").arg(atoi(_streamInfo.uri)));
break;
case VIDEO_STREAM_TYPE_MPEG_TS_H264:
_videoReceiver->setUri(QStringLiteral("mpegts://0.0.0.0:%1").arg(atoi(_streamInfo.uri)));
break;
default:
_videoReceiver->setUri(QString(_streamInfo.uri));
break;
}
}
} }
//----------------------------------------------------------------------------- //-----------------------------------------------------------------------------
...@@ -212,6 +233,7 @@ void ...@@ -212,6 +233,7 @@ void
VideoManager::_restartVideo() VideoManager::_restartVideo()
{ {
#if defined(QGC_GST_STREAMING) #if defined(QGC_GST_STREAMING)
qCDebug(VideoManagerLog) << "Restart video streaming";
if(!_videoReceiver) if(!_videoReceiver)
return; return;
_videoReceiver->stop(); _videoReceiver->stop();
......
...@@ -61,7 +61,7 @@ public: ...@@ -61,7 +61,7 @@ public:
#endif #endif
void setfullScreen (bool f) { _fullScreen = f; emit fullScreenChanged(); } void setfullScreen (bool f) { _fullScreen = f; emit fullScreenChanged(); }
void setIsTaisync (bool t) { _isTaisync = t; emit isTaisyncChanged(); } void setIsTaisync (bool t) { _isTaisync = t; emit isTaisyncChanged(); }
// Override from QGCTool // Override from QGCTool
void setToolbox (QGCToolbox *toolbox); void setToolbox (QGCToolbox *toolbox);
......
...@@ -25,6 +25,7 @@ const char* VideoSettings::videoSourceAuto = "Automatic Video Stream"; ...@@ -25,6 +25,7 @@ const char* VideoSettings::videoSourceAuto = "Automatic Video Stream";
const char* VideoSettings::videoSourceRTSP = "RTSP Video Stream"; const char* VideoSettings::videoSourceRTSP = "RTSP Video Stream";
const char* VideoSettings::videoSourceUDP = "UDP Video Stream"; const char* VideoSettings::videoSourceUDP = "UDP Video Stream";
const char* VideoSettings::videoSourceTCP = "TCP-MPEG2 Video Stream"; const char* VideoSettings::videoSourceTCP = "TCP-MPEG2 Video Stream";
const char* VideoSettings::videoSourceMPEGTS = "MPEG-TS (h.264) Video Stream";
DECLARE_SETTINGGROUP(Video, "Video") DECLARE_SETTINGGROUP(Video, "Video")
{ {
...@@ -40,6 +41,7 @@ DECLARE_SETTINGGROUP(Video, "Video") ...@@ -40,6 +41,7 @@ DECLARE_SETTINGGROUP(Video, "Video")
videoSourceList.append(videoSourceUDP); videoSourceList.append(videoSourceUDP);
#endif #endif
videoSourceList.append(videoSourceTCP); videoSourceList.append(videoSourceTCP);
videoSourceList.append(videoSourceMPEGTS);
#endif #endif
#ifndef QGC_DISABLE_UVC #ifndef QGC_DISABLE_UVC
QList<QCameraInfo> cameras = QCameraInfo::availableCameras(); QList<QCameraInfo> cameras = QCameraInfo::availableCameras();
...@@ -150,6 +152,11 @@ bool VideoSettings::streamConfigured(void) ...@@ -150,6 +152,11 @@ bool VideoSettings::streamConfigured(void)
qCDebug(VideoManagerLog) << "Testing configuration for TCP Stream:" << tcpUrl()->rawValue().toString(); qCDebug(VideoManagerLog) << "Testing configuration for TCP Stream:" << tcpUrl()->rawValue().toString();
return !tcpUrl()->rawValue().toString().isEmpty(); return !tcpUrl()->rawValue().toString().isEmpty();
} }
//-- If MPEG-TS, check if port is set
if(vSource == videoSourceMPEGTS) {
qCDebug(VideoManagerLog) << "Testing configuration for MPEG-TS Stream:" << udpPort()->rawValue().toInt();
return udpPort()->rawValue().toInt() != 0;
}
//-- If Auto, check for received URL //-- If Auto, check for received URL
if(vSource == videoSourceAuto) { if(vSource == videoSourceAuto) {
qCDebug(VideoManagerLog) << "Testing configuration for Auto Stream:" << qgcApp()->toolbox()->videoManager()->autoURL(); qCDebug(VideoManagerLog) << "Testing configuration for Auto Stream:" << qgcApp()->toolbox()->videoManager()->autoURL();
......
...@@ -40,12 +40,14 @@ public: ...@@ -40,12 +40,14 @@ public:
Q_PROPERTY(QString rtspVideoSource READ rtspVideoSource CONSTANT) Q_PROPERTY(QString rtspVideoSource READ rtspVideoSource CONSTANT)
Q_PROPERTY(QString udpVideoSource READ udpVideoSource CONSTANT) Q_PROPERTY(QString udpVideoSource READ udpVideoSource CONSTANT)
Q_PROPERTY(QString tcpVideoSource READ tcpVideoSource CONSTANT) Q_PROPERTY(QString tcpVideoSource READ tcpVideoSource CONSTANT)
Q_PROPERTY(QString mpegtsVideoSource READ mpegtsVideoSource CONSTANT)
bool streamConfigured (); bool streamConfigured ();
QString autoVideoSource () { return videoSourceAuto; } QString autoVideoSource () { return videoSourceAuto; }
QString rtspVideoSource () { return videoSourceRTSP; } QString rtspVideoSource () { return videoSourceRTSP; }
QString udpVideoSource () { return videoSourceUDP; } QString udpVideoSource () { return videoSourceUDP; }
QString tcpVideoSource () { return videoSourceTCP; } QString tcpVideoSource () { return videoSourceTCP; }
QString mpegtsVideoSource () { return videoSourceMPEGTS; }
static const char* videoSourceNoVideo; static const char* videoSourceNoVideo;
static const char* videoDisabled; static const char* videoDisabled;
...@@ -53,6 +55,7 @@ public: ...@@ -53,6 +55,7 @@ public:
static const char* videoSourceRTSP; static const char* videoSourceRTSP;
static const char* videoSourceAuto; static const char* videoSourceAuto;
static const char* videoSourceTCP; static const char* videoSourceTCP;
static const char* videoSourceMPEGTS;
signals: signals:
void streamConfiguredChanged (); void streamConfiguredChanged ();
......
...@@ -239,9 +239,10 @@ VideoReceiver::start() ...@@ -239,9 +239,10 @@ VideoReceiver::start()
#else #else
bool isTaisyncUSB = false; bool isTaisyncUSB = false;
#endif #endif
bool isUdp = _uri.contains("udp://") && !isTaisyncUSB; bool isUdp = _uri.contains("udp://") && !isTaisyncUSB;
bool isRtsp = _uri.contains("rtsp://") && !isTaisyncUSB; bool isRtsp = _uri.contains("rtsp://") && !isTaisyncUSB;
bool isTCP = _uri.contains("tcp://") && !isTaisyncUSB; bool isTCP = _uri.contains("tcp://") && !isTaisyncUSB;
bool isMPEGTS = _uri.contains("mpegts://") && !isTaisyncUSB;
if (!isTaisyncUSB && _uri.isEmpty()) { if (!isTaisyncUSB && _uri.isEmpty()) {
qCritical() << "VideoReceiver::start() failed because URI is not specified"; qCritical() << "VideoReceiver::start() failed because URI is not specified";
...@@ -281,7 +282,7 @@ VideoReceiver::start() ...@@ -281,7 +282,7 @@ VideoReceiver::start()
break; break;
} }
if(isUdp || isTaisyncUSB) { if(isUdp || isMPEGTS || isTaisyncUSB) {
dataSource = gst_element_factory_make("udpsrc", "udp-source"); dataSource = gst_element_factory_make("udpsrc", "udp-source");
} else if(isTCP) { } else if(isTCP) {
dataSource = gst_element_factory_make("tcpclientsrc", "tcpclient-source"); dataSource = gst_element_factory_make("tcpclientsrc", "tcpclient-source");
...@@ -309,24 +310,26 @@ VideoReceiver::start() ...@@ -309,24 +310,26 @@ VideoReceiver::start()
} else if(isTCP) { } else if(isTCP) {
QUrl url(_uri); QUrl url(_uri);
g_object_set(static_cast<gpointer>(dataSource), "host", qPrintable(url.host()), "port", url.port(), nullptr ); g_object_set(static_cast<gpointer>(dataSource), "host", qPrintable(url.host()), "port", url.port(), nullptr );
} else if(isMPEGTS) {
QUrl url(_uri);
g_object_set(static_cast<gpointer>(dataSource), "port", url.port(), nullptr);
} else { } else {
g_object_set(static_cast<gpointer>(dataSource), "location", qPrintable(_uri), "latency", 17, "udp-reconnect", 1, "timeout", _udpReconnect_us, NULL); g_object_set(static_cast<gpointer>(dataSource), "location", qPrintable(_uri), "latency", 17, "udp-reconnect", 1, "timeout", _udpReconnect_us, NULL);
} }
// Currently, we expect H264 when using anything except for TCP. Long term we may want this to be settable if (isTCP || isMPEGTS) {
if (isTCP) { if ((demux = gst_element_factory_make("tsdemux", "mpeg-ts-demuxer")) == nullptr) {
if ((demux = gst_element_factory_make("tsdemux", "mpeg2-ts-demuxer")) == nullptr) {
qCritical() << "VideoReceiver::start() failed. Error with gst_element_factory_make('tsdemux')"; qCritical() << "VideoReceiver::start() failed. Error with gst_element_factory_make('tsdemux')";
break; break;
} }
} else { } else {
if(!isTaisyncUSB) { if(!isTaisyncUSB) {
if ((demux = gst_element_factory_make("rtph264depay", "rtp-h264-depacketizer")) == nullptr) { if ((demux = gst_element_factory_make("rtph264depay", "rtp-h264-depacketizer")) == nullptr) {
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 ((parser = gst_element_factory_make("h264parse", "h264-parser")) == nullptr) { if ((parser = gst_element_factory_make("h264parse", "h264-parser")) == nullptr) {
qCritical() << "VideoReceiver::start() failed. Error with gst_element_factory_make('h264parse')"; qCritical() << "VideoReceiver::start() failed. Error with gst_element_factory_make('h264parse')";
...@@ -374,13 +377,13 @@ VideoReceiver::start() ...@@ -374,13 +377,13 @@ VideoReceiver::start()
qCritical() << "Unable to link Taisync USB elements."; qCritical() << "Unable to link Taisync USB elements.";
break; break;
} }
} else if (isTCP) { } else if (isTCP || isMPEGTS) {
if(!gst_element_link(dataSource, demux)) { if(!gst_element_link(dataSource, demux)) {
qCritical() << "Unable to link TCP dataSource to Demux."; qCritical() << "Unable to link TCP/MPEG-TS dataSource to Demux.";
break; break;
} }
if(!gst_element_link_many(parser, _tee, queue, decoder, queue1, _videoSink, nullptr)) { if(!gst_element_link_many(parser, _tee, queue, decoder, queue1, _videoSink, nullptr)) {
qCritical() << "Unable to link TCP pipline to parser."; qCritical() << "Unable to link TCP/MPEG-TS pipline to parser.";
break; break;
} }
g_signal_connect(demux, "pad-added", G_CALLBACK(newPadCB), parser); g_signal_connect(demux, "pad-added", G_CALLBACK(newPadCB), parser);
...@@ -469,7 +472,7 @@ VideoReceiver::start() ...@@ -469,7 +472,7 @@ VideoReceiver::start()
void void
VideoReceiver::stop() VideoReceiver::stop()
{ {
if(!qgcApp()->runningUnitTests()) { if(qgcApp()->runningUnitTests()) {
return; return;
} }
#if defined(QGC_GST_STREAMING) #if defined(QGC_GST_STREAMING)
......
...@@ -130,11 +130,13 @@ void initializeVideoStreaming(int &argc, char* argv[], char* logpath, char* debu ...@@ -130,11 +130,13 @@ void initializeVideoStreaming(int &argc, char* argv[], char* logpath, char* debu
#else #else
//-- Generic initialization //-- Generic initialization
if (logpath) { if (logpath) {
QString gstDebugFile = QString("%1/%2").arg(logpath).arg("gstreamer-log.txt");
qDebug() << "GStreamer debug output:" << gstDebugFile;
if (debuglevel) { if (debuglevel) {
qputenv("GST_DEBUG", debuglevel); qputenv("GST_DEBUG", debuglevel);
} }
qputenv("GST_DEBUG_NO_COLOR", "1"); qputenv("GST_DEBUG_NO_COLOR", "1");
qputenv("GST_DEBUG_FILE", QString("%1/%2").arg(logpath).arg("gstreamer-log.txt").toUtf8()); qputenv("GST_DEBUG_FILE", gstDebugFile.toUtf8());
qputenv("GST_DEBUG_DUMP_DOT_DIR", logpath); qputenv("GST_DEBUG_DUMP_DOT_DIR", logpath);
} }
GError* error = nullptr; GError* error = nullptr;
......
...@@ -37,7 +37,7 @@ QGCView { ...@@ -37,7 +37,7 @@ QGCView {
property Fact _userBrandImageIndoor: QGroundControl.settingsManager.brandImageSettings.userBrandImageIndoor property Fact _userBrandImageIndoor: QGroundControl.settingsManager.brandImageSettings.userBrandImageIndoor
property Fact _userBrandImageOutdoor: QGroundControl.settingsManager.brandImageSettings.userBrandImageOutdoor property Fact _userBrandImageOutdoor: QGroundControl.settingsManager.brandImageSettings.userBrandImageOutdoor
property real _labelWidth: ScreenTools.defaultFontPixelWidth * 20 property real _labelWidth: ScreenTools.defaultFontPixelWidth * 20
property real _comboFieldWidth: ScreenTools.defaultFontPixelWidth * 25 property real _comboFieldWidth: ScreenTools.defaultFontPixelWidth * 28
property real _valueFieldWidth: ScreenTools.defaultFontPixelWidth * 10 property real _valueFieldWidth: ScreenTools.defaultFontPixelWidth * 10
property Fact _mapProvider: QGroundControl.settingsManager.flightMapSettings.mapProvider property Fact _mapProvider: QGroundControl.settingsManager.flightMapSettings.mapProvider
property Fact _mapType: QGroundControl.settingsManager.flightMapSettings.mapType property Fact _mapType: QGroundControl.settingsManager.flightMapSettings.mapType
...@@ -51,6 +51,7 @@ QGCView { ...@@ -51,6 +51,7 @@ QGCView {
property bool _isUDP: _isGst && _videoSource === QGroundControl.settingsManager.videoSettings.udpVideoSource property bool _isUDP: _isGst && _videoSource === QGroundControl.settingsManager.videoSettings.udpVideoSource
property bool _isRTSP: _isGst && _videoSource === QGroundControl.settingsManager.videoSettings.rtspVideoSource property bool _isRTSP: _isGst && _videoSource === QGroundControl.settingsManager.videoSettings.rtspVideoSource
property bool _isTCP: _isGst && _videoSource === QGroundControl.settingsManager.videoSettings.tcpVideoSource property bool _isTCP: _isGst && _videoSource === QGroundControl.settingsManager.videoSettings.tcpVideoSource
property bool _isMPEGTS: _isGst && _videoSource === QGroundControl.settingsManager.videoSettings.mpegtsVideoSource
readonly property real _internalWidthRatio: 0.8 readonly property real _internalWidthRatio: 0.8
...@@ -707,7 +708,6 @@ QGCView { ...@@ -707,7 +708,6 @@ QGCView {
Layout.fillWidth: false Layout.fillWidth: false
Layout.fillHeight: false Layout.fillHeight: false
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
...@@ -722,12 +722,12 @@ QGCView { ...@@ -722,12 +722,12 @@ QGCView {
QGCLabel { QGCLabel {
text: qsTr("UDP Port") text: qsTr("UDP Port")
visible: _isUDP && QGroundControl.settingsManager.videoSettings.udpPort.visible visible: (_isUDP || _isMPEGTS) && QGroundControl.settingsManager.videoSettings.udpPort.visible
} }
FactTextField { FactTextField {
Layout.preferredWidth: _comboFieldWidth Layout.preferredWidth: _comboFieldWidth
fact: QGroundControl.settingsManager.videoSettings.udpPort fact: QGroundControl.settingsManager.videoSettings.udpPort
visible: _isUDP && QGroundControl.settingsManager.videoSettings.udpPort.visible visible: (_isUDP || _isMPEGTS) && QGroundControl.settingsManager.videoSettings.udpPort.visible
} }
QGCLabel { QGCLabel {
......
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