diff --git a/src/FlightDisplay/VideoManager.cc b/src/FlightDisplay/VideoManager.cc index 6a05f3c5e6d7c06888d258fb92a9e20b3001e524..68a157ad65229c55ac37429e01c70f3714147443 100644 --- a/src/FlightDisplay/VideoManager.cc +++ b/src/FlightDisplay/VideoManager.cc @@ -35,6 +35,7 @@ QGC_LOGGING_CATEGORY(VideoManagerLog, "VideoManagerLog") VideoManager::VideoManager(QGCApplication* app, QGCToolbox* toolbox) : QGCTool(app, toolbox) { + _streamInfo = {}; } //----------------------------------------------------------------------------- @@ -164,7 +165,8 @@ VideoManager::isGStreamer() videoSource == VideoSettings::videoSourceUDP || videoSource == VideoSettings::videoSourceRTSP || videoSource == VideoSettings::videoSourceAuto || - videoSource == VideoSettings::videoSourceTCP; + videoSource == VideoSettings::videoSourceTCP || + videoSource == VideoSettings::videoSourceMPEGTS; #else return false; #endif @@ -197,14 +199,33 @@ VideoManager::_updateSettings() { if(!_videoSettings || !_videoReceiver) 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())); - 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()); - else if (_videoSettings->videoSource()->rawValue().toString() == VideoSettings::videoSourceTCP) + else if (source == VideoSettings::videoSourceTCP) _videoReceiver->setUri(QStringLiteral("tcp://%1").arg(_videoSettings->tcpUrl()->rawValue().toString())); - else if (isAutoStream()) - _videoReceiver->setUri(QString(_streamInfo.uri)); + //-- Auto discovery + 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 VideoManager::_restartVideo() { #if defined(QGC_GST_STREAMING) + qCDebug(VideoManagerLog) << "Restart video streaming"; if(!_videoReceiver) return; _videoReceiver->stop(); diff --git a/src/FlightDisplay/VideoManager.h b/src/FlightDisplay/VideoManager.h index 7fa28c42e305f38ca7c42cbf389c17fcf24d4d64..a21d1391be8305f390cd0ea525dff919b0b0b314 100644 --- a/src/FlightDisplay/VideoManager.h +++ b/src/FlightDisplay/VideoManager.h @@ -61,7 +61,7 @@ public: #endif 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 void setToolbox (QGCToolbox *toolbox); diff --git a/src/Settings/VideoSettings.cc b/src/Settings/VideoSettings.cc index 8be433f2537defd557eea08872be6cb3e727d312..16ea77d446c64445a64662ba733c9f32bc4a52e2 100644 --- a/src/Settings/VideoSettings.cc +++ b/src/Settings/VideoSettings.cc @@ -25,6 +25,7 @@ const char* VideoSettings::videoSourceAuto = "Automatic Video Stream"; const char* VideoSettings::videoSourceRTSP = "RTSP Video Stream"; const char* VideoSettings::videoSourceUDP = "UDP Video Stream"; const char* VideoSettings::videoSourceTCP = "TCP-MPEG2 Video Stream"; +const char* VideoSettings::videoSourceMPEGTS = "MPEG-TS (h.264) Video Stream"; DECLARE_SETTINGGROUP(Video, "Video") { @@ -40,6 +41,7 @@ DECLARE_SETTINGGROUP(Video, "Video") videoSourceList.append(videoSourceUDP); #endif videoSourceList.append(videoSourceTCP); + videoSourceList.append(videoSourceMPEGTS); #endif #ifndef QGC_DISABLE_UVC QList cameras = QCameraInfo::availableCameras(); @@ -150,6 +152,11 @@ bool VideoSettings::streamConfigured(void) qCDebug(VideoManagerLog) << "Testing configuration for TCP Stream:" << tcpUrl()->rawValue().toString(); 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(vSource == videoSourceAuto) { qCDebug(VideoManagerLog) << "Testing configuration for Auto Stream:" << qgcApp()->toolbox()->videoManager()->autoURL(); diff --git a/src/Settings/VideoSettings.h b/src/Settings/VideoSettings.h index d0002fd0c07e14a88f11e991ef542069b3280b19..ff560235851f9de52338eb4514335725def43b85 100644 --- a/src/Settings/VideoSettings.h +++ b/src/Settings/VideoSettings.h @@ -40,12 +40,14 @@ public: Q_PROPERTY(QString rtspVideoSource READ rtspVideoSource CONSTANT) Q_PROPERTY(QString udpVideoSource READ udpVideoSource CONSTANT) Q_PROPERTY(QString tcpVideoSource READ tcpVideoSource CONSTANT) + Q_PROPERTY(QString mpegtsVideoSource READ mpegtsVideoSource CONSTANT) bool streamConfigured (); QString autoVideoSource () { return videoSourceAuto; } QString rtspVideoSource () { return videoSourceRTSP; } QString udpVideoSource () { return videoSourceUDP; } QString tcpVideoSource () { return videoSourceTCP; } + QString mpegtsVideoSource () { return videoSourceMPEGTS; } static const char* videoSourceNoVideo; static const char* videoDisabled; @@ -53,6 +55,7 @@ public: static const char* videoSourceRTSP; static const char* videoSourceAuto; static const char* videoSourceTCP; + static const char* videoSourceMPEGTS; signals: void streamConfiguredChanged (); diff --git a/src/VideoStreaming/VideoReceiver.cc b/src/VideoStreaming/VideoReceiver.cc index 32ca17317cfd065a4b1c3f8642fa153297a1d0e6..f7e52eb68578f39b5c5c24c7f855d508bb9bfaf6 100644 --- a/src/VideoStreaming/VideoReceiver.cc +++ b/src/VideoStreaming/VideoReceiver.cc @@ -239,9 +239,10 @@ VideoReceiver::start() #else bool isTaisyncUSB = false; #endif - bool isUdp = _uri.contains("udp://") && !isTaisyncUSB; - bool isRtsp = _uri.contains("rtsp://") && !isTaisyncUSB; - bool isTCP = _uri.contains("tcp://") && !isTaisyncUSB; + bool isUdp = _uri.contains("udp://") && !isTaisyncUSB; + bool isRtsp = _uri.contains("rtsp://") && !isTaisyncUSB; + bool isTCP = _uri.contains("tcp://") && !isTaisyncUSB; + bool isMPEGTS = _uri.contains("mpegts://") && !isTaisyncUSB; if (!isTaisyncUSB && _uri.isEmpty()) { qCritical() << "VideoReceiver::start() failed because URI is not specified"; @@ -281,7 +282,7 @@ VideoReceiver::start() break; } - if(isUdp || isTaisyncUSB) { + if(isUdp || isMPEGTS || isTaisyncUSB) { dataSource = gst_element_factory_make("udpsrc", "udp-source"); } else if(isTCP) { dataSource = gst_element_factory_make("tcpclientsrc", "tcpclient-source"); @@ -309,24 +310,26 @@ VideoReceiver::start() } else if(isTCP) { QUrl url(_uri); g_object_set(static_cast(dataSource), "host", qPrintable(url.host()), "port", url.port(), nullptr ); + } else if(isMPEGTS) { + QUrl url(_uri); + g_object_set(static_cast(dataSource), "port", url.port(), nullptr); } else { g_object_set(static_cast(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) { - if ((demux = gst_element_factory_make("tsdemux", "mpeg2-ts-demuxer")) == nullptr) { + if (isTCP || isMPEGTS) { + if ((demux = gst_element_factory_make("tsdemux", "mpeg-ts-demuxer")) == nullptr) { qCritical() << "VideoReceiver::start() failed. Error with gst_element_factory_make('tsdemux')"; break; } } else { if(!isTaisyncUSB) { if ((demux = gst_element_factory_make("rtph264depay", "rtp-h264-depacketizer")) == nullptr) { - qCritical() << "VideoReceiver::start() failed. Error with gst_element_factory_make('rtph264depay')"; - break; + qCritical() << "VideoReceiver::start() failed. Error with gst_element_factory_make('rtph264depay')"; + break; + } } } - } if ((parser = gst_element_factory_make("h264parse", "h264-parser")) == nullptr) { qCritical() << "VideoReceiver::start() failed. Error with gst_element_factory_make('h264parse')"; @@ -374,13 +377,13 @@ VideoReceiver::start() qCritical() << "Unable to link Taisync USB elements."; break; } - } else if (isTCP) { + } else if (isTCP || isMPEGTS) { 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; } 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; } g_signal_connect(demux, "pad-added", G_CALLBACK(newPadCB), parser); @@ -469,7 +472,7 @@ VideoReceiver::start() void VideoReceiver::stop() { - if(!qgcApp()->runningUnitTests()) { + if(qgcApp()->runningUnitTests()) { return; } #if defined(QGC_GST_STREAMING) diff --git a/src/VideoStreaming/VideoStreaming.cc b/src/VideoStreaming/VideoStreaming.cc index 265d6ecaeac69805668090d83ea3e170711ac8a9..cd02747e7a87ee4789fa939890dc641e22ae8de7 100644 --- a/src/VideoStreaming/VideoStreaming.cc +++ b/src/VideoStreaming/VideoStreaming.cc @@ -130,11 +130,13 @@ void initializeVideoStreaming(int &argc, char* argv[], char* logpath, char* debu #else //-- Generic initialization if (logpath) { + QString gstDebugFile = QString("%1/%2").arg(logpath).arg("gstreamer-log.txt"); + qDebug() << "GStreamer debug output:" << gstDebugFile; if (debuglevel) { qputenv("GST_DEBUG", debuglevel); } 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); } GError* error = nullptr; diff --git a/src/ui/preferences/GeneralSettings.qml b/src/ui/preferences/GeneralSettings.qml index fdb49133e4eca3d21567d10792f5011780fabc91..2a906c2cc44f64d193a255b512126ac86226936a 100644 --- a/src/ui/preferences/GeneralSettings.qml +++ b/src/ui/preferences/GeneralSettings.qml @@ -37,7 +37,7 @@ QGCView { property Fact _userBrandImageIndoor: QGroundControl.settingsManager.brandImageSettings.userBrandImageIndoor property Fact _userBrandImageOutdoor: QGroundControl.settingsManager.brandImageSettings.userBrandImageOutdoor 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 Fact _mapProvider: QGroundControl.settingsManager.flightMapSettings.mapProvider property Fact _mapType: QGroundControl.settingsManager.flightMapSettings.mapType @@ -51,6 +51,7 @@ QGCView { property bool _isUDP: _isGst && _videoSource === QGroundControl.settingsManager.videoSettings.udpVideoSource property bool _isRTSP: _isGst && _videoSource === QGroundControl.settingsManager.videoSettings.rtspVideoSource property bool _isTCP: _isGst && _videoSource === QGroundControl.settingsManager.videoSettings.tcpVideoSource + property bool _isMPEGTS: _isGst && _videoSource === QGroundControl.settingsManager.videoSettings.mpegtsVideoSource readonly property real _internalWidthRatio: 0.8 @@ -707,7 +708,6 @@ QGCView { Layout.fillWidth: false Layout.fillHeight: false columns: 2 - QGCLabel { text: qsTr("Video Source") visible: QGroundControl.settingsManager.videoSettings.videoSource.visible @@ -722,12 +722,12 @@ QGCView { QGCLabel { text: qsTr("UDP Port") - visible: _isUDP && QGroundControl.settingsManager.videoSettings.udpPort.visible + visible: (_isUDP || _isMPEGTS) && QGroundControl.settingsManager.videoSettings.udpPort.visible } FactTextField { Layout.preferredWidth: _comboFieldWidth fact: QGroundControl.settingsManager.videoSettings.udpPort - visible: _isUDP && QGroundControl.settingsManager.videoSettings.udpPort.visible + visible: (_isUDP || _isMPEGTS) && QGroundControl.settingsManager.videoSettings.udpPort.visible } QGCLabel {