From 73a4581c258793b6119d3bda348cd3bdbbc9d0a6 Mon Sep 17 00:00:00 2001 From: Holden Date: Mon, 7 Oct 2024 23:21:07 -0400 Subject: [PATCH] VideoManager: Convert to Singleton --- src/Camera/SimulatedCameraControl.cc | 13 +- src/Camera/SimulatedCameraControl.h | 4 +- src/Camera/VehicleCameraControl.cc | 14 +- src/QGCApplication.cc | 8 +- src/QGCToolbox.cc | 3 - src/QGCToolbox.h | 3 - src/QmlControls/QGroundControlQmlGlobal.cc | 4 +- src/QmlControls/QGroundControlQmlGlobal.h | 2 +- src/Settings/VideoSettings.cc | 2 +- src/Vehicle/Vehicle.cc | 2 +- src/VideoManager/VideoManager.cc | 892 ++++++++++----------- src/VideoManager/VideoManager.h | 228 +++--- 12 files changed, 548 insertions(+), 627 deletions(-) diff --git a/src/Camera/SimulatedCameraControl.cc b/src/Camera/SimulatedCameraControl.cc index 4cb739820e1..2f41a9ea42d 100644 --- a/src/Camera/SimulatedCameraControl.cc +++ b/src/Camera/SimulatedCameraControl.cc @@ -19,11 +19,10 @@ SimulatedCameraControl::SimulatedCameraControl(Vehicle* vehicle, QObject* parent) : MavlinkCameraControl (parent) , _vehicle (vehicle) - , _videoManager (qgcApp()->toolbox()->videoManager()) { QQmlEngine::setObjectOwnership(this, QQmlEngine::CppOwnership); - connect(_videoManager, &VideoManager::recordingChanged, this, &SimulatedCameraControl::videoCaptureStatusChanged); + connect(VideoManager::instance(), &VideoManager::recordingChanged, this, &SimulatedCameraControl::videoCaptureStatusChanged); auto flyViewSettings = qgcApp()->toolbox()->settingsManager()->flyViewSettings(); connect(flyViewSettings->showSimpleCameraControl(), &Fact::rawValueChanged, this, &SimulatedCameraControl::infoChanged); @@ -44,7 +43,7 @@ QString SimulatedCameraControl::recordTimeStr() SimulatedCameraControl::VideoCaptureStatus SimulatedCameraControl::videoCaptureStatus() { - return _videoCaptureStatus = _videoManager->recording() ? VIDEO_CAPTURE_STATUS_RUNNING : VIDEO_CAPTURE_STATUS_STOPPED; + return _videoCaptureStatus = VideoManager::instance()->recording() ? VIDEO_CAPTURE_STATUS_RUNNING : VIDEO_CAPTURE_STATUS_STOPPED; } void SimulatedCameraControl::setCameraMode(CameraMode mode) @@ -163,7 +162,7 @@ bool SimulatedCameraControl::startVideoRecording() _videoRecordTimeUpdateTimer.start(); _videoRecordTimeElapsedTimer.start(); - _videoManager->startRecording(); + VideoManager::instance()->startRecording(); return false; } @@ -177,7 +176,7 @@ bool SimulatedCameraControl::stopVideoRecording() } _videoRecordTimeUpdateTimer.stop(); - _videoManager->stopRecording(); + VideoManager::instance()->stopRecording(); return true; } @@ -192,7 +191,7 @@ quint32 SimulatedCameraControl::recordTime() bool SimulatedCameraControl::capturesVideo() { - return _videoManager->hasVideo(); + return VideoManager::instance()->hasVideo(); } void SimulatedCameraControl::setPhotoLapse(double) @@ -207,7 +206,7 @@ bool SimulatedCameraControl::capturesPhotos() bool SimulatedCameraControl::hasVideoStream() { - return _videoManager->hasVideo(); + return VideoManager::instance()->hasVideo(); } void SimulatedCameraControl::setPhotoLapseCount(int) diff --git a/src/Camera/SimulatedCameraControl.h b/src/Camera/SimulatedCameraControl.h index 3611a4f5981..c0da8f939a2 100644 --- a/src/Camera/SimulatedCameraControl.h +++ b/src/Camera/SimulatedCameraControl.h @@ -14,7 +14,6 @@ #include #include -class VideoManager; class Vehicle; /// Creates a simulated Camera Control which supports: @@ -141,7 +140,6 @@ protected slots: PhotoCaptureMode _photoCaptureMode = PHOTO_CAPTURE_SINGLE; qreal _photoLapse = 1.0; int _photoLapseCount = 0; - VideoManager* _videoManager = nullptr; QTimer _videoRecordTimeUpdateTimer; QElapsedTimer _videoRecordTimeElapsedTimer; -}; \ No newline at end of file +}; diff --git a/src/Camera/VehicleCameraControl.cc b/src/Camera/VehicleCameraControl.cc index e83e06ade72..9b617019467 100644 --- a/src/Camera/VehicleCameraControl.cc +++ b/src/Camera/VehicleCameraControl.cc @@ -360,9 +360,7 @@ VehicleCameraControl::takePhoto() _setPhotoStatus(PHOTO_CAPTURE_IN_PROGRESS); _captureInfoRetries = 0; //-- Capture local image as well - if(qgcApp()->toolbox()->videoManager()) { - qgcApp()->toolbox()->videoManager()->grabImage(); - } + VideoManager::instance()->grabImage(); return true; } } @@ -1563,12 +1561,10 @@ VehicleCameraControl::handleCaptureStatus(const mavlink_camera_capture_status_t& //-- Time Lapse if(photoCaptureStatus() == PHOTO_CAPTURE_INTERVAL_IDLE || photoCaptureStatus() == PHOTO_CAPTURE_INTERVAL_IN_PROGRESS) { //-- Capture local image as well - if(qgcApp()->toolbox()->videoManager()) { - QString photoPath = qgcApp()->toolbox()->settingsManager()->appSettings()->savePath()->rawValue().toString() + QStringLiteral("/Photo"); - QDir().mkpath(photoPath); - photoPath += + "/" + QDateTime::currentDateTime().toString("yyyy-MM-dd_hh.mm.ss.zzz") + ".jpg"; - qgcApp()->toolbox()->videoManager()->grabImage(photoPath); - } + QString photoPath = qgcApp()->toolbox()->settingsManager()->appSettings()->savePath()->rawValue().toString() + QStringLiteral("/Photo"); + QDir().mkpath(photoPath); + photoPath += + "/" + QDateTime::currentDateTime().toString("yyyy-MM-dd_hh.mm.ss.zzz") + ".jpg"; + VideoManager::instance()->grabImage(photoPath); } } diff --git a/src/QGCApplication.cc b/src/QGCApplication.cc index f117c0c767b..8be96a39137 100644 --- a/src/QGCApplication.cc +++ b/src/QGCApplication.cc @@ -316,6 +316,8 @@ void QGCApplication::_initForNormalAppBoot() QQuickWindow::setGraphicsApi(QSGRendererInterface::OpenGL); #endif + VideoManager::instance(); // GStreamer must be initialized before QmlEngine + QQuickStyle::setStyle("Basic"); _qmlAppEngine = _toolbox->corePlugin()->createQmlApplicationEngine(this); QObject::connect(_qmlAppEngine, &QQmlApplicationEngine::objectCreationFailed, this, QCoreApplication::quit, Qt::QueuedConnection); @@ -328,11 +330,7 @@ void QGCApplication::_initForNormalAppBoot() // Image provider for Optical Flow _qmlAppEngine->addImageProvider(qgcImageProviderId, new QGCImageProvider()); - QQuickWindow* rootWindow = mainRootWindow(); - if (rootWindow) { - rootWindow->scheduleRenderJob(new FinishVideoInitialization(_toolbox->videoManager()), - QQuickWindow::BeforeSynchronizingStage); - } + VideoManager::instance()->init(); // Safe to show popup error messages now that main window is created _showErrorsInToolbar = true; diff --git a/src/QGCToolbox.cc b/src/QGCToolbox.cc index dbb2ea7f972..0f7338c5338 100644 --- a/src/QGCToolbox.cc +++ b/src/QGCToolbox.cc @@ -11,7 +11,6 @@ #include "LinkManager.h" #include "MAVLinkProtocol.h" #include "MultiVehicleManager.h" -#include "VideoManager.h" #include "QGCCorePlugin.h" #include "SettingsManager.h" #include "QGCApplication.h" @@ -31,7 +30,6 @@ QGCToolbox::QGCToolbox(QGCApplication* app) _linkManager = new LinkManager (app, this); _mavlinkProtocol = new MAVLinkProtocol (app, this); _multiVehicleManager = new MultiVehicleManager (app, this); - _videoManager = new VideoManager (app, this); } void QGCToolbox::setChildToolboxes(void) @@ -43,7 +41,6 @@ void QGCToolbox::setChildToolboxes(void) _linkManager->setToolbox(this); _mavlinkProtocol->setToolbox(this); _multiVehicleManager->setToolbox(this); - _videoManager->setToolbox(this); } void QGCToolbox::_scanAndLoadPlugins(QGCApplication* app) diff --git a/src/QGCToolbox.h b/src/QGCToolbox.h index fbbc8364315..5327a7491e8 100644 --- a/src/QGCToolbox.h +++ b/src/QGCToolbox.h @@ -17,7 +17,6 @@ class LinkManager; class MAVLinkProtocol; class MultiVehicleManager; class QGCApplication; -class VideoManager; class QGCCorePlugin; class SettingsManager; @@ -31,7 +30,6 @@ class QGCToolbox : public QObject { LinkManager* linkManager () { return _linkManager; } MAVLinkProtocol* mavlinkProtocol () { return _mavlinkProtocol; } MultiVehicleManager* multiVehicleManager () { return _multiVehicleManager; } - VideoManager* videoManager () { return _videoManager; } QGCCorePlugin* corePlugin () { return _corePlugin; } SettingsManager* settingsManager () { return _settingsManager; } @@ -42,7 +40,6 @@ class QGCToolbox : public QObject { LinkManager* _linkManager = nullptr; MAVLinkProtocol* _mavlinkProtocol = nullptr; MultiVehicleManager* _multiVehicleManager = nullptr; - VideoManager* _videoManager = nullptr; QGCCorePlugin* _corePlugin = nullptr; SettingsManager* _settingsManager = nullptr; friend class QGCApplication; diff --git a/src/QmlControls/QGroundControlQmlGlobal.cc b/src/QmlControls/QGroundControlQmlGlobal.cc index 17b66a6f921..0000167b4da 100644 --- a/src/QmlControls/QGroundControlQmlGlobal.cc +++ b/src/QmlControls/QGroundControlQmlGlobal.cc @@ -40,7 +40,7 @@ #include "TerrainProfile.h" #include "ToolStripAction.h" #include "ToolStripActionList.h" - +#include "VideoManager.h" #ifndef NO_SERIAL_LINK #include "GPSManager.h" #include "GPSRtk.h" @@ -111,6 +111,7 @@ QGroundControlQmlGlobal::QGroundControlQmlGlobal(QGCApplication* app, QGCToolbox , _adsbVehicleManager(ADSBVehicleManager::instance()) , _qgcPositionManager(QGCPositionManager::instance()) , _missionCommandTree(MissionCommandTree::instance()) + , _videoManager(VideoManager::instance()) #ifndef QGC_AIRLINK_DISABLED , _airlinkManager(AirLinkManager::instance()) #endif @@ -159,7 +160,6 @@ void QGroundControlQmlGlobal::setToolbox(QGCToolbox* toolbox) _linkManager = toolbox->linkManager(); _multiVehicleManager = toolbox->multiVehicleManager(); - _videoManager = toolbox->videoManager(); _corePlugin = toolbox->corePlugin(); _settingsManager = toolbox->settingsManager(); #ifndef NO_SERIAL_LINK diff --git a/src/QmlControls/QGroundControlQmlGlobal.h b/src/QmlControls/QGroundControlQmlGlobal.h index 3a1e5fe64b9..ecdcbde8c4f 100644 --- a/src/QmlControls/QGroundControlQmlGlobal.h +++ b/src/QmlControls/QGroundControlQmlGlobal.h @@ -256,6 +256,7 @@ class QGroundControlQmlGlobal : public QGCTool ADSBVehicleManager* _adsbVehicleManager = nullptr; QGCPositionManager* _qgcPositionManager = nullptr; MissionCommandTree* _missionCommandTree = nullptr; + VideoManager* _videoManager = nullptr; #ifndef QGC_AIRLINK_DISABLED AirLinkManager* _airlinkManager = nullptr; #endif @@ -266,7 +267,6 @@ class QGroundControlQmlGlobal : public QGCTool double _flightMapInitialZoom = 17.0; LinkManager* _linkManager = nullptr; MultiVehicleManager* _multiVehicleManager = nullptr; - VideoManager* _videoManager = nullptr; QGCCorePlugin* _corePlugin = nullptr; SettingsManager* _settingsManager = nullptr; #ifndef NO_SERIAL_LINK diff --git a/src/Settings/VideoSettings.cc b/src/Settings/VideoSettings.cc index 2d8931c6009..b5bafb77dbd 100644 --- a/src/Settings/VideoSettings.cc +++ b/src/Settings/VideoSettings.cc @@ -174,7 +174,7 @@ DECLARE_SETTINGSFACT_NO_FUNC(VideoSettings, tcpUrl) bool VideoSettings::streamConfigured(void) { //-- First, check if it's autoconfigured - if(qgcApp()->toolbox()->videoManager()->autoStreamConfigured()) { + if(VideoManager::instance()->autoStreamConfigured()) { qCDebug(VideoManagerLog) << "Stream auto configured"; return true; } diff --git a/src/Vehicle/Vehicle.cc b/src/Vehicle/Vehicle.cc index deb550e0e1c..875b97904f1 100644 --- a/src/Vehicle/Vehicle.cc +++ b/src/Vehicle/Vehicle.cc @@ -1113,7 +1113,7 @@ void Vehicle::_updateArmed(bool armed) // Also handle Video Streaming if(_settingsManager->videoSettings()->disableWhenDisarmed()->rawValue().toBool()) { _settingsManager->videoSettings()->streamEnabled()->setRawValue(false); - qgcApp()->toolbox()->videoManager()->stopVideo(); + VideoManager::instance()->stopVideo(); } } } diff --git a/src/VideoManager/VideoManager.cc b/src/VideoManager/VideoManager.cc index fbc9066eeef..21b7f4aef29 100644 --- a/src/VideoManager/VideoManager.cc +++ b/src/VideoManager/VideoManager.cc @@ -8,17 +8,17 @@ ****************************************************************************/ #include "VideoManager.h" +#include "MultiVehicleManager.h" #include "QGCApplication.h" -#include "QGCToolbox.h" +#include "QGCCameraManager.h" #include "QGCCorePlugin.h" -#include "MultiVehicleManager.h" +#include "QGCLoggingCategory.h" +#include "QGCToolbox.h" #include "SettingsManager.h" +#include "SubtitleWriter.h" #include "Vehicle.h" -#include "QGCCameraManager.h" -#include "QGCLoggingCategory.h" #include "VideoReceiver.h" #include "VideoSettings.h" -#include "SubtitleWriter.h" #ifdef QGC_GST_STREAMING #include "GStreamer.h" #else @@ -26,40 +26,53 @@ #endif #ifdef QGC_QT_STREAMING #include "QtMultimediaReceiver.h" +// #include "UVCReceiver.h" #endif #ifndef QGC_DISABLE_UVC -#include -#include #include +#include +#include #include #endif +#include #include #include #include QGC_LOGGING_CATEGORY(VideoManagerLog, "qgc.videomanager.videomanager") -static constexpr const char* kFileExtension[VideoReceiver::FILE_FORMAT_MAX - VideoReceiver::FILE_FORMAT_MIN] = { +static constexpr const char *kFileExtension[VideoReceiver::FILE_FORMAT_MAX - VideoReceiver::FILE_FORMAT_MIN] = { "mkv", "mov", "mp4" }; -//----------------------------------------------------------------------------- -VideoManager::VideoManager(QGCApplication* app, QGCToolbox* toolbox) - : QGCTool(app, toolbox) +Q_APPLICATION_STATIC(VideoManager, _videoManagerInstance); + +VideoManager::VideoManager(QObject *parent) + : QObject(parent) , _subtitleWriter(new SubtitleWriter(this)) + , _videoSettings(qgcApp()->toolbox()->settingsManager()->videoSettings()) { + // qCDebug(VideoManagerLog) << Q_FUNC_INFO << this; + + if (qgcApp()->runningUnitTests()) { + return; + } + + (void) qmlRegisterUncreatableType ("QGroundControl.VideoManager", 1, 0, "VideoManager", "Reference only"); + (void) qmlRegisterUncreatableType("QGroundControl", 1, 0, "VideoReceiver","Reference only"); + #ifdef QGC_GST_STREAMING GStreamer::initialize(); + GStreamer::blacklist(static_cast(_videoSettings->forceVideoDecoder()->rawValue().toInt())); #else - qmlRegisterType("org.freedesktop.gstreamer.Qt6GLVideoItem", 1, 0, "GstGLQt6VideoItem"); + (void) qmlRegisterType("org.freedesktop.gstreamer.Qt6GLVideoItem", 1, 0, "GstGLQt6VideoItem"); #endif } -//----------------------------------------------------------------------------- VideoManager::~VideoManager() { for (VideoReceiverData &videoReceiver : _videoReceiverData) { @@ -69,201 +82,141 @@ VideoManager::~VideoManager() } if (videoReceiver.sink != nullptr) { + // TODO: How to detect video backend type? #ifdef QGC_GST_STREAMING - // FIXME: AV: we need some interaface for video sink with .release() call - // Currently VideoManager is destroyed after corePlugin() and we are crashing on app exit - // calling _toolbox->corePlugin()->releaseVideoSink(_videoSink[i]); - // As for now let's call GStreamer::releaseVideoSink() directly - GStreamer::releaseVideoSink(videoReceiver.sink); + qgcApp()->toolbox()->corePlugin()->releaseVideoSink(videoReceiver.sink); #elif defined(QGC_QT_STREAMING) QtMultimediaReceiver::releaseVideoSink(videoReceiver.sink); #endif } } + + // qCDebug(VideoManagerLog) << Q_FUNC_INFO << this; } -//----------------------------------------------------------------------------- -void -VideoManager::setToolbox(QGCToolbox *toolbox) +VideoManager *VideoManager::instance() { - QGCTool::setToolbox(toolbox); - QQmlEngine::setObjectOwnership(this, QQmlEngine::CppOwnership); - qmlRegisterUncreatableType ("QGroundControl.VideoManager", 1, 0, "VideoManager", "Reference only"); - qmlRegisterUncreatableType("QGroundControl", 1, 0, "VideoReceiver","Reference only"); + return _videoManagerInstance(); +} - // TODO: Those connections should be Per Video, not per VideoManager. - _videoSettings = toolbox->settingsManager()->videoSettings(); - const QString videoSource = _videoSettings->videoSource()->rawValue().toString(); - qCDebug(VideoManagerLog) << "New Video Source:" << videoSource; - connect(_videoSettings->videoSource(), &Fact::rawValueChanged, this, &VideoManager::_videoSourceChanged); - connect(_videoSettings->udpPort(), &Fact::rawValueChanged, this, &VideoManager::_videoSourceChanged); - connect(_videoSettings->rtspUrl(), &Fact::rawValueChanged, this, &VideoManager::_videoSourceChanged); - connect(_videoSettings->tcpUrl(), &Fact::rawValueChanged, this, &VideoManager::_videoSourceChanged); - connect(_videoSettings->aspectRatio(), &Fact::rawValueChanged, this, &VideoManager::aspectRatioChanged); - connect(_videoSettings->lowLatencyMode(),&Fact::rawValueChanged, this, &VideoManager::_lowLatencyModeChanged); - MultiVehicleManager *pVehicleMgr = _toolbox->multiVehicleManager(); - connect(pVehicleMgr, &MultiVehicleManager::activeVehicleChanged, this, &VideoManager::_setActiveVehicle); +void VideoManager::init() +{ + if (_initialized) { + return; + } -#ifdef QGC_GST_STREAMING - GStreamer::blacklist(static_cast(_videoSettings->forceVideoDecoder()->rawValue().toInt())); -#endif + // TODO: Those connections should be Per Video, not per VideoManager. + (void) connect(_videoSettings->videoSource(), &Fact::rawValueChanged, this, &VideoManager::_videoSourceChanged); + (void) connect(_videoSettings->udpPort(), &Fact::rawValueChanged, this, &VideoManager::_videoSourceChanged); + (void) connect(_videoSettings->rtspUrl(), &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, &VideoManager::_lowLatencyModeChanged); + (void) connect(qgcApp()->toolbox()->multiVehicleManager(), &MultiVehicleManager::activeVehicleChanged, this, &VideoManager::_setActiveVehicle); int index = 0; for (VideoReceiverData &videoReceiver : _videoReceiverData) { - videoReceiver.receiver = toolbox->corePlugin()->createVideoReceiver(this); - videoReceiver.index = index; - index++; - } - - if (_videoReceiverData[0].receiver != nullptr) { - (void) connect(_videoReceiverData[0].receiver, &VideoReceiver::streamingChanged, this, [this](bool active){ - _streaming = active; - emit streamingChanged(); - }); + videoReceiver.index = index++; + videoReceiver.receiver = qgcApp()->toolbox()->corePlugin()->createVideoReceiver(this); + if (!videoReceiver.receiver) { + continue; + } - (void) connect(_videoReceiverData[0].receiver, &VideoReceiver::onStartComplete, this, [this](VideoReceiver::STATUS status) { - qCDebug(VideoManagerLog) << "Video 0 Start complete, status: " << status; - if (status == VideoReceiver::STATUS_OK) { - _videoReceiverData[0].started = true; - if (_videoReceiverData[0].sink != nullptr) { - qCDebug(VideoManagerLog) << "Video 0 start decoding"; - // It is absolutely ok to have video receiver active (streaming) and decoding not active - // It should be handy for cases when you have many streams and want to show only some of them - // NOTE that even if decoder did not start it is still possible to record video - _videoReceiverData[0].receiver->startDecoding(_videoReceiverData[0].sink); + (void) connect(videoReceiver.receiver, &VideoReceiver::onStartComplete, this, [this, &videoReceiver](VideoReceiver::STATUS status) { + qCDebug(VideoManagerLog) << "Video" << videoReceiver.index << "Start complete, status:" << status; + switch (status) { + case VideoReceiver::STATUS_OK: + videoReceiver.started = true; + if (videoReceiver.sink != nullptr) { + videoReceiver.receiver->startDecoding(videoReceiver.sink); } - } else if (status == VideoReceiver::STATUS_INVALID_URL) { - // Invalid URL - don't restart - } else if (status == VideoReceiver::STATUS_INVALID_STATE) { - // Already running - } else { - _restartVideo(0); + break; + case VideoReceiver::STATUS_INVALID_URL: + case VideoReceiver::STATUS_INVALID_STATE: + break; + default: + _restartVideo(videoReceiver.index); + break; } }); - (void) connect(_videoReceiverData[0].receiver, &VideoReceiver::onStopComplete, this, [this](VideoReceiver::STATUS status) { - qCDebug(VideoManagerLog) << "Video 0 Stop complete, status: " << status; - _videoReceiverData[0].started = false; + (void) connect(videoReceiver.receiver, &VideoReceiver::onStopComplete, this, [this, &videoReceiver](VideoReceiver::STATUS status) { + qCDebug(VideoManagerLog) << "Video" << videoReceiver.index << "Stop complete, status:" << status; + videoReceiver.started = false; if (status == VideoReceiver::STATUS_INVALID_URL) { qCDebug(VideoManagerLog) << "Invalid video URL. Not restarting"; } else { - _startReceiver(0); + _startReceiver(videoReceiver.index); } }); - (void) connect(_videoReceiverData[0].receiver, &VideoReceiver::decodingChanged, this, [this](bool active){ - qCDebug(VideoManagerLog) << "Video 0 decoding changed, active: " << (active ? "yes" : "no"); - _decoding = active; - emit decodingChanged(); + // TODO: Create status variables for each receiver in VideoReceiverData + (void) connect(videoReceiver.receiver, &VideoReceiver::streamingChanged, this, [this, &videoReceiver](bool active) { + qCDebug(VideoManagerLog) << "Video" << videoReceiver.index << "streaming changed, active:" << (active ? "yes" : "no"); + if (videoReceiver.index == 0) { + _streaming = active; + emit streamingChanged(); + } }); - (void) connect(_videoReceiverData[0].receiver, &VideoReceiver::recordingChanged, this, [this](bool active){ - qCDebug(VideoManagerLog) << "Video 0 recording changed, active: " << (active ? "yes" : "no"); - _recording = active; - if (!active) { - _subtitleWriter->stopCapturingTelemetry(); + (void) connect(videoReceiver.receiver, &VideoReceiver::decodingChanged, this, [this, &videoReceiver](bool active) { + qCDebug(VideoManagerLog) << "Video" << videoReceiver.index << "decoding changed, active:" << (active ? "yes" : "no"); + if (videoReceiver.index == 0) { + _decoding = active; + emit decodingChanged(); } - emit recordingChanged(); }); - (void) connect(_videoReceiverData[0].receiver, &VideoReceiver::recordingStarted, this, [this](){ - qCDebug(VideoManagerLog) << "Video 0 recording started"; - _subtitleWriter->startCapturingTelemetry(_videoFile); + (void) connect(videoReceiver.receiver, &VideoReceiver::recordingChanged, this, [this, &videoReceiver](bool active) { + qCDebug(VideoManagerLog) << "Video" << videoReceiver.index << "recording changed, active:" << (active ? "yes" : "no"); + if (videoReceiver.index == 0) { + _recording = active; + if (!active) { + _subtitleWriter->stopCapturingTelemetry(); + } + emit recordingChanged(); + } }); - (void) connect(_videoReceiverData[0].receiver, &VideoReceiver::videoSizeChanged, this, [this](QSize size){ - qCDebug(VideoManagerLog) << "Video 0 resized. New resolution: " << size.width() << "x" << size.height(); - _videoSize = ((quint32)size.width() << 16) | (quint32)size.height(); - emit videoSizeChanged(); + (void) connect(videoReceiver.receiver, &VideoReceiver::recordingStarted, this, [this, &videoReceiver]() { + qCDebug(VideoManagerLog) << "Video" << videoReceiver.index << "recording started"; + if (videoReceiver.index == 0) { + _subtitleWriter->startCapturingTelemetry(_videoFile); + } }); - (void) connect(_videoReceiverData[0].receiver, &VideoReceiver::onTakeScreenshotComplete, this, [this](VideoReceiver::STATUS status){ - if (status == VideoReceiver::STATUS_OK) { - qCDebug(VideoManagerLog) << "Video 0 screenshot taken"; - } else { - qCWarning(VideoManagerLog) << "Video 1 screenshot failed"; + (void) connect(videoReceiver.receiver, &VideoReceiver::videoSizeChanged, this, [this, &videoReceiver](QSize size) { + qCDebug(VideoManagerLog) << "Video" << videoReceiver.index << "resized. New resolution:" << size.width() << "x" << size.height(); + if (videoReceiver.index == 0) { + _videoSize = (static_cast(size.width()) << 16) | static_cast(size.height()); + emit videoSizeChanged(); } }); - } - if (_videoReceiverData[1].receiver != nullptr) { - (void) connect(_videoReceiverData[1].receiver, &VideoReceiver::onStartComplete, this, [this](VideoReceiver::STATUS status) { + (void) connect(videoReceiver.receiver, &VideoReceiver::onTakeScreenshotComplete, this, [this, &videoReceiver](VideoReceiver::STATUS status) { if (status == VideoReceiver::STATUS_OK) { - _videoReceiverData[1].started = true; - if (_videoReceiverData[1].sink != nullptr) { - _videoReceiverData[1].receiver->startDecoding(_videoReceiverData[1].sink); - } - } else if (status == VideoReceiver::STATUS_INVALID_URL) { - // Invalid URL - don't restart - } else if (status == VideoReceiver::STATUS_INVALID_STATE) { - // Already running + qCDebug(VideoManagerLog) << "Video" << videoReceiver.index << "screenshot taken"; } else { - _restartVideo(1); + qCWarning(VideoManagerLog) << "Video" << videoReceiver.index << "screenshot failed"; } }); - - (void) connect(_videoReceiverData[1].receiver, &VideoReceiver::onStopComplete, this, [this](VideoReceiver::STATUS) { - _videoReceiverData[1].started = false; - _startReceiver(1); - }); } - for (VideoReceiverData &videoReceiver : _videoReceiverData) { - (void) _updateSettings(videoReceiver.index); - } + _videoSourceChanged(); - emit isStreamSourceChanged(); startVideo(); -} - -void VideoManager::_cleanupOldVideos() -{ - //-- Only perform cleanup if storage limit is enabled - if(!_videoSettings->enableStorageLimit()->rawValue().toBool()) { - return; - } - const QString savePath = _toolbox->settingsManager()->appSettings()->videoSavePath(); - QDir videoDir = QDir(savePath); - videoDir.setFilter(QDir::Files | QDir::Readable | QDir::NoSymLinks | QDir::Writable); - videoDir.setSorting(QDir::Time); - - QStringList nameFilters; - for(size_t i = 0; i < sizeof(kFileExtension) / sizeof(kFileExtension[0]); i += 1) { - nameFilters << QString("*.") + kFileExtension[i]; + QQuickWindow *const rootWindow = qgcApp()->mainRootWindow(); + if (rootWindow) { + rootWindow->scheduleRenderJob(new FinishVideoInitialization(), QQuickWindow::BeforeSynchronizingStage); } - videoDir.setNameFilters(nameFilters); - //-- get the list of videos stored - QFileInfoList vidList = videoDir.entryInfoList(); - if(!vidList.isEmpty()) { - uint64_t total = 0; - //-- Settings are stored using MB - const uint64_t maxSize = _videoSettings->maxVideoSize()->rawValue().toUInt() * pow(1024, 2); - //-- Compute total used storage - for(int i = 0; i < vidList.size(); i++) { - total += vidList[i].size(); - } - //-- Remove old movies until max size is satisfied. - while(total >= maxSize && !vidList.isEmpty()) { - total -= vidList.last().size(); - qCDebug(VideoManagerLog) << "Removing old video file:" << vidList.last().filePath(); - QFile file (vidList.last().filePath()); - file.remove(); - vidList.removeLast(); - } - } + _initialized = true; } -//----------------------------------------------------------------------------- -void -VideoManager::startVideo() +void VideoManager::startVideo() { - if (_app->runningUnitTests()) { - return; - } - - if(!_videoSettings->streamEnabled()->rawValue().toBool() || !hasVideo()) { + if (!_videoSettings->streamEnabled()->rawValue().toBool() || !hasVideo()) { qCDebug(VideoManagerLog) << "Stream not enabled/configured"; return; } @@ -273,89 +226,59 @@ VideoManager::startVideo() } } -//----------------------------------------------------------------------------- -void -VideoManager::stopVideo() +void VideoManager::stopVideo() { - if (_app->runningUnitTests()) { - return; - } - for (VideoReceiverData &videoReceiver : _videoReceiverData) { _stopReceiver(videoReceiver.index); } } -void -VideoManager::startRecording(const QString& videoFile) +void VideoManager::startRecording(const QString &videoFile) { - if (_app->runningUnitTests()) { - return; - } - - if (!_videoReceiverData[0].receiver) { - _app->showAppMessage(tr("Video receiver is not ready.")); - return; - } - const VideoReceiver::FILE_FORMAT fileFormat = static_cast(_videoSettings->recordingFormat()->rawValue().toInt()); - - if(fileFormat < VideoReceiver::FILE_FORMAT_MIN || fileFormat >= VideoReceiver::FILE_FORMAT_MAX) { - _app->showAppMessage(tr("Invalid video format defined.")); + if (fileFormat < VideoReceiver::FILE_FORMAT_MIN || fileFormat >= VideoReceiver::FILE_FORMAT_MAX) { + qgcApp()->showAppMessage(tr("Invalid video format defined.")); return; } _cleanupOldVideos(); - const QString savePath = _toolbox->settingsManager()->appSettings()->videoSavePath(); - + const QString savePath = qgcApp()->toolbox()->settingsManager()->appSettings()->videoSavePath(); if (savePath.isEmpty()) { - _app->showAppMessage(tr("Unabled to record video. Video save path must be specified in Settings.")); + qgcApp()->showAppMessage(tr("Unabled to record video. Video save path must be specified in Settings.")); return; } - _videoFile = savePath + "/" - + (videoFile.isEmpty() ? QDateTime::currentDateTime().toString("yyyy-MM-dd_hh.mm.ss") : videoFile) - + "."; - + const QString videoFileUrl = videoFile.isEmpty() ? QDateTime::currentDateTime().toString("yyyy-MM-dd_hh.mm.ss") : videoFile; const QString ext = kFileExtension[fileFormat - VideoReceiver::FILE_FORMAT_MIN]; - const QString videoFile2 = _videoFile + "2." + ext; - _videoFile += ext; - const QStringList videoFiles = {_videoFile, videoFile2}; + const QString videoFile1 = savePath + "/" + videoFileUrl + "." + ext; + const QString videoFile2 = savePath + "/" + videoFileUrl + ".2." + ext; + + _videoFile = videoFile1; + + const QStringList videoFiles = {videoFile1, videoFile2}; for (VideoReceiverData &videoReceiver : _videoReceiverData) { if (videoReceiver.receiver && videoReceiver.started) { videoReceiver.receiver->startRecording(videoFiles.at(videoReceiver.index), fileFormat); + } else { + qCDebug(VideoManagerLog) << "Video receiver is not ready."; } } } -void -VideoManager::stopRecording() +void VideoManager::stopRecording() { - if (_app->runningUnitTests()) { - return; - } - for (VideoReceiverData &videoReceiver : _videoReceiverData) { videoReceiver.receiver->stopRecording(); } } -void -VideoManager::grabImage(const QString& imageFile) +void VideoManager::grabImage(const QString &imageFile) { - if (_app->runningUnitTests()) { - return; - } - - if (!_videoReceiverData[0].receiver) { - return; - } - if (imageFile.isEmpty()) { - _imageFile = _toolbox->settingsManager()->appSettings()->photoSavePath(); - _imageFile += + "/" + QDateTime::currentDateTime().toString("yyyy-MM-dd_hh.mm.ss.zzz") + ".jpg"; + _imageFile = qgcApp()->toolbox()->settingsManager()->appSettings()->photoSavePath(); + _imageFile += "/" + QDateTime::currentDateTime().toString("yyyy-MM-dd_hh.mm.ss.zzz") + ".jpg"; } else { _imageFile = imageFile; } @@ -365,77 +288,74 @@ VideoManager::grabImage(const QString& imageFile) _videoReceiverData[0].receiver->takeScreenshot(_imageFile); } -//----------------------------------------------------------------------------- double VideoManager::aspectRatio() const { - if(_activeVehicle && _activeVehicle->cameraManager()) { + if (_activeVehicle && _activeVehicle->cameraManager()) { const QGCVideoStreamInfo* const pInfo = _activeVehicle->cameraManager()->currentStreamInstance(); - if(pInfo) { - qCDebug(VideoManagerLog) << "Primary AR: " << pInfo->aspectRatio(); + if (pInfo) { + qCDebug(VideoManagerLog) << "Primary AR:" << pInfo->aspectRatio(); return pInfo->aspectRatio(); } } + // FIXME: AV: use _videoReceiver->videoSize() to calculate AR (if AR is not specified in the settings?) return _videoSettings->aspectRatio()->rawValue().toDouble(); } -//----------------------------------------------------------------------------- double VideoManager::thermalAspectRatio() const { - if(_activeVehicle && _activeVehicle->cameraManager()) { + if (_activeVehicle && _activeVehicle->cameraManager()) { const QGCVideoStreamInfo* const pInfo = _activeVehicle->cameraManager()->thermalStreamInstance(); - if(pInfo) { - qCDebug(VideoManagerLog) << "Thermal AR: " << pInfo->aspectRatio(); + if (pInfo) { + qCDebug(VideoManagerLog) << "Thermal AR:" << pInfo->aspectRatio(); return pInfo->aspectRatio(); } } + return 1.0; } -//----------------------------------------------------------------------------- double VideoManager::hfov() const { - if(_activeVehicle && _activeVehicle->cameraManager()) { + if (_activeVehicle && _activeVehicle->cameraManager()) { const QGCVideoStreamInfo* const pInfo = _activeVehicle->cameraManager()->currentStreamInstance(); - if(pInfo) { + if (pInfo) { return pInfo->hfov(); } } + return 1.0; } -//----------------------------------------------------------------------------- double VideoManager::thermalHfov() const { - if(_activeVehicle && _activeVehicle->cameraManager()) { + if (_activeVehicle && _activeVehicle->cameraManager()) { const QGCVideoStreamInfo* const pInfo = _activeVehicle->cameraManager()->thermalStreamInstance(); - if(pInfo) { + if (pInfo) { return pInfo->aspectRatio(); } } + return _videoSettings->aspectRatio()->rawValue().toDouble(); } -//----------------------------------------------------------------------------- -bool -VideoManager::hasThermal() const +bool VideoManager::hasThermal() const { - if(_activeVehicle && _activeVehicle->cameraManager()) { + if (_activeVehicle && _activeVehicle->cameraManager()) { const QGCVideoStreamInfo* const pInfo = _activeVehicle->cameraManager()->thermalStreamInstance(); - if(pInfo) { + if (pInfo) { return true; } } + return false; } -//----------------------------------------------------------------------------- -bool -VideoManager::autoStreamConfigured() const +bool VideoManager::autoStreamConfigured() const { - if(_activeVehicle && _activeVehicle->cameraManager()) { + if (_activeVehicle && _activeVehicle->cameraManager()) { const QGCVideoStreamInfo* const pInfo = _activeVehicle->cameraManager()->currentStreamInstance(); - if(pInfo) { + if (pInfo) { return !pInfo->uri().isEmpty(); } } @@ -443,103 +363,35 @@ VideoManager::autoStreamConfigured() const return false; } -//----------------------------------------------------------------------------- -// If we are using a UVC camera setup the device name -bool -VideoManager::_updateUVC() -{ - bool result = false; -#ifndef QGC_DISABLE_UVC - const QString oldUvcVideoSrcID = _uvcVideoSourceID; - if (!hasVideo() || isStreamSource()) { - _uvcVideoSourceID = ""; - } else { - const QString videoSource = _videoSettings->videoSource()->rawValue().toString(); - const QList videoInputs = QMediaDevices::videoInputs(); - for (const auto& cameraDevice: videoInputs) { - if (cameraDevice.description() == videoSource) { - _uvcVideoSourceID = cameraDevice.description(); - qCDebug(VideoManagerLog) << "Found USB source:" << _uvcVideoSourceID << " Name:" << videoSource; - break; - } - } - } - - if (oldUvcVideoSrcID != _uvcVideoSourceID) { - qCDebug(VideoManagerLog) << "UVC changed from [" << oldUvcVideoSrcID << "] to [" << _uvcVideoSourceID << "]"; - const QCameraPermission cameraPermission; - if (_app->checkPermission(cameraPermission) == Qt::PermissionStatus::Undetermined) { - _app->requestPermission(cameraPermission, [this](const QPermission &permission) { - if (permission.status() == Qt::PermissionStatus::Granted) { - _app->showRebootAppMessage(tr("Restart application for changes to take effect.")); - } - }); - } - result = true; - emit uvcVideoSourceIDChanged(); - emit isUvcChanged(); - } -#endif - return result; -} - -//----------------------------------------------------------------------------- -void -VideoManager::_videoSourceChanged() -{ - (void) _updateSettings(0); - emit hasVideoChanged(); - emit isStreamSourceChanged(); - emit isUvcChanged(); - emit isAutoStreamChanged(); - if (hasVideo()) { - _restartVideo(0); - } else { - stopVideo(); - } -} - -//----------------------------------------------------------------------------- -void -VideoManager::_lowLatencyModeChanged() -{ - _restartAllVideos(); -} - -//----------------------------------------------------------------------------- -bool -VideoManager::hasVideo() const +bool VideoManager::hasVideo() const { return (autoStreamConfigured() || _videoSettings->streamConfigured()); } -//----------------------------------------------------------------------------- -bool -VideoManager::isStreamSource() const -{ +bool VideoManager::isStreamSource() const +{ + static const QStringList videoSourceList = { + VideoSettings::videoSourceUDPH264, + VideoSettings::videoSourceUDPH265, + VideoSettings::videoSourceRTSP, + VideoSettings::videoSourceTCP, + VideoSettings::videoSourceMPEGTS, + VideoSettings::videoSource3DRSolo, + VideoSettings::videoSourceParrotDiscovery, + VideoSettings::videoSourceYuneecMantisG, + VideoSettings::videoSourceHerelinkAirUnit, + VideoSettings::videoSourceHerelinkHotspot, + }; const QString videoSource = _videoSettings->videoSource()->rawValue().toString(); - return videoSource == VideoSettings::videoSourceUDPH264 || - videoSource == VideoSettings::videoSourceUDPH265 || - videoSource == VideoSettings::videoSourceRTSP || - videoSource == VideoSettings::videoSourceTCP || - videoSource == VideoSettings::videoSourceMPEGTS || - videoSource == VideoSettings::videoSource3DRSolo || - videoSource == VideoSettings::videoSourceParrotDiscovery || - videoSource == VideoSettings::videoSourceYuneecMantisG || - videoSource == VideoSettings::videoSourceHerelinkAirUnit || - videoSource == VideoSettings::videoSourceHerelinkHotspot || - autoStreamConfigured(); -} - -bool -VideoManager::isUvc() const + return videoSourceList.contains(videoSource) || autoStreamConfigured(); +} + +bool VideoManager::isUvc() const { return (uvcEnabled() && (hasVideo() && !_uvcVideoSourceID.isEmpty())); } -//----------------------------------------------------------------------------- -bool -VideoManager::gstreamerEnabled() const +bool VideoManager::gstreamerEnabled() const { #ifdef QGC_GST_STREAMING return true; @@ -548,9 +400,7 @@ VideoManager::gstreamerEnabled() const #endif } -//----------------------------------------------------------------------------- -bool -VideoManager::uvcEnabled() const +bool VideoManager::uvcEnabled() const { #ifndef QGC_DISABLE_UVC return !QMediaDevices::videoInputs().isEmpty(); @@ -559,9 +409,7 @@ VideoManager::uvcEnabled() const #endif } -//----------------------------------------------------------------------------- -bool -VideoManager::qtmultimediaEnabled() const +bool VideoManager::qtmultimediaEnabled() const { #ifdef QGC_QT_STREAMING return true; @@ -570,13 +418,10 @@ VideoManager::qtmultimediaEnabled() const #endif } -//----------------------------------------------------------------------------- -void -VideoManager::setfullScreen(bool on) +void VideoManager::setfullScreen(bool on) { if (on) { - //-- No can do if no vehicle or connection lost - if(!_activeVehicle || _activeVehicle->vehicleLinkManager()->communicationLost()) { + if (!_activeVehicle || _activeVehicle->vehicleLinkManager()->communicationLost()) { on = false; } } @@ -587,12 +432,9 @@ VideoManager::setfullScreen(bool on) } } -//----------------------------------------------------------------------------- -void -VideoManager::_initVideo() +void VideoManager::_initVideo() { - QQuickWindow* root = _app->mainRootWindow(); - + QQuickWindow *const root = qgcApp()->mainRootWindow(); if (root == nullptr) { qCDebug(VideoManagerLog) << "mainRootWindow() failed. No root window"; return; @@ -601,8 +443,8 @@ VideoManager::_initVideo() const QStringList widgetTypes = {"videoContent", "thermalVideo"}; for (VideoReceiverData &videoReceiver : _videoReceiverData) { QQuickItem* const widget = root->findChild(widgetTypes.at(videoReceiver.index)); - if (widget != nullptr && videoReceiver.receiver != nullptr) { - videoReceiver.sink = _toolbox->corePlugin()->createVideoSink(this, widget); + if ((widget != nullptr) && (videoReceiver.receiver != nullptr)) { + videoReceiver.sink = qgcApp()->toolbox()->corePlugin()->createVideoSink(this, widget); if (videoReceiver.sink != nullptr) { if (videoReceiver.started) { videoReceiver.receiver->startDecoding(videoReceiver.sink); @@ -616,11 +458,173 @@ VideoManager::_initVideo() } } -//----------------------------------------------------------------------------- -bool -VideoManager::_updateSettings(unsigned id) +void VideoManager::_cleanupOldVideos() +{ + if (!qgcApp()->toolbox()->settingsManager()->videoSettings()->enableStorageLimit()->rawValue().toBool()) { + return; + } + + const QString savePath = qgcApp()->toolbox()->settingsManager()->appSettings()->videoSavePath(); + QDir videoDir = QDir(savePath); + videoDir.setFilter(QDir::Files | QDir::Readable | QDir::NoSymLinks | QDir::Writable); + videoDir.setSorting(QDir::Time); + + QStringList nameFilters; + for (size_t i = 0; i < std::size(kFileExtension); i++) { + nameFilters << QStringLiteral("*.") + kFileExtension[i]; + } + + videoDir.setNameFilters(nameFilters); + QFileInfoList vidList = videoDir.entryInfoList(); + if (!vidList.isEmpty()) { + uint64_t total = 0; + for (int i = 0; i < vidList.size(); i++) { + total += vidList[i].size(); + } + + const uint64_t maxSize = qgcApp()->toolbox()->settingsManager()->videoSettings()->maxVideoSize()->rawValue().toUInt() * qPow(1024, 2); + while ((total >= maxSize) && !vidList.isEmpty()) { + total -= vidList.last().size(); + qCDebug(VideoManagerLog) << "Removing old video file:" << vidList.last().filePath(); + QFile file(vidList.last().filePath()); + (void) file.remove(); + vidList.removeLast(); + } + } +} + +void VideoManager::_videoSourceChanged() { - if(!_videoSettings) { + for (const VideoReceiverData &videoReceiver : _videoReceiverData) { + (void) _updateSettings(videoReceiver.index); + } + + emit hasVideoChanged(); + emit isStreamSourceChanged(); + emit isUvcChanged(); + emit isAutoStreamChanged(); + + if (hasVideo()) { + _restartAllVideos(); + } else { + stopVideo(); + } + + qCDebug(VideoManagerLog) << "New Video Source:" << _videoSettings->videoSource()->rawValue().toString(); +} + +bool VideoManager::_updateUVC() +{ + bool result = false; + +#ifndef QGC_DISABLE_UVC + const QString oldUvcVideoSrcID = _uvcVideoSourceID; + if (!hasVideo() || isStreamSource()) { + _uvcVideoSourceID = ""; + } else { + const QString videoSource = _videoSettings->videoSource()->rawValue().toString(); + const QList videoInputs = QMediaDevices::videoInputs(); + for (const auto& cameraDevice: videoInputs) { + if (cameraDevice.description() == videoSource) { + _uvcVideoSourceID = cameraDevice.description(); + qCDebug(VideoManagerLog) << "Found USB source:" << _uvcVideoSourceID << " Name:" << videoSource; + break; + } + } + } + + if (oldUvcVideoSrcID != _uvcVideoSourceID) { + qCDebug(VideoManagerLog) << "UVC changed from [" << oldUvcVideoSrcID << "] to [" << _uvcVideoSourceID << "]"; + const QCameraPermission cameraPermission; + if (qgcApp()->checkPermission(cameraPermission) == Qt::PermissionStatus::Undetermined) { + qgcApp()->requestPermission(cameraPermission, [this](const QPermission &permission) { + if (permission.status() == Qt::PermissionStatus::Granted) { + qgcApp()->showRebootAppMessage(tr("Restart application for changes to take effect.")); + } + }); + } + result = true; + emit uvcVideoSourceIDChanged(); + emit isUvcChanged(); + } +#endif + + return result; +} + +bool VideoManager::_updateAutoStream(unsigned id) +{ + if (!_activeVehicle || !_activeVehicle->cameraManager()) { + return false; + } + + const QGCVideoStreamInfo* const pInfo = _activeVehicle->cameraManager()->currentStreamInstance(); + if (!pInfo) { + return false; + } + + bool settingsChanged = false; + if (id == 0) { + qCDebug(VideoManagerLog) << "Configure primary stream:" << pInfo->uri(); + switch(pInfo->type()) { + case VIDEO_STREAM_TYPE_RTSP: + settingsChanged = _updateVideoUri(id, pInfo->uri()); + if (settingsChanged) { + qgcApp()->toolbox()->settingsManager()->videoSettings()->videoSource()->setRawValue(VideoSettings::videoSourceRTSP); + } + break; + case VIDEO_STREAM_TYPE_TCP_MPEG: + settingsChanged = _updateVideoUri(id, pInfo->uri()); + if (settingsChanged) { + qgcApp()->toolbox()->settingsManager()->videoSettings()->videoSource()->setRawValue(VideoSettings::videoSourceTCP); + } + break; + case VIDEO_STREAM_TYPE_RTPUDP: { + const QString url = pInfo->uri().contains("udp://") ? pInfo->uri() : QStringLiteral("udp://0.0.0.0:%1").arg(pInfo->uri()); + settingsChanged = _updateVideoUri(id, url); + if (settingsChanged) { + qgcApp()->toolbox()->settingsManager()->videoSettings()->videoSource()->setRawValue(VideoSettings::videoSourceUDPH264); + } + break; + } + case VIDEO_STREAM_TYPE_MPEG_TS: + settingsChanged = _updateVideoUri(id, QStringLiteral("mpegts://0.0.0.0:%1").arg(pInfo->uri())); + if (settingsChanged) { + qgcApp()->toolbox()->settingsManager()->videoSettings()->videoSource()->setRawValue(VideoSettings::videoSourceMPEGTS); + } + break; + default: + settingsChanged = _updateVideoUri(id, pInfo->uri()); + break; + } + } else if (id == 1) { + const QGCVideoStreamInfo* const pTinfo = _activeVehicle->cameraManager()->thermalStreamInstance(); + if (pTinfo) { + qCDebug(VideoManagerLog) << "Configure secondary stream:" << pTinfo->uri(); + switch(pTinfo->type()) { + case VIDEO_STREAM_TYPE_RTSP: + case VIDEO_STREAM_TYPE_TCP_MPEG: + settingsChanged = _updateVideoUri(id, pTinfo->uri()); + break; + case VIDEO_STREAM_TYPE_RTPUDP: + settingsChanged = _updateVideoUri(id, QStringLiteral("udp://0.0.0.0:%1").arg(pTinfo->uri())); + break; + case VIDEO_STREAM_TYPE_MPEG_TS: + settingsChanged = _updateVideoUri(id, QStringLiteral("mpegts://0.0.0.0:%1").arg(pTinfo->uri())); + break; + default: + settingsChanged = _updateVideoUri(id, pTinfo->uri()); + break; + } + } + } + + return settingsChanged; +} + +bool VideoManager::_updateSettings(unsigned id) +{ + if (!_videoSettings) { return false; } @@ -639,107 +643,50 @@ VideoManager::_updateSettings(unsigned id) settingsChanged |= _updateUVC(); - //-- Auto discovery - - if(_activeVehicle && _activeVehicle->cameraManager()) { + if (_activeVehicle && _activeVehicle->cameraManager()) { const QGCVideoStreamInfo* const pInfo = _activeVehicle->cameraManager()->currentStreamInstance(); - if(pInfo) { - if (id == 0) { - qCDebug(VideoManagerLog) << "Configure primary stream:" << pInfo->uri(); - switch(pInfo->type()) { - case VIDEO_STREAM_TYPE_RTSP: - if ((settingsChanged |= _updateVideoUri(id, pInfo->uri()))) { - _toolbox->settingsManager()->videoSettings()->videoSource()->setRawValue(VideoSettings::videoSourceRTSP); - } - break; - case VIDEO_STREAM_TYPE_TCP_MPEG: - if ((settingsChanged |= _updateVideoUri(id, pInfo->uri()))) { - _toolbox->settingsManager()->videoSettings()->videoSource()->setRawValue(VideoSettings::videoSourceTCP); - } - break; - case VIDEO_STREAM_TYPE_RTPUDP: - if ((settingsChanged |= _updateVideoUri( - id, - pInfo->uri().contains("udp://") - ? pInfo->uri() // Specced case - : QStringLiteral("udp://0.0.0.0:%1").arg(pInfo->uri())))) { - _toolbox->settingsManager()->videoSettings()->videoSource()->setRawValue(VideoSettings::videoSourceUDPH264); - } - break; - case VIDEO_STREAM_TYPE_MPEG_TS: - if ((settingsChanged |= _updateVideoUri(id, QStringLiteral("mpegts://0.0.0.0:%1").arg(pInfo->uri())))) { - _toolbox->settingsManager()->videoSettings()->videoSource()->setRawValue(VideoSettings::videoSourceMPEGTS); - } - break; - default: - settingsChanged |= _updateVideoUri(id, pInfo->uri()); - break; - } - } else if (id == 1) { //-- Thermal stream (if any) - const QGCVideoStreamInfo* const pTinfo = _activeVehicle->cameraManager()->thermalStreamInstance(); - if (pTinfo) { - qCDebug(VideoManagerLog) << "Configure secondary stream:" << pTinfo->uri(); - switch(pTinfo->type()) { - case VIDEO_STREAM_TYPE_RTSP: - case VIDEO_STREAM_TYPE_TCP_MPEG: - settingsChanged |= _updateVideoUri(id, pTinfo->uri()); - break; - case VIDEO_STREAM_TYPE_RTPUDP: - settingsChanged |= _updateVideoUri(id, QStringLiteral("udp://0.0.0.0:%1").arg(pTinfo->uri())); - break; - case VIDEO_STREAM_TYPE_MPEG_TS: - settingsChanged |= _updateVideoUri(id, QStringLiteral("mpegts://0.0.0.0:%1").arg(pTinfo->uri())); - break; - default: - settingsChanged |= _updateVideoUri(id, pTinfo->uri()); - break; - } - } - } - settingsChanged |= _updateUVC(); + if (pInfo) { + settingsChanged |= _updateAutoStream(id); return settingsChanged; } } - settingsChanged |= _updateUVC(); - - const QString source = _videoSettings->videoSource()->rawValue().toString(); - if (source == VideoSettings::videoSourceUDPH264) - settingsChanged |= _updateVideoUri(0, QStringLiteral("udp://0.0.0.0:%1").arg(_videoSettings->udpPort()->rawValue().toInt())); - else if (source == VideoSettings::videoSourceUDPH265) - settingsChanged |= _updateVideoUri(0, QStringLiteral("udp265://0.0.0.0:%1").arg(_videoSettings->udpPort()->rawValue().toInt())); - else if (source == VideoSettings::videoSourceMPEGTS) - settingsChanged |= _updateVideoUri(0, QStringLiteral("mpegts://0.0.0.0:%1").arg(_videoSettings->udpPort()->rawValue().toInt())); - else if (source == VideoSettings::videoSourceRTSP) - settingsChanged |= _updateVideoUri(0, _videoSettings->rtspUrl()->rawValue().toString()); - else if (source == VideoSettings::videoSourceTCP) - settingsChanged |= _updateVideoUri(0, QStringLiteral("tcp://%1").arg(_videoSettings->tcpUrl()->rawValue().toString())); - else if (source == VideoSettings::videoSource3DRSolo) - settingsChanged |= _updateVideoUri(0, QStringLiteral("udp://0.0.0.0:5600")); - else if (source == VideoSettings::videoSourceParrotDiscovery) - settingsChanged |= _updateVideoUri(0, QStringLiteral("udp://0.0.0.0:8888")); - else if (source == VideoSettings::videoSourceYuneecMantisG) - settingsChanged |= _updateVideoUri(0, QStringLiteral("rtsp://192.168.42.1:554/live")); - else if (source == VideoSettings::videoSourceHerelinkAirUnit) - settingsChanged |= _updateVideoUri(0, QStringLiteral("rtsp://192.168.0.10:8554/H264Video")); - else if (source == VideoSettings::videoSourceHerelinkHotspot) - settingsChanged |= _updateVideoUri(0, QStringLiteral("rtsp://192.168.43.1:8554/fpv_stream")); - else if (source == VideoSettings::videoDisabled || source == VideoSettings::videoSourceNoVideo) - settingsChanged |= _updateVideoUri(0, ""); - else { - settingsChanged |= _updateVideoUri(0, ""); - if (!isUvc()) { - qCCritical(VideoManagerLog) - << "Video source URI \"" << source << "\" is not supported. Please add support!"; + if (id == 0) { + const QString source = _videoSettings->videoSource()->rawValue().toString(); + if (source == VideoSettings::videoSourceUDPH264) { + settingsChanged |= _updateVideoUri(id, QStringLiteral("udp://0.0.0.0:%1").arg(_videoSettings->udpPort()->rawValue().toInt())); + } else if (source == VideoSettings::videoSourceUDPH265) { + settingsChanged |= _updateVideoUri(id, QStringLiteral("udp265://0.0.0.0:%1").arg(_videoSettings->udpPort()->rawValue().toInt())); + } else if (source == VideoSettings::videoSourceMPEGTS) { + settingsChanged |= _updateVideoUri(id, QStringLiteral("mpegts://0.0.0.0:%1").arg(_videoSettings->udpPort()->rawValue().toInt())); + } else if (source == VideoSettings::videoSourceRTSP) { + settingsChanged |= _updateVideoUri(id, _videoSettings->rtspUrl()->rawValue().toString()); + } else if (source == VideoSettings::videoSourceTCP) { + settingsChanged |= _updateVideoUri(id, QStringLiteral("tcp://%1").arg(_videoSettings->tcpUrl()->rawValue().toString())); + } else if (source == VideoSettings::videoSource3DRSolo) { + settingsChanged |= _updateVideoUri(id, QStringLiteral("udp://0.0.0.0:5600")); + } else if (source == VideoSettings::videoSourceParrotDiscovery) { + settingsChanged |= _updateVideoUri(id, QStringLiteral("udp://0.0.0.0:8888")); + } else if (source == VideoSettings::videoSourceYuneecMantisG) { + settingsChanged |= _updateVideoUri(id, QStringLiteral("rtsp://192.168.42.1:554/live")); + } else if (source == VideoSettings::videoSourceHerelinkAirUnit) { + settingsChanged |= _updateVideoUri(id, QStringLiteral("rtsp://192.168.0.10:8554/H264Video")); + } else if (source == VideoSettings::videoSourceHerelinkHotspot) { + settingsChanged |= _updateVideoUri(id, QStringLiteral("rtsp://192.168.43.1:8554/fpv_stream")); + } else if (source == VideoSettings::videoDisabled || source == VideoSettings::videoSourceNoVideo) { + settingsChanged |= _updateVideoUri(id, ""); + } else { + settingsChanged |= _updateVideoUri(id, ""); + if (!isUvc()) { + qCCritical(VideoManagerLog) << "Video source URI \"" << source << "\" is not supported. Please add support!"; + } } } return settingsChanged; } -//----------------------------------------------------------------------------- -bool -VideoManager::_updateVideoUri(unsigned id, const QString& uri) +bool VideoManager::_updateVideoUri(unsigned id, const QString &uri) { if (id > (_videoReceiverData.size() - 1)) { qCDebug(VideoManagerLog) << "Unsupported receiver id" << id; @@ -750,27 +697,21 @@ VideoManager::_updateVideoUri(unsigned id, const QString& uri) return false; } - qCDebug(VideoManagerLog) << "New Video URI " << uri; + qCDebug(VideoManagerLog) << "New Video URI" << uri; _videoReceiverData[id].uri = uri; return true; } -//----------------------------------------------------------------------------- -void -VideoManager::_restartVideo(unsigned id) +void VideoManager::_restartVideo(unsigned id) { - if (_app->runningUnitTests()) { - return; - } - if (id > (_videoReceiverData.size() - 1)) { qCDebug(VideoManagerLog) << "Unsupported receiver id" << id; return; } - qCDebug(VideoManagerLog) << "Restart video streaming" << id; + qCDebug(VideoManagerLog) << "Restart video streaming" << id; if (_videoReceiverData[id].started) { _stopReceiver(id); @@ -779,18 +720,14 @@ VideoManager::_restartVideo(unsigned id) _startReceiver(id); } -//----------------------------------------------------------------------------- -void -VideoManager::_restartAllVideos() +void VideoManager::_restartAllVideos() { for (const VideoReceiverData &videoReceiver : _videoReceiverData) { _restartVideo(videoReceiver.index); } } -//---------------------------------------------------------------------------------------- -void -VideoManager::_startReceiver(unsigned id) +void VideoManager::_startReceiver(unsigned id) { if (id > (_videoReceiverData.size() - 1)) { qCDebug(VideoManagerLog) << "Unsupported receiver id" << id; @@ -802,23 +739,21 @@ VideoManager::_startReceiver(unsigned id) return; } + if (_videoReceiverData[id].uri.isEmpty()) { + qCDebug(VideoManagerLog) << "VideoUri is NULL" << id; + return; + } + const QString source = _videoSettings->videoSource()->rawValue().toString(); const unsigned rtsptimeout = _videoSettings->rtspTimeout()->rawValue().toUInt(); /* The gstreamer rtsp source will switch to tcp if udp is not available after 5 seconds. So we should allow for some negotiation time for rtsp */ const unsigned timeout = (source == VideoSettings::videoSourceRTSP ? rtsptimeout : 2); - if (_videoReceiverData[id].uri.isEmpty()) { - qCDebug(VideoManagerLog) << "VideoUri is NULL" << id; - return; - } - _videoReceiverData[id].receiver->start(_videoReceiverData[id].uri, timeout, _videoReceiverData[id].lowLatencyStreaming ? -1 : 0); } -//---------------------------------------------------------------------------------------- -void -VideoManager::_stopReceiver(unsigned id) +void VideoManager::_stopReceiver(unsigned id) { if (id > (_videoReceiverData.size() - 1)) { qCDebug(VideoManagerLog) << "Unsupported receiver id" << id; @@ -833,28 +768,26 @@ VideoManager::_stopReceiver(unsigned id) _videoReceiverData[id].receiver->stop(); } -//---------------------------------------------------------------------------------------- -void -VideoManager::_setActiveVehicle(Vehicle* vehicle) +void VideoManager::_setActiveVehicle(Vehicle *vehicle) { - if(_activeVehicle) { - disconnect(_activeVehicle->vehicleLinkManager(), &VehicleLinkManager::communicationLostChanged, this, &VideoManager::_communicationLostChanged); - if(_activeVehicle->cameraManager()) { - auto pCamera = _activeVehicle->cameraManager()->currentCameraInstance(); - if(pCamera) { + if (_activeVehicle) { + (void) disconnect(_activeVehicle->vehicleLinkManager(), &VehicleLinkManager::communicationLostChanged, this, &VideoManager::_communicationLostChanged); + if (_activeVehicle->cameraManager()) { + MavlinkCameraControl *const pCamera = _activeVehicle->cameraManager()->currentCameraInstance(); + if (pCamera) { pCamera->stopStream(); } - disconnect(_activeVehicle->cameraManager(), &QGCCameraManager::streamChanged, this, &VideoManager::_restartAllVideos); + (void) disconnect(_activeVehicle->cameraManager(), &QGCCameraManager::streamChanged, this, &VideoManager::_restartAllVideos); } } _activeVehicle = vehicle; - if(_activeVehicle) { - connect(_activeVehicle->vehicleLinkManager(), &VehicleLinkManager::communicationLostChanged, this, &VideoManager::_communicationLostChanged); - if(_activeVehicle->cameraManager()) { - connect(_activeVehicle->cameraManager(), &QGCCameraManager::streamChanged, this, &VideoManager::_restartAllVideos); - auto pCamera = _activeVehicle->cameraManager()->currentCameraInstance(); - if(pCamera) { + if (_activeVehicle) { + (void) connect(_activeVehicle->vehicleLinkManager(), &VehicleLinkManager::communicationLostChanged, this, &VideoManager::_communicationLostChanged); + if (_activeVehicle->cameraManager()) { + (void) connect(_activeVehicle->cameraManager(), &QGCCameraManager::streamChanged, this, &VideoManager::_restartAllVideos); + MavlinkCameraControl *const pCamera = _activeVehicle->cameraManager()->currentCameraInstance(); + if (pCamera) { pCamera->resumeStream(); } } @@ -866,12 +799,27 @@ VideoManager::_setActiveVehicle(Vehicle* vehicle) _restartAllVideos(); } -//---------------------------------------------------------------------------------------- -void -VideoManager::_communicationLostChanged(bool connectionLost) +void VideoManager::_communicationLostChanged(bool connectionLost) { - if(connectionLost) { + if (connectionLost) { setfullScreen(false); } } +/*===========================================================================*/ + +FinishVideoInitialization::FinishVideoInitialization() + : QRunnable() +{ + // qCDebug(VideoManagerLog) << Q_FUNC_INFO << this; +} + +FinishVideoInitialization::~FinishVideoInitialization() +{ + // qCDebug(VideoManagerLog) << Q_FUNC_INFO << this; +} + +void FinishVideoInitialization::run() +{ + VideoManager::instance()->_initVideo(); +} diff --git a/src/VideoManager/VideoManager.h b/src/VideoManager/VideoManager.h index c8ed043c219..32179ea1631 100644 --- a/src/VideoManager/VideoManager.h +++ b/src/VideoManager/VideoManager.h @@ -7,163 +7,151 @@ * ****************************************************************************/ - #pragma once -#include -#include #include - -#include "QGCToolbox.h" +#include +#include +#include Q_DECLARE_LOGGING_CATEGORY(VideoManagerLog) #define MAX_VIDEO_RECEIVERS 2 -class VideoSettings; +class FinishVideoInitialization; +class SubtitleWriter; class Vehicle; -class Joystick; class VideoReceiver; -class SubtitleWriter; +class VideoSettings; -class VideoManager : public QGCTool +class VideoManager : public QObject { Q_OBJECT - Q_PROPERTY(bool hasVideo READ hasVideo NOTIFY hasVideoChanged) - Q_PROPERTY(bool isStreamSource READ isStreamSource NOTIFY isStreamSourceChanged) - Q_PROPERTY(bool gstreamerEnabled READ gstreamerEnabled CONSTANT) - Q_PROPERTY(bool isUvc READ isUvc NOTIFY isUvcChanged) - Q_PROPERTY(QString uvcVideoSourceID READ uvcVideoSourceID NOTIFY uvcVideoSourceIDChanged) - Q_PROPERTY(bool uvcEnabled READ uvcEnabled CONSTANT) - Q_PROPERTY(bool qtmultimediaEnabled READ qtmultimediaEnabled CONSTANT) - Q_PROPERTY(bool fullScreen READ fullScreen WRITE setfullScreen NOTIFY fullScreenChanged) - Q_PROPERTY(double aspectRatio READ aspectRatio NOTIFY aspectRatioChanged) - Q_PROPERTY(double thermalAspectRatio READ thermalAspectRatio NOTIFY aspectRatioChanged) - Q_PROPERTY(double hfov READ hfov NOTIFY aspectRatioChanged) - Q_PROPERTY(double thermalHfov READ thermalHfov NOTIFY aspectRatioChanged) - Q_PROPERTY(bool autoStreamConfigured READ autoStreamConfigured NOTIFY autoStreamConfiguredChanged) - Q_PROPERTY(bool hasThermal READ hasThermal NOTIFY decodingChanged) - Q_PROPERTY(QString imageFile READ imageFile NOTIFY imageFileChanged) - Q_PROPERTY(bool streaming READ streaming NOTIFY streamingChanged) - Q_PROPERTY(bool decoding READ decoding NOTIFY decodingChanged) - Q_PROPERTY(bool recording READ recording NOTIFY recordingChanged) - Q_PROPERTY(QSize videoSize READ videoSize NOTIFY videoSizeChanged) - -public: - VideoManager(QGCApplication* app, QGCToolbox* toolbox); - virtual ~VideoManager(); - - void setToolbox(QGCToolbox *toolbox) override; - - virtual bool hasVideo () const; - virtual bool isStreamSource () const; - virtual bool isUvc () const; - virtual bool fullScreen () const { return _fullScreen; } - virtual QString uvcVideoSourceID () const { return _uvcVideoSourceID; } - virtual double aspectRatio () const; - virtual double thermalAspectRatio () const; - virtual double hfov () const; - virtual double thermalHfov () const; - virtual bool autoStreamConfigured() const; - virtual bool hasThermal () const; - virtual QString imageFile () const { return _imageFile; } + Q_PROPERTY(bool gstreamerEnabled READ gstreamerEnabled CONSTANT) + Q_PROPERTY(bool qtmultimediaEnabled READ qtmultimediaEnabled CONSTANT) + Q_PROPERTY(bool uvcEnabled READ uvcEnabled CONSTANT) + 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 hasThermal READ hasThermal NOTIFY decodingChanged) + Q_PROPERTY(bool hasVideo READ hasVideo NOTIFY hasVideoChanged) + Q_PROPERTY(bool isStreamSource READ isStreamSource NOTIFY isStreamSourceChanged) + Q_PROPERTY(bool isUvc READ isUvc NOTIFY isUvcChanged) + Q_PROPERTY(bool recording READ recording NOTIFY recordingChanged) + Q_PROPERTY(bool streaming READ streaming NOTIFY streamingChanged) + Q_PROPERTY(double aspectRatio READ aspectRatio NOTIFY aspectRatioChanged) + Q_PROPERTY(double hfov READ hfov NOTIFY aspectRatioChanged) + Q_PROPERTY(double thermalAspectRatio READ thermalAspectRatio NOTIFY aspectRatioChanged) + Q_PROPERTY(double thermalHfov READ thermalHfov NOTIFY aspectRatioChanged) + Q_PROPERTY(QSize videoSize READ videoSize NOTIFY videoSizeChanged) + Q_PROPERTY(QString imageFile READ imageFile NOTIFY imageFileChanged) + Q_PROPERTY(QString uvcVideoSourceID READ uvcVideoSourceID NOTIFY uvcVideoSourceIDChanged) - bool streaming() const { return _streaming; } - bool decoding() const { return _decoding; } - bool recording() const { return _recording; } - QSize videoSize() const { return QSize((_videoSize >> 16) & 0xFFFF, _videoSize & 0xFFFF); } + friend class FinishVideoInitialization; - virtual bool gstreamerEnabled() const; - virtual bool uvcEnabled() const; - virtual bool qtmultimediaEnabled() const; +public: + explicit VideoManager(QObject *parent = nullptr); + ~VideoManager(); - virtual void setfullScreen(bool on); + /// Gets the singleton instance of VideoManager. + /// @return The singleton instance. + static VideoManager *instance(); + Q_INVOKABLE void grabImage(const QString &imageFile = QString()); + Q_INVOKABLE void startRecording(const QString &videoFile = QString()); Q_INVOKABLE void startVideo(); - Q_INVOKABLE void stopVideo(); - - Q_INVOKABLE void startRecording(const QString& videoFile = QString()); Q_INVOKABLE void stopRecording(); + Q_INVOKABLE void stopVideo(); - Q_INVOKABLE void grabImage(const QString& imageFile = QString()); + void init(); + bool autoStreamConfigured() const; + bool decoding() const { return _decoding; } + bool fullScreen() const { return _fullScreen; } + bool gstreamerEnabled() const; + bool hasThermal() const; + bool hasVideo() const; + bool isStreamSource() const; + bool isUvc() const; + bool qtmultimediaEnabled() const; + bool recording() const { return _recording; } + bool streaming() const { return _streaming; } + bool uvcEnabled() const; + double aspectRatio() const; + double hfov() const; + double thermalAspectRatio() const; + double thermalHfov() const; + QSize videoSize() const { return QSize((_videoSize >> 16) & 0xFFFF, _videoSize & 0xFFFF); } + QString imageFile() const { return _imageFile; } + QString uvcVideoSourceID() const { return _uvcVideoSourceID; } + void setfullScreen(bool on); signals: - void hasVideoChanged (); - void isStreamSourceChanged (); - void isUvcChanged (); - void uvcVideoSourceIDChanged (); - void fullScreenChanged (); - void isAutoStreamChanged (); - void aspectRatioChanged (); + void aspectRatioChanged(); void autoStreamConfiguredChanged(); - void imageFileChanged (); - void streamingChanged (); - void decodingChanged (); - void recordingChanged (); - void recordingStarted (); - void videoSizeChanged (); - -protected slots: - void _videoSourceChanged (); - void _lowLatencyModeChanged (); - bool _updateUVC (); - void _setActiveVehicle (Vehicle* vehicle); - void _communicationLostChanged (bool communicationLost); - -protected: - friend class FinishVideoInitialization; + void decodingChanged(); + void fullScreenChanged(); + void hasVideoChanged(); + void imageFileChanged(); + void isAutoStreamChanged(); + void isStreamSourceChanged(); + void isUvcChanged(); + void recordingChanged(); + void recordingStarted(); + void streamingChanged(); + void uvcVideoSourceIDChanged(); + void videoSizeChanged(); + +private slots: + bool _updateUVC(); + void _communicationLostChanged(bool communicationLost); + void _lowLatencyModeChanged() { _restartAllVideos(); } + void _setActiveVehicle(Vehicle *vehicle); + void _videoSourceChanged(); - void _initVideo (); - bool _updateSettings (unsigned id); - bool _updateVideoUri (unsigned id, const QString& uri); - void _cleanupOldVideos(); +private: + bool _updateAutoStream(unsigned id); + bool _updateSettings(unsigned id); + bool _updateVideoUri(unsigned id, const QString &uri); + void _initVideo(); void _restartAllVideos(); - void _restartVideo (unsigned id); - void _startReceiver (unsigned id); - void _stopReceiver (unsigned id); - - QString _videoFile; - QString _imageFile; - SubtitleWriter* _subtitleWriter = nullptr; + void _restartVideo(unsigned id); + void _startReceiver(unsigned id); + void _stopReceiver(unsigned id); + static void _cleanupOldVideos(); struct VideoReceiverData { - VideoReceiver* receiver = nullptr; - void* sink = nullptr; + VideoReceiver *receiver = nullptr; + void *sink = nullptr; QString uri; bool started = false; bool lowLatencyStreaming = false; size_t index = 0; }; - QList _videoReceiverData = QList(MAX_VIDEO_RECEIVERS); - // FIXME: AV: _videoStarted seems to be access from 3 different threads, from time to time - // 1) Video Receiver thread - // 2) Video Manager/main app thread - // 3) Qt rendering thread (during video sink creation process which should happen in this thread) - // It works for now but... - - QAtomicInteger _streaming = false; - QAtomicInteger _decoding = false; - QAtomicInteger _recording = false; - QAtomicInteger _videoSize = 0; - VideoSettings* _videoSettings = nullptr; - QString _uvcVideoSourceID; - bool _fullScreen = false; - Vehicle* _activeVehicle = nullptr; + QList _videoReceiverData = QList(MAX_VIDEO_RECEIVERS); + + SubtitleWriter *_subtitleWriter = nullptr; + + bool _initialized = false; + bool _fullScreen = false; + QAtomicInteger _decoding = false; + QAtomicInteger _recording = false; + QAtomicInteger _streaming = false; + QAtomicInteger _videoSize = 0; + QString _imageFile; + QString _uvcVideoSourceID; + QString _videoFile; + Vehicle *_activeVehicle = nullptr; + VideoSettings *_videoSettings = nullptr; }; +/*===========================================================================*/ + class FinishVideoInitialization : public QRunnable { public: - explicit FinishVideoInitialization(VideoManager* manager) - : _manager(manager) - {} - - void run() - { - _manager->_initVideo(); - } + explicit FinishVideoInitialization(); + ~FinishVideoInitialization(); -private: - VideoManager* _manager = nullptr; + void run() final; };