diff --git a/ChangeLog.md b/ChangeLog.md index 3d58591c8981cf64036855dba92af2635c38d653..41237564f31f4da2596c4db75ed9813bd9f04d3d 100644 --- a/ChangeLog.md +++ b/ChangeLog.md @@ -6,6 +6,7 @@ Note: This file only contains high level features or important fixes. ### 3.6.0 - Daily Build +* Adding support for UDP RTP h.265 video streams * For text to speech engine on Linux to English (all messages are in English) * Automated the ingestion of localization from Crowdin * Automated the generation of language resources into the application diff --git a/src/FlightDisplay/VideoManager.cc b/src/FlightDisplay/VideoManager.cc index 97736420725536251ae825e3d5afbbdc9c50ae8e..1bacebb9dd54b243dc14442a92d2778e0c06f6e1 100644 --- a/src/FlightDisplay/VideoManager.cc +++ b/src/FlightDisplay/VideoManager.cc @@ -249,7 +249,8 @@ VideoManager::isGStreamer() #if defined(QGC_GST_STREAMING) QString videoSource = _videoSettings->videoSource()->rawValue().toString(); return - videoSource == VideoSettings::videoSourceUDP || + videoSource == VideoSettings::videoSourceUDPH264 || + videoSource == VideoSettings::videoSourceUDPH265 || videoSource == VideoSettings::videoSourceRTSP || videoSource == VideoSettings::videoSourceTCP || videoSource == VideoSettings::videoSourceMPEGTS || @@ -325,8 +326,10 @@ VideoManager::_updateSettings() } } QString source = _videoSettings->videoSource()->rawValue().toString(); - if (source == VideoSettings::videoSourceUDP) + if (source == VideoSettings::videoSourceUDPH264) _videoReceiver->setUri(QStringLiteral("udp://0.0.0.0:%1").arg(_videoSettings->udpPort()->rawValue().toInt())); + else if (source == VideoSettings::videoSourceUDPH265) + _videoReceiver->setUri(QStringLiteral("udp265://0.0.0.0:%1").arg(_videoSettings->udpPort()->rawValue().toInt())); else if (source == VideoSettings::videoSourceMPEGTS) _videoReceiver->setUri(QStringLiteral("mpegts://0.0.0.0:%1").arg(_videoSettings->udpPort()->rawValue().toInt())); else if (source == VideoSettings::videoSourceRTSP) diff --git a/src/Settings/VideoSettings.cc b/src/Settings/VideoSettings.cc index 78b0c6f1fb0c3890cfffff3f5a7919fd6a593501..a0d0184c50cef861d8eeab6aabfa97997db22164 100644 --- a/src/Settings/VideoSettings.cc +++ b/src/Settings/VideoSettings.cc @@ -22,7 +22,8 @@ const char* VideoSettings::videoSourceNoVideo = "No Video Available"; const char* VideoSettings::videoDisabled = "Video Stream Disabled"; const char* VideoSettings::videoSourceRTSP = "RTSP Video Stream"; -const char* VideoSettings::videoSourceUDP = "UDP Video Stream"; +const char* VideoSettings::videoSourceUDPH264 = "UDP h.264 Video Stream"; +const char* VideoSettings::videoSourceUDPH265 = "UDP h.265 Video Stream"; const char* VideoSettings::videoSourceTCP = "TCP-MPEG2 Video Stream"; const char* VideoSettings::videoSourceMPEGTS = "MPEG-TS (h.264) Video Stream"; @@ -35,7 +36,8 @@ DECLARE_SETTINGGROUP(Video, "Video") #ifdef QGC_GST_STREAMING videoSourceList.append(videoSourceRTSP); #ifndef NO_UDP_VIDEO - videoSourceList.append(videoSourceUDP); + videoSourceList.append(videoSourceUDPH264); + videoSourceList.append(videoSourceUDPH265); #endif videoSourceList.append(videoSourceTCP); videoSourceList.append(videoSourceMPEGTS); @@ -141,7 +143,7 @@ bool VideoSettings::streamConfigured(void) return false; } //-- If UDP, check if port is set - if(vSource == videoSourceUDP) { + if(vSource == videoSourceUDPH264 || vSource == videoSourceUDPH265) { qCDebug(VideoManagerLog) << "Testing configuration for UDP Stream:" << udpPort()->rawValue().toInt(); return udpPort()->rawValue().toInt() != 0; } diff --git a/src/Settings/VideoSettings.h b/src/Settings/VideoSettings.h index a419b6a95d8e7ee7b12f3d7dc286931349dc8026..431e5a31f0fa46b9c796ae3c4d20d97cd1418ec8 100644 --- a/src/Settings/VideoSettings.h +++ b/src/Settings/VideoSettings.h @@ -37,19 +37,22 @@ public: Q_PROPERTY(bool streamConfigured READ streamConfigured NOTIFY streamConfiguredChanged) Q_PROPERTY(QString rtspVideoSource READ rtspVideoSource CONSTANT) - Q_PROPERTY(QString udpVideoSource READ udpVideoSource CONSTANT) + Q_PROPERTY(QString udp264VideoSource READ udp264VideoSource CONSTANT) + Q_PROPERTY(QString udp265VideoSource READ udp265VideoSource CONSTANT) Q_PROPERTY(QString tcpVideoSource READ tcpVideoSource CONSTANT) Q_PROPERTY(QString mpegtsVideoSource READ mpegtsVideoSource CONSTANT) bool streamConfigured (); QString rtspVideoSource () { return videoSourceRTSP; } - QString udpVideoSource () { return videoSourceUDP; } + QString udp264VideoSource () { return videoSourceUDPH264; } + QString udp265VideoSource () { return videoSourceUDPH265; } QString tcpVideoSource () { return videoSourceTCP; } QString mpegtsVideoSource () { return videoSourceMPEGTS; } static const char* videoSourceNoVideo; static const char* videoDisabled; - static const char* videoSourceUDP; + static const char* videoSourceUDPH264; + static const char* videoSourceUDPH265; static const char* videoSourceRTSP; static const char* videoSourceTCP; static const char* videoSourceMPEGTS; diff --git a/src/Taisync/TaisyncManager.cc b/src/Taisync/TaisyncManager.cc index cdc0eadbc79a8ee19c6130efbe064972f1a0ad25..86033f95f8e79968e55515cddd43b8c9181acc09 100644 --- a/src/Taisync/TaisyncManager.cc +++ b/src/Taisync/TaisyncManager.cc @@ -337,7 +337,7 @@ TaisyncManager::_setVideoEnabled() pVSettings->udpPort()->setRawValue(5600); //-- TODO: this AR must come from somewhere pVSettings->aspectRatio()->setRawValue(1024.0 / 768.0); - pVSettings->videoSource()->setRawValue(QString(VideoSettings::videoSourceUDP)); + pVSettings->videoSource()->setRawValue(QString(VideoSettings::videoSourceUDPH264)); #if defined(__ios__) || defined(__android__) if(!_taiVideo) { //-- iOS and Android receive raw h.264 and need a different pipeline diff --git a/src/Vehicle/Vehicle.cc b/src/Vehicle/Vehicle.cc index 690c2a8ca186a30c2e77b882f404996552239818..fb1e76bfc5abd21290a647653b6064e6364c891d 100644 --- a/src/Vehicle/Vehicle.cc +++ b/src/Vehicle/Vehicle.cc @@ -511,7 +511,7 @@ void Vehicle::_commonInit(void) // Set video stream to udp if running ArduSub and Video is disabled if (sub() && _settingsManager->videoSettings()->videoSource()->rawValue() == VideoSettings::videoDisabled) { - _settingsManager->videoSettings()->videoSource()->setRawValue(VideoSettings::videoSourceUDP); + _settingsManager->videoSettings()->videoSource()->setRawValue(VideoSettings::videoSourceUDPH264); } //-- Airspace Management diff --git a/src/VideoStreaming/README.md b/src/VideoStreaming/README.md index feb2916fbbd187e4b3a4e0ac4f550c7a0932ff57..4e851fed6aee8d085ba076641ed4d70bbf06de46 100644 --- a/src/VideoStreaming/README.md +++ b/src/VideoStreaming/README.md @@ -7,15 +7,22 @@ To build video streaming support, you will need to install the GStreamer develop If you do have the proper GStreamer development libraries installed where QGC looks for it, the QGC build system will automatically use it and build video streaming support. If you would like to disable video streaming support, you can add **DISABLE_VIDEOSTREAMING** to the **DEFINES** build variable. -### Pipeline +### UDP Pipeline -For the time being, the pipeline is somewhat hardcoded, using h.264. It's best to use a camera capable of hardware encoding h.264, such as the Logitech C920. On the sender end, for RTP (UDP Streaming) you would run something like this: +For the time being, the RTP UDP pipeline is somewhat hardcoded, using h.264 or h.265. It's best to use a camera capable of hardware encoding either h.264 (such as the Logitech C920) or h.265. On the sender end, for RTP (UDP Streaming) you would run something like this: +h.264 ``` gst-launch-1.0 uvch264src initial-bitrate=1000000 average-bitrate=1000000 iframe-period=1000 device=/dev/video0 name=src auto-start=true src.vidsrc ! video/x-h264,width=1920,height=1080,framerate=24/1 ! h264parse ! rtph264pay ! udpsink host=xxx.xxx.xxx.xxx port=5600 ``` -Where xxx.xxx.xxx.xxx is the IP address where QGC is running. You may tweak the bitrate, the resolution and the FPS based on your needs and/or available bandwidth. +h.265 +``` +ffmpeg -f v4l2 -i /dev/video1 -pix_fmt yuv420p -c:v libx265 -preset ultrafast -x265-params crf=23 -strict experimental -f rtp udp://xxx.xxx.xxx.xxx:5600 +``` + +Where xxx.xxx.xxx.xxx is the IP address where QGC is running. + To test using a test source on localhost, you can run this command: ``` @@ -31,6 +38,10 @@ On the receiving end, if you want to test it from the command line, you can use gst-launch-1.0 udpsrc port=5600 caps='application/x-rtp, media=(string)video, clock-rate=(int)90000, encoding-name=(string)H264' ! rtph264depay ! avdec_h264 ! autovideosink fps-update-interval=1000 sync=false ``` +### Additional Protocols + +QGC also supports RTSP, TCP-MPEG2 and MPEG-TS (h.264) pipelines. + ### Linux Use apt-get to install GStreamer 1.0 diff --git a/src/VideoStreaming/VideoReceiver.cc b/src/VideoStreaming/VideoReceiver.cc index 6fc9c3184289090c9259aa9ac7bfa1b2cf2c60ee..cd62f8d11aa28864b44d8f4ecd5f75c57f08a430 100644 --- a/src/VideoStreaming/VideoReceiver.cc +++ b/src/VideoStreaming/VideoReceiver.cc @@ -75,7 +75,7 @@ VideoReceiver::VideoReceiver(QObject* parent) , _swDecoderName("avdec_h264") { _videoSurface = new VideoSurface; - _videoSettings = qgcApp()->toolbox()->settingsManager()->videoSettings(); + _videoSettings = qgcApp()->toolbox()->settingsManager()->videoSettings(); #if defined(QGC_GST_STREAMING) setVideoDecoder(H264_SW); _setVideoSink(_videoSurface->videoSink()); @@ -183,7 +183,8 @@ VideoReceiver::start() #else bool isTaisyncUSB = false; #endif - bool isUdp = _uri.contains("udp://") && !isTaisyncUSB; + bool isUdp264 = _uri.contains("udp://") && !isTaisyncUSB; + bool isUdp265 = _uri.contains("udp265://") && !isTaisyncUSB; bool isTCP = _uri.contains("tcp://") && !isTaisyncUSB; bool isMPEGTS = _uri.contains("mpegts://") && !isTaisyncUSB; @@ -199,6 +200,11 @@ VideoReceiver::start() qCDebug(VideoReceiverLog) << "Already running!"; return; } + if (isUdp264) { + setVideoDecoder(H264_HW); + } else if (isUdp265) { + setVideoDecoder(H265_HW); + } _starting = true; @@ -219,7 +225,7 @@ VideoReceiver::start() break; } - if(isUdp || isMPEGTS || isTaisyncUSB) { + if(isUdp264 || isUdp265 || isMPEGTS || isTaisyncUSB) { dataSource = gst_element_factory_make("udpsrc", "udp-source"); } else if(isTCP) { dataSource = gst_element_factory_make("tcpclientsrc", "tcpclient-source"); @@ -232,12 +238,18 @@ VideoReceiver::start() break; } - if(isUdp) { + if(isUdp264) { if ((caps = gst_caps_from_string("application/x-rtp, media=(string)video, clock-rate=(int)90000, encoding-name=(string)H264")) == nullptr) { qCritical() << "VideoReceiver::start() failed. Error with gst_caps_from_string()"; break; } g_object_set(static_cast(dataSource), "uri", qPrintable(_uri), "caps", caps, nullptr); + } else if(isUdp265) { + if ((caps = gst_caps_from_string("application/x-rtp, media=(string)video, clock-rate=(int)90000, encoding-name=(string)H265")) == nullptr) { + qCritical() << "VideoReceiver::start() failed. Error with gst_caps_from_string()"; + break; + } + g_object_set(static_cast(dataSource), "uri", qPrintable(_uri.replace("udp265", "udp")), "caps", caps, nullptr); #if defined(QGC_GST_TAISYNC_ENABLED) && (defined(__android__) || defined(__ios__)) } else if(isTaisyncUSB) { QString uri = QString("0.0.0.0:%1").arg(TAISYNC_VIDEO_UDP_PORT); @@ -305,7 +317,7 @@ VideoReceiver::start() } pipelineUp = true; - if(isUdp) { + if(isUdp264 || isUdp265) { // Link the pipeline in front of the tee if(!gst_element_link_many(dataSource, demux, parser, _tee, queue, decoder, queue1, _videoSink, nullptr)) { qCritical() << "Unable to link UDP elements."; diff --git a/src/ui/preferences/GeneralSettings.qml b/src/ui/preferences/GeneralSettings.qml index 809807b4866939e45043bfe0124f9185971962d6..add796374c6b5a8caacc1f4f02546228df99f805 100644 --- a/src/ui/preferences/GeneralSettings.qml +++ b/src/ui/preferences/GeneralSettings.qml @@ -46,7 +46,8 @@ Rectangle { property string _videoSource: QGroundControl.settingsManager.videoSettings.videoSource.value property bool _isGst: QGroundControl.videoManager.isGStreamer - property bool _isUDP: _isGst && _videoSource === QGroundControl.settingsManager.videoSettings.udpVideoSource + property bool _isUDP264: _isGst && _videoSource === QGroundControl.settingsManager.videoSettings.udp264VideoSource + property bool _isUDP265: _isGst && _videoSource === QGroundControl.settingsManager.videoSettings.udp265VideoSource 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 @@ -801,12 +802,12 @@ Rectangle { QGCLabel { text: qsTr("UDP Port") - visible: (_isUDP || _isMPEGTS) && QGroundControl.settingsManager.videoSettings.udpPort.visible + visible: (_isUDP264 || _isUDP265 || _isMPEGTS) && QGroundControl.settingsManager.videoSettings.udpPort.visible } FactTextField { Layout.preferredWidth: _comboFieldWidth fact: QGroundControl.settingsManager.videoSettings.udpPort - visible: (_isUDP || _isMPEGTS) && QGroundControl.settingsManager.videoSettings.udpPort.visible + visible: (_isUDP264 || _isUDP265 || _isMPEGTS) && QGroundControl.settingsManager.videoSettings.udpPort.visible } QGCLabel {