From 7bd3eb7a2f12db724e90ff52ae1e21d11c36ac48 Mon Sep 17 00:00:00 2001 From: Vitalii Dovgan Date: Mon, 1 Dec 2025 20:48:26 +0200 Subject: [PATCH 1/2] Draft: Two video streams --- src/FlightDisplay/FlightDisplayViewVideo.qml | 145 ++++++++++++++---- src/Settings/Video.SettingsGroup.json | 28 ++++ src/Settings/VideoSettings.cc | 69 ++++++++- src/Settings/VideoSettings.h | 12 +- src/UI/AppSettings/VideoSettings.qml | 32 ++++ src/VideoManager/VideoManager.cc | 84 ++++++++-- src/VideoManager/VideoManager.h | 13 ++ .../VideoReceiver/VideoReceiver.h | 2 + 8 files changed, 337 insertions(+), 48 deletions(-) diff --git a/src/FlightDisplay/FlightDisplayViewVideo.qml b/src/FlightDisplay/FlightDisplayViewVideo.qml index 3723c527d842..d19b4490707b 100644 --- a/src/FlightDisplay/FlightDisplayViewVideo.qml +++ b/src/FlightDisplay/FlightDisplayViewVideo.qml @@ -85,7 +85,7 @@ Item { visible: QGroundControl.videoManager.decoding function getWidth() { if(_ar != 0.0){ - if(_isMode_FIT_HEIGHT + if(_isMode_FIT_HEIGHT || (_isMode_FILL && (root.width/root.height < _ar)) || (_isMode_NO_CROP && (root.width/root.height > _ar))){ // This return value has different implications depending on the mode @@ -100,8 +100,8 @@ Item { } function getHeight() { if(_ar != 0.0){ - if(_isMode_FIT_WIDTH - || (_isMode_FILL && (root.width/root.height > _ar)) + if(_isMode_FIT_WIDTH + || (_isMode_FILL && (root.width/root.height > _ar)) || (_isMode_NO_CROP && (root.width/root.height < _ar))){ // This return value has different implications depending on the mode // For FIT_WIDTH and FILL @@ -173,42 +173,121 @@ Item { property bool videoDisabled: QGroundControl.settingsManager.videoSettings.videoSource.rawValue === QGroundControl.settingsManager.videoSettings.disabledVideoSource } - //-- Thermal Image + //-- Backup Image Item { - id: thermalItem - width: height * QGroundControl.videoManager.thermalAspectRatio - height: _camera ? (_camera.thermalMode === MavlinkCameraControl.THERMAL_FULL ? parent.height : (_camera.thermalMode === MavlinkCameraControl.THERMAL_PIP ? ScreenTools.defaultFontPixelHeight * 12 : parent.height * _thermalHeightFactor)) : 0 - anchors.centerIn: parent - visible: QGroundControl.videoManager.hasThermal && _camera.thermalMode !== MavlinkCameraControl.THERMAL_OFF - function pipOrNot() { - if(_camera) { - if(_camera.thermalMode === MavlinkCameraControl.THERMAL_PIP) { - anchors.centerIn = undefined - anchors.top = parent.top - anchors.topMargin = mainWindow.header.height + (ScreenTools.defaultFontPixelHeight * 0.5) - anchors.left = parent.left - anchors.leftMargin = ScreenTools.defaultFontPixelWidth * 12 - } else { - anchors.top = undefined - anchors.topMargin = undefined - anchors.left = undefined - anchors.leftMargin = undefined - anchors.centerIn = parent - } - } + id: backupItem + width: height * QGroundControl.videoManager.aspectRatio + height: parent.height / 4 + visible: QGroundControl.settingsManager.videoSettings.rtspUrlBackup.rawValue !== "" && QGroundControl.videoManager.decoding + anchors.centerIn : undefined + anchors.verticalCenter: parent.verticalCenter + anchors.left : parent.left + + function undefinePosition() { + anchors.centerIn = undefined + anchors.horizontalCenter = undefined + anchors.top = undefined + anchors.bottom = undefined + anchors.verticalCenter = undefined + anchors.left = undefined + anchors.right = undefined } - Connections { - target: _camera - function onThermalModeChanged() { thermalItem.pipOrNot() } + + function leftPosition() { + undefinePosition() + + anchors.verticalCenter = parent.verticalCenter + anchors.left = parent.left } - onVisibleChanged: { - thermalItem.pipOrNot() + + function rightPosition() { + undefinePosition() + anchors.verticalCenter = parent.verticalCenter + anchors.right = parent.right + } + + function topPosition() { + undefinePosition() + anchors.horizontalCenter = parent.horizontalCenter + anchors.top = parent.top } + + function bottomPosition() { + undefinePosition() + anchors.horizontalCenter = parent.horizontalCenter + anchors.bottom = parent.bottom + } + QGCVideoBackground { - id: thermalVideo - objectName: "thermalVideo" + id: backupVideo + objectName: "backupVideo" anchors.fill: parent - opacity: _camera ? (_camera.thermalMode === MavlinkCameraControl.THERMAL_BLEND ? _camera.thermalOpacity / 100 : 1.0) : 0 + opacity: 1.0 + } + + ToolTip { + delay: 1000 + timeout: 3000 + visible: parent.visible + anchors.centerIn: parent.centerIn + text: qsTr("Right-click to open control menu") + } + + MouseArea { + anchors.fill: parent + acceptedButtons: Qt.RightButton + onClicked: backupItemPositionMenu.popup() + } + + QGCMenu { + id: backupItemPositionMenu + + property bool hasAuxStream: QGroundControl.videoManager.hasAuxStream + property bool usesPrimaryStream: QGroundControl.videoManager.isPrimaryStream + + QGCMenuItem { + text: qsTr("Left") + onTriggered: backupItem.leftPosition() + } + + QGCMenuItem { + text: qsTr("Right") + onTriggered: backupItem.rightPosition() + } + + QGCMenuItem { + text: qsTr("Top") + onTriggered: backupItem.topPosition() + } + + QGCMenuItem { + text: qsTr("Bottom") + onTriggered: backupItem.bottomPosition() + } + + QGCMenuSeparator { + visible: true // should be visible when backup stream is configured + } + + QGCMenuItem { + id: switchStreamMenuItem + text: qsTr("Switch video streams") + visible: true + enabled: false + onTriggered: QGroundControl.videoManager.isPrimaryStream = !QGroundControl.videoManager.isPrimaryStream + } + + onHasAuxStreamChanged: { + switchStreamMenuItem.enabled = hasAuxStream + } + + onUsesPrimaryStreamChanged: { + if (usesPrimaryStream) { + switchStreamMenuItem.text = qsTr("Switch to auxiliary video stream") + } else { + switchStreamMenuItem.text = qsTr("Switch to primary video stream") + } + } } } //-- Zoom diff --git a/src/Settings/Video.SettingsGroup.json b/src/Settings/Video.SettingsGroup.json index aff4a24c8ac1..258cc492fe80 100644 --- a/src/Settings/Video.SettingsGroup.json +++ b/src/Settings/Video.SettingsGroup.json @@ -24,6 +24,34 @@ "type": "string", "default": "" }, +{ + "name": "rtspUrlBackup", + "shortDesc": "Backup Video RTSP Url", + "longDesc": "Backup RTSP url address and port to bind to for video stream. Example: rtsp://192.168.42.1:554/live", + "type": "string", + "default": "" +}, +{ + "name": "rtspUseAux", + "shortDesc": "Enable auxiliary video streams", + "longDesc": "Enable auxiliary RTSP video streams and add possibility to switch between primary and aux ones", + "type": "bool", + "default": false +}, +{ + "name": "rtspUrlAux", + "shortDesc": "Video RTSP Url Aux", + "longDesc": "Additional RTSP url address and port to bind to for video stream. Example: rtsp://192.168.42.1:554/live", + "type": "string", + "default": "" +}, +{ + "name": "rtspUrlBackupAux", + "shortDesc": "Backup Video RTSP Url Aux", + "longDesc": "Additional backup RTSP url address and port to bind to for video stream. Example: rtsp://192.168.42.1:554/live", + "type": "string", + "default": "" +}, { "name": "tcpUrl", "shortDesc": "Video TCP Url", diff --git a/src/Settings/VideoSettings.cc b/src/Settings/VideoSettings.cc index 084afafa4a64..3a31e2880736 100644 --- a/src/Settings/VideoSettings.cc +++ b/src/Settings/VideoSettings.cc @@ -175,6 +175,38 @@ DECLARE_SETTINGSFACT_NO_FUNC(VideoSettings, rtspUrl) return _rtspUrlFact; } +DECLARE_SETTINGSFACT_NO_FUNC(VideoSettings, rtspUrlBackup) { + if (!_rtspUrlBackupFact) { + _rtspUrlBackupFact = _createSettingsFact(rtspUrlBackupName); + connect(_rtspUrlBackupFact, &Fact::valueChanged, this, &VideoSettings::_configChanged); + } + return _rtspUrlBackupFact; +} + +DECLARE_SETTINGSFACT_NO_FUNC(VideoSettings, rtspUseAux) { + if (!_rtspUseAuxFact) { + _rtspUseAuxFact = _createSettingsFact(rtspUseAuxName); + connect(_rtspUseAuxFact, &Fact::valueChanged, this, &VideoSettings::_auxConfigChanged); + } + return _rtspUseAuxFact; +} + +DECLARE_SETTINGSFACT_NO_FUNC(VideoSettings, rtspUrlAux) { + if (!_rtspUrlAuxFact) { + _rtspUrlAuxFact = _createSettingsFact(rtspUrlAuxName); + connect(_rtspUrlAuxFact, &Fact::valueChanged, this, &VideoSettings::_auxConfigChanged); + } + return _rtspUrlAuxFact; +} + +DECLARE_SETTINGSFACT_NO_FUNC(VideoSettings, rtspUrlBackupAux) { + if (!_rtspUrlBackupAuxFact) { + _rtspUrlBackupAuxFact = _createSettingsFact(rtspUrlBackupAuxName); + connect(_rtspUrlBackupAuxFact, &Fact::valueChanged, this, &VideoSettings::_auxConfigChanged); + } + return _rtspUrlBackupAuxFact; +} + DECLARE_SETTINGSFACT_NO_FUNC(VideoSettings, tcpUrl) { if (!_tcpUrlFact) { @@ -199,22 +231,22 @@ bool VideoSettings::streamConfigured(void) //-- If UDP, check for URL if(vSource == videoSourceUDPH264 || vSource == videoSourceUDPH265) { qCDebug(VideoManagerLog) << "Testing configuration for UDP Stream:" << udpUrl()->rawValue().toString(); - return !udpUrl()->rawValue().toString().isEmpty(); + return _isConfigured(udpUrl()); } //-- If RTSP, check for URL if(vSource == videoSourceRTSP) { qCDebug(VideoManagerLog) << "Testing configuration for RTSP Stream:" << rtspUrl()->rawValue().toString(); - return !rtspUrl()->rawValue().toString().isEmpty(); + return _isConfigured(rtspUrl()); } //-- If TCP, check for URL if(vSource == videoSourceTCP) { qCDebug(VideoManagerLog) << "Testing configuration for TCP Stream:" << tcpUrl()->rawValue().toString(); - return !tcpUrl()->rawValue().toString().isEmpty(); + return _isConfigured(tcpUrl()); } //-- If MPEG-TS, check for URL if(vSource == videoSourceMPEGTS) { qCDebug(VideoManagerLog) << "Testing configuration for MPEG-TS Stream:" << udpUrl()->rawValue().toString(); - return !udpUrl()->rawValue().toString().isEmpty(); + return _isConfigured(udpUrl()); } //-- If Herelink Air unit, good to go if(vSource == videoSourceHerelinkAirUnit) { @@ -235,11 +267,32 @@ bool VideoSettings::streamConfigured(void) return false; } +bool VideoSettings::auxStreamConfigured() +{ + QString vSource = videoSource()->rawValue().toString(); + if(vSource != videoSourceRTSP || !rtspUseAux()->rawValue().toBool()) { + return false; + } + + const bool primaryConfigured = _isConfigured(rtspUrl()); + const bool backupConfigured = _isConfigured(rtspUrlBackup()); + + const bool auxConfigured = primaryConfigured ? _isConfigured(rtspUrlAux()) : false; + const bool auxBackupConfigured = backupConfigured ? _isConfigured(rtspUrlBackupAux()) : false; + + return auxConfigured || auxBackupConfigured; +} + void VideoSettings::_configChanged(QVariant) { emit streamConfiguredChanged(streamConfigured()); } +void VideoSettings::_auxConfigChanged(QVariant) +{ + emit auxStreamConfiguredChanged(auxStreamConfigured()); +} + void VideoSettings::_setForceVideoDecodeList() { #ifdef QGC_GST_STREAMING @@ -272,3 +325,11 @@ void VideoSettings::_setForceVideoDecodeList() } #endif } + +bool VideoSettings::_isConfigured(const Fact* parameter) +{ + if (!parameter) + return false; + + return !parameter->rawValue().toString().isEmpty(); +} diff --git a/src/Settings/VideoSettings.h b/src/Settings/VideoSettings.h index 8c0ad3a081bb..43ee7c161885 100644 --- a/src/Settings/VideoSettings.h +++ b/src/Settings/VideoSettings.h @@ -26,6 +26,10 @@ class VideoSettings : public SettingsGroup DEFINE_SETTINGFACT(udpUrl) DEFINE_SETTINGFACT(tcpUrl) DEFINE_SETTINGFACT(rtspUrl) + DEFINE_SETTINGFACT(rtspUrlBackup) + DEFINE_SETTINGFACT(rtspUseAux) + DEFINE_SETTINGFACT(rtspUrlAux) + DEFINE_SETTINGFACT(rtspUrlBackupAux) DEFINE_SETTINGFACT(aspectRatio) DEFINE_SETTINGFACT(videoFit) DEFINE_SETTINGFACT(gridLines) @@ -48,6 +52,7 @@ class VideoSettings : public SettingsGroup Q_PROPERTY(QString disabledVideoSource READ disabledVideoSource CONSTANT) bool streamConfigured (); + bool auxStreamConfigured (); QString rtspVideoSource () { return videoSourceRTSP; } QString udp264VideoSource () { return videoSourceUDPH264; } QString udp265VideoSource () { return videoSourceUDPH265; } @@ -69,14 +74,17 @@ class VideoSettings : public SettingsGroup static constexpr const char* videoSourceHerelinkHotspot = QT_TRANSLATE_NOOP("VideoSettings", "Herelink Hotspot"); signals: - void streamConfiguredChanged (bool configured); + void streamConfiguredChanged(bool configured); + void auxStreamConfiguredChanged(bool configured); private slots: - void _configChanged (QVariant value); + void _configChanged(QVariant value); + void _auxConfigChanged(QVariant value); private: void _setDefaults (); void _setForceVideoDecodeList(); + static bool _isConfigured(const Fact* parameter); private: bool _noVideo = false; diff --git a/src/UI/AppSettings/VideoSettings.qml b/src/UI/AppSettings/VideoSettings.qml index cf8f8843ce7a..4147ab0bfe71 100644 --- a/src/UI/AppSettings/VideoSettings.qml +++ b/src/UI/AppSettings/VideoSettings.qml @@ -63,6 +63,38 @@ SettingsPage { visible: _isRTSP && _videoSettings.rtspUrl.visible } + LabelledFactTextField { + Layout.fillWidth: true + textFieldPreferredWidth: _urlFieldWidth + label: qsTr("RTSP URL Backup") + fact: _videoSettings.rtspUrlBackup + visible: _isRTSP && _videoSettings.rtspUrlBackup.visible + } + + FactCheckBoxSlider { + id: auxStreamCheckBox + Layout.fillWidth: true + text: fact.shortDescription + fact: _videoSettings.rtspUseAux + visible: fact.visible + } + + LabelledFactTextField { + Layout.fillWidth: true + textFieldPreferredWidth: _urlFieldWidth + label: qsTr("Aux RTSP URL") + fact: _videoSettings.rtspUrlAux + visible: _isRTSP && _videoSettings.rtspUrlAux.visible && auxStreamCheckBox.checked + } + + LabelledFactTextField { + Layout.fillWidth: true + textFieldPreferredWidth: _urlFieldWidth + label: qsTr("Aux RTSP URL Backup") + fact: _videoSettings.rtspUrlBackupAux + visible: _isRTSP && _videoSettings.rtspUrlBackupAux.visible && auxStreamCheckBox.checked + } + LabelledFactTextField { Layout.fillWidth: true label: qsTr("TCP URL") diff --git a/src/VideoManager/VideoManager.cc b/src/VideoManager/VideoManager.cc index 4648b198e906..0102d42e7fac 100644 --- a/src/VideoManager/VideoManager.cc +++ b/src/VideoManager/VideoManager.cc @@ -90,12 +90,20 @@ void VideoManager::init(QQuickWindow *mainWindow) (void) connect(_videoSettings->videoSource(), &Fact::rawValueChanged, this, &VideoManager::_videoSourceChanged); (void) connect(_videoSettings->udpUrl(), &Fact::rawValueChanged, this, &VideoManager::_videoSourceChanged); (void) connect(_videoSettings->rtspUrl(), &Fact::rawValueChanged, this, &VideoManager::_videoSourceChanged); + (void) connect(_videoSettings->rtspUrlBackup(), &Fact::rawValueChanged, this, &VideoManager::_videoSourceChanged); + (void) connect(_videoSettings->rtspUrlAux(), &Fact::rawValueChanged, this, &VideoManager::_videoSourceChanged); + (void) connect(_videoSettings->rtspUrlBackupAux(), &Fact::rawValueChanged, this, &VideoManager::_videoSourceChanged); (void) connect(_videoSettings->tcpUrl(), &Fact::rawValueChanged, this, &VideoManager::_videoSourceChanged); (void) connect(_videoSettings->aspectRatio(), &Fact::rawValueChanged, this, &VideoManager::aspectRatioChanged); (void) connect(_videoSettings->lowLatencyMode(), &Fact::rawValueChanged, this, [this](const QVariant &value) { Q_UNUSED(value); _restartAllVideos(); }); + (void) connect(_videoSettings, &VideoSettings::auxStreamConfiguredChanged, this, &VideoManager::_enableAuxStream); (void) connect(MultiVehicleManager::instance(), &MultiVehicleManager::activeVehicleChanged, this, &VideoManager::_setActiveVehicle); (void) connect(this, &VideoManager::autoStreamConfiguredChanged, this, &VideoManager::_videoSourceChanged); + (void) connect(this, &VideoManager::videoStreamChanged, this, &VideoManager::_videoSourceChanged); + + // force aux stream enable/disable recognition on init + _enableAuxStream(_videoSettings->auxStreamConfigured()); _mainWindow->scheduleRenderJob(new FinishVideoInitialization(), QQuickWindow::BeforeSynchronizingStage); @@ -118,7 +126,7 @@ void VideoManager::_initAfterQmlIsReady() static const QStringList videoStreamList = { "videoContent", - "thermalVideo" + "backupVideo" }; for (const QString &streamName : videoStreamList) { VideoReceiver *receiver = QGCCorePlugin::instance()->createVideoReceiver(this); @@ -175,6 +183,16 @@ void VideoManager::_cleanupOldVideos() } } +QString VideoManager::_getRtspUrlForReceiver(VideoReceiver *receiver) const +{ + const Fact *fact = nullptr; + if (receiver->isPrimary()) + fact = _usesPrimaryVideoStream ? _videoSettings->rtspUrl() : _videoSettings->rtspUrlAux(); + else + fact = _usesPrimaryVideoStream ? _videoSettings->rtspUrlBackup() : _videoSettings->rtspUrlBackupAux(); + return fact->rawValue().toString(); +} + void VideoManager::startRecording(const QString &videoFile) { const VideoReceiver::FILE_FORMAT fileFormat = static_cast(_videoSettings->recordingFormat()->rawValue().toInt()); @@ -280,6 +298,27 @@ double VideoManager::thermalHfov() const return _videoSettings->aspectRatio()->rawValue().toDouble(); } +bool VideoManager::isPrimaryStream() const +{ + return _usesPrimaryVideoStream; +} + +bool VideoManager::hasAuxStream() const +{ + return _hasAuxStreamConfigured; +} + +bool VideoManager::hasBackup() const { + for (VideoReceiver *receiver : _videoReceivers) { + QGCVideoStreamInfo *pInfo = receiver->videoStreamInfo(); + if (receiver->isBackup() && pInfo && !pInfo->uri().isEmpty()) { + return true; + } + } + + return false; +} + bool VideoManager::hasThermal() const { for (VideoReceiver *receiver : _videoReceivers) { @@ -335,6 +374,17 @@ void VideoManager::setfullScreen(bool on) } } +void VideoManager::setStream(bool primary) +{ + if (!primary && !_hasAuxStreamConfigured) + return; + + if (primary != _usesPrimaryVideoStream) { + _usesPrimaryVideoStream = primary; + emit videoStreamChanged(); + } +} + bool VideoManager::isStreamSource() const { static const QStringList videoSourceList = { @@ -391,6 +441,18 @@ void VideoManager::_videoSourceChanged() } } +void VideoManager::_enableAuxStream(bool enable) +{ + if (enable != _hasAuxStreamConfigured) { + _hasAuxStreamConfigured = enable; + emit hasAuxStreamChanged(); + + if (!enable && !_usesPrimaryVideoStream) { + setStream(true); + } + } +} + bool VideoManager::_updateUVC(VideoReceiver *receiver) { bool result = false; @@ -442,8 +504,12 @@ bool VideoManager::_updateAutoStream(VideoReceiver *receiver) case VIDEO_STREAM_TYPE_RTSP: source = VideoSettings::videoSourceRTSP; url = pInfo->uri(); - if (source == VideoSettings::videoSourceRTSP) { - _videoSettings->rtspUrl()->setRawValue(url); + if (receiver->isPrimary()) { + _usesPrimaryVideoStream ? _videoSettings->rtspUrl()->setRawValue(url) + : _videoSettings->rtspUrlAux()->setRawValue(url); + } else if (receiver->isBackup()) { + _usesPrimaryVideoStream ? _videoSettings->rtspUrlBackup()->setRawValue(url) + : _videoSettings->rtspUrlBackupAux()->setRawValue(url); } break; case VIDEO_STREAM_TYPE_TCP_MPEG: @@ -530,7 +596,7 @@ bool VideoManager::_updateSettings(VideoReceiver *receiver) } else if (source == VideoSettings::videoSourceMPEGTS) { settingsChanged |= _updateVideoUri(receiver, QStringLiteral("mpegts://%1").arg(_videoSettings->udpUrl()->rawValue().toString())); } else if (source == VideoSettings::videoSourceRTSP) { - settingsChanged |= _updateVideoUri(receiver, _videoSettings->rtspUrl()->rawValue().toString()); + settingsChanged |= _updateVideoUri(receiver, _getRtspUrlForReceiver(receiver)); } else if (source == VideoSettings::videoSourceTCP) { settingsChanged |= _updateVideoUri(receiver, QStringLiteral("tcp://%1").arg(_videoSettings->tcpUrl()->rawValue().toString())); } else if (source == VideoSettings::videoSource3DRSolo) { @@ -735,7 +801,7 @@ void VideoManager::_initVideoReceiver(VideoReceiver *receiver, QQuickWindow *win (void) connect(receiver, &VideoReceiver::streamingChanged, this, [this, receiver](bool active) { qCDebug(VideoManagerLog) << "Video" << receiver->name() << "streaming changed, active:" << (active ? "yes" : "no"); - if (!receiver->isThermal()) { + if (receiver->isPrimary()) { _streaming = active; emit streamingChanged(); } @@ -743,7 +809,7 @@ void VideoManager::_initVideoReceiver(VideoReceiver *receiver, QQuickWindow *win (void) connect(receiver, &VideoReceiver::decodingChanged, this, [this, receiver](bool active) { qCDebug(VideoManagerLog) << "Video" << receiver->name() << "decoding changed, active:" << (active ? "yes" : "no"); - if (!receiver->isThermal()) { + if (receiver->isPrimary()) { _decoding = active; emit decodingChanged(); } @@ -751,7 +817,7 @@ void VideoManager::_initVideoReceiver(VideoReceiver *receiver, QQuickWindow *win (void) connect(receiver, &VideoReceiver::recordingChanged, this, [this, receiver](bool active) { qCDebug(VideoManagerLog) << "Video" << receiver->name() << "recording changed, active:" << (active ? "yes" : "no"); - if (!receiver->isThermal()) { + if (receiver->isPrimary()) { _recording = active; if (!active) { _subtitleWriter->stopCapturingTelemetry(); @@ -762,14 +828,14 @@ void VideoManager::_initVideoReceiver(VideoReceiver *receiver, QQuickWindow *win (void) connect(receiver, &VideoReceiver::recordingStarted, this, [this, receiver](const QString &filename) { qCDebug(VideoManagerLog) << "Video" << receiver->name() << "recording started"; - if (!receiver->isThermal()) { + if (receiver->isPrimary()) { _subtitleWriter->startCapturingTelemetry(filename, videoSize()); } }); (void) connect(receiver, &VideoReceiver::videoSizeChanged, this, [this, receiver](QSize size) { qCDebug(VideoManagerLog) << "Video" << receiver->name() << "resized. New resolution:" << size.width() << "x" << size.height(); - if (!receiver->isThermal()) { + if (receiver->isPrimary()) { _videoSize = size; emit videoSizeChanged(); } diff --git a/src/VideoManager/VideoManager.h b/src/VideoManager/VideoManager.h index cb1e173e560c..018c3d33a6e9 100644 --- a/src/VideoManager/VideoManager.h +++ b/src/VideoManager/VideoManager.h @@ -37,6 +37,9 @@ class VideoManager : public QObject Q_PROPERTY(bool autoStreamConfigured READ autoStreamConfigured NOTIFY autoStreamConfiguredChanged) Q_PROPERTY(bool decoding READ decoding NOTIFY decodingChanged) Q_PROPERTY(bool fullScreen READ fullScreen WRITE setfullScreen NOTIFY fullScreenChanged) + Q_PROPERTY(bool hasBackup READ hasBackup NOTIFY hasVideoChanged) + Q_PROPERTY(bool isPrimaryStream READ isPrimaryStream WRITE setStream NOTIFY videoStreamChanged) + Q_PROPERTY(bool hasAuxStream READ hasAuxStream NOTIFY hasAuxStreamChanged) Q_PROPERTY(bool hasThermal READ hasThermal NOTIFY decodingChanged) Q_PROPERTY(bool hasVideo READ hasVideo NOTIFY hasVideoChanged) Q_PROPERTY(bool isStreamSource READ isStreamSource NOTIFY isStreamSourceChanged) @@ -70,6 +73,9 @@ class VideoManager : public QObject bool autoStreamConfigured() const; bool decoding() const { return _decoding; } bool fullScreen() const { return _fullScreen; } + bool isPrimaryStream() const; + bool hasAuxStream() const; + bool hasBackup() const; bool hasThermal() const; bool hasVideo() const; bool isStreamSource() const; @@ -84,6 +90,7 @@ class VideoManager : public QObject QString imageFile() const { return _imageFile; } QString uvcVideoSourceID() const { return _uvcVideoSourceID; } void setfullScreen(bool on); + void setStream(bool primary); static bool gstreamerEnabled(); static bool qtmultimediaEnabled(); static bool uvcEnabled(); @@ -103,11 +110,14 @@ class VideoManager : public QObject void streamingChanged(); void uvcVideoSourceIDChanged(); void videoSizeChanged(); + void videoStreamChanged(); + void hasAuxStreamChanged(); private slots: void _communicationLostChanged(bool communicationLost); void _setActiveVehicle(Vehicle *vehicle); void _videoSourceChanged(); + void _enableAuxStream(bool enable); private: void _initAfterQmlIsReady(); @@ -121,6 +131,7 @@ private slots: void _startReceiver(VideoReceiver *receiver); void _stopReceiver(VideoReceiver *receiver); static void _cleanupOldVideos(); + QString _getRtspUrlForReceiver(VideoReceiver *receiver) const; QList _videoReceivers; @@ -130,6 +141,8 @@ private slots: bool _initialized = false; bool _initAfterQmlIsReadyDone = false; bool _fullScreen = false; + bool _usesPrimaryVideoStream = true; + bool _hasAuxStreamConfigured = false; QAtomicInteger _decoding = false; QAtomicInteger _recording = false; QAtomicInteger _streaming = false; diff --git a/src/VideoManager/VideoReceiver/VideoReceiver.h b/src/VideoManager/VideoReceiver/VideoReceiver.h index a55c1f02fb69..c855f4db2d4a 100644 --- a/src/VideoManager/VideoReceiver/VideoReceiver.h +++ b/src/VideoManager/VideoReceiver/VideoReceiver.h @@ -27,6 +27,8 @@ class VideoReceiver : public QObject : QObject(parent) {} + bool isPrimary() const { return (_name == QStringLiteral("videoContent")); } + bool isBackup() const { return (_name == QStringLiteral("backupVideo")); } bool isThermal() const { return (_name == QStringLiteral("thermalVideo")); } void *sink() { return _sink; } From cdd812d1c688611a58a1fa9b9585965553f64514 Mon Sep 17 00:00:00 2001 From: Vitalii Dovgan Date: Thu, 4 Dec 2025 17:04:00 +0200 Subject: [PATCH 2/2] remove the trailing spaces --- src/FlightDisplay/FlightDisplayViewVideo.qml | 8 ++++---- 1 file changed, 4 insertions(+), 4 deletions(-) diff --git a/src/FlightDisplay/FlightDisplayViewVideo.qml b/src/FlightDisplay/FlightDisplayViewVideo.qml index d19b4490707b..0f397145c673 100644 --- a/src/FlightDisplay/FlightDisplayViewVideo.qml +++ b/src/FlightDisplay/FlightDisplayViewVideo.qml @@ -85,7 +85,7 @@ Item { visible: QGroundControl.videoManager.decoding function getWidth() { if(_ar != 0.0){ - if(_isMode_FIT_HEIGHT + if(_isMode_FIT_HEIGHT || (_isMode_FILL && (root.width/root.height < _ar)) || (_isMode_NO_CROP && (root.width/root.height > _ar))){ // This return value has different implications depending on the mode @@ -100,8 +100,8 @@ Item { } function getHeight() { if(_ar != 0.0){ - if(_isMode_FIT_WIDTH - || (_isMode_FILL && (root.width/root.height > _ar)) + if(_isMode_FIT_WIDTH + || (_isMode_FILL && (root.width/root.height > _ar)) || (_isMode_NO_CROP && (root.width/root.height < _ar))){ // This return value has different implications depending on the mode // For FIT_WIDTH and FILL @@ -287,7 +287,7 @@ Item { } else { switchStreamMenuItem.text = qsTr("Switch to primary video stream") } - } + } } } //-- Zoom