Commit ef6ef06c authored by Gus Grubba's avatar Gus Grubba

UDP RTP h.265 stream WIP

parent 1ec45440
......@@ -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
......
......@@ -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)
......
......@@ -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;
}
......
......@@ -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;
......
......@@ -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
......
......@@ -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
......
......@@ -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;
......@@ -219,7 +220,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 +233,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<gpointer>(dataSource), "uri", qPrintable(_uri), "caps", caps, nullptr);
} else if(isUdp265) {
//-- TODO
#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 +312,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.";
......
......@@ -46,7 +46,7 @@ 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 _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 +801,12 @@ Rectangle {
QGCLabel {
text: qsTr("UDP Port")
visible: (_isUDP || _isMPEGTS) && QGroundControl.settingsManager.videoSettings.udpPort.visible
visible: (_isUDP264 || _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 || _isMPEGTS) && QGroundControl.settingsManager.videoSettings.udpPort.visible
}
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