QGroundControl
Ground Control Station for MAVLink Drones
Loading...
Searching...
No Matches
VideoManager.cc
Go to the documentation of this file.
1#include "VideoManager.h"
2#include "AppSettings.h"
5#include "AppMessages.h"
6#include "QGCApplication.h"
7#include "QGCCameraManager.h"
8#include "QGCCorePlugin.h"
10#include "QGCVideoStreamInfo.h"
11#include "SettingsManager.h"
12#include "SubtitleWriter.h"
13#include "Vehicle.h"
14#include "VehicleLinkManager.h"
15#include "VideoReceiver.h"
16#include "VideoSettings.h"
18#include "UVCReceiver.h"
19#ifdef QGC_GST_STREAMING
20#include "GStreamerHelpers.h"
21#include "GStreamer.h"
22#if defined(QGC_HAS_ANY_GPU_PATH)
24#endif
25#include <QtMultimedia/QVideoSink>
26#include <QtMultimediaQuick/private/qquickvideooutput_p.h>
27#endif
28
29#include <QtConcurrent/QtConcurrent>
30#include <QtCore/QApplicationStatic>
31#include <QtCore/QDir>
32#include <QtCore/QEventLoop>
33#include <QtCore/QFutureWatcher>
34#include <QtCore/QPointer>
35#include <QtCore/QRunnable>
36#include <QtCore/QTimer>
37#include <QtQml/QQmlEngine>
38#include <QtQuick/QQuickItem>
39#include <QtQuick/QQuickWindow>
40
41QGC_LOGGING_CATEGORY(VideoManagerLog, "Video.VideoManager")
42
43static constexpr const char *kFileExtension[VideoReceiver::FILE_FORMAT_MAX + 1] = {
44 "mkv",
45 "mov",
46 "mp4"
47};
48
49Q_APPLICATION_STATIC(VideoManager, _videoManagerInstance);
50
51bool VideoManager::_shouldSkipGStreamerForUnitTests()
52{
53 return qgcApp() && QGC::runningUnitTests() && !qEnvironmentVariableIsSet("QGC_TEST_ENABLE_GSTREAMER");
54}
55
57 : QObject(parent)
58 , _subtitleWriter(new SubtitleWriter(this))
59 , _videoSettings(SettingsManager::instance()->videoSettings())
60{
61 qCDebug(VideoManagerLog) << this;
62
63 (void) qRegisterMetaType<VideoReceiver::STATUS>("STATUS");
64
65#ifdef QGC_GST_STREAMING
66 _gstreamerDisabledForUnitTests = _shouldSkipGStreamerForUnitTests();
67 if (_gstreamerDisabledForUnitTests) {
68 qCInfo(VideoManagerLog) << "Skipping GStreamer initialization for unit tests";
69 }
70#endif
71}
72
74{
75 qCDebug(VideoManagerLog) << this;
76}
77
79{
80 return _videoManagerInstance();
81}
82
84{
85#ifdef QGC_GST_STREAMING
86 if (_gstreamerDisabledForUnitTests) {
87 _initState = InitState::GstReady;
88 qCInfo(VideoManagerLog) << "GStreamer initialization disabled for unit tests";
89 return;
90 }
91
92 if (_initState != InitState::NotStarted) {
93 qCWarning(VideoManagerLog) << "GStreamer init already started";
94 return;
95 }
96
97 _initState = InitState::Pending;
98
100 _gstInitFuture = QtConcurrent::run(&GStreamer::initialize);
101
102 _gstInitFuture.then(this, [this](bool success) {
103 _onGstInitComplete(success);
104 }).onCanceled(this, [this] {
105 _onGstInitComplete(false);
106 });
107#endif
108}
109
111{
112#ifdef QGC_GST_STREAMING
113 if (_gstreamerDisabledForUnitTests) {
114 return true;
115 }
116
117 if (_initState == InitState::NotStarted) {
119 }
120
121 switch (_initState) {
122 case InitState::Failed:
123 return false;
124 case InitState::GstReady:
125 case InitState::Running:
126 return true;
127 default:
128 break;
129 }
130
131 if (!_gstInitFuture.isValid()) {
132 qCCritical(VideoManagerLog) << "waitForGStreamerInit: no valid future";
133 return false;
134 }
135
136 QEventLoop loop;
137 QTimer timer;
138 timer.setSingleShot(true);
139 QFutureWatcher<bool> watcher;
140 (void) connect(&watcher, &QFutureWatcher<bool>::finished, &loop, &QEventLoop::quit);
141 (void) connect(&timer, &QTimer::timeout, &loop, &QEventLoop::quit);
142
143 watcher.setFuture(_gstInitFuture);
144 if (!watcher.isFinished()) {
145 timer.start(timeoutMs);
146 loop.exec();
147 }
148
149 if (!watcher.isFinished()) {
150 qCCritical(VideoManagerLog) << "Timed out waiting for GStreamer init";
151 return false;
152 }
153
154 const bool success = watcher.result();
155 if (_initState == InitState::Pending || _initState == InitState::QmlReady) {
156 _onGstInitComplete(success);
157 }
158 return _initState != InitState::Failed;
159#else
160 Q_UNUSED(timeoutMs);
161 return true;
162#endif
163}
164
165void VideoManager::init(QQuickWindow *mainWindow)
166{
167 if (_initialized) {
168 qCDebug(VideoManagerLog) << "Video Manager already initialized";
169 return;
170 }
171
172 if (!mainWindow) {
173 qCCritical(VideoManagerLog) << "Failed To Init Video Manager - mainWindow is NULL";
174 return;
175 }
176 _mainWindow = mainWindow;
177
178#if defined(QGC_HAS_ANY_GPU_PATH)
179 QGCRhiCapture::connectWindow(mainWindow); // populate cached QRhi for GPU bridge handlers
180#endif
181
182 (void) connect(_videoSettings->videoSource(), &Fact::rawValueChanged, this, &VideoManager::_videoSourceChanged);
183 (void) connect(_videoSettings->udpUrl(), &Fact::rawValueChanged, this, &VideoManager::_videoSourceChanged);
184 (void) connect(_videoSettings->rtspUrl(), &Fact::rawValueChanged, this, &VideoManager::_videoSourceChanged);
185 (void) connect(_videoSettings->tcpUrl(), &Fact::rawValueChanged, this, &VideoManager::_videoSourceChanged);
186 (void) connect(_videoSettings->aspectRatio(), &Fact::rawValueChanged, this, &VideoManager::aspectRatioChanged);
187 (void) connect(_videoSettings->lowLatencyMode(), &Fact::rawValueChanged, this, [this](const QVariant &value) { Q_UNUSED(value); _restartAllVideos(); });
188 (void) connect(SettingsManager::instance()->appSettings()->gstDebugLevel(), &Fact::rawValueChanged, this, [](const QVariant &value) {
189#ifdef QGC_GST_STREAMING
190 GStreamer::setDebugLevel(value.toInt());
191#else
192 Q_UNUSED(value);
193#endif
194 });
195 (void) connect(MultiVehicleManager::instance(), &MultiVehicleManager::activeVehicleChanged, this, &VideoManager::_setActiveVehicle);
196
197 (void) connect(this, &VideoManager::autoStreamConfiguredChanged, this, &VideoManager::_videoSourceChanged);
198
199#ifdef QGC_GST_STREAMING
200 if (_initState == InitState::NotStarted) {
202 }
203#endif
204
205 _mainWindow->scheduleRenderJob(
206 QRunnable::create([this] {
207 QMetaObject::invokeMethod(this, &VideoManager::_initAfterQmlIsReady, Qt::QueuedConnection);
208 }),
209 QQuickWindow::AfterSynchronizingStage);
210
211 _initialized = true;
212}
213
214void VideoManager::_initAfterQmlIsReady()
215{
216 if (!_mainWindow) {
217 qCCritical(VideoManagerLog) << "_initAfterQmlIsReady called with NULL mainWindow";
218 return;
219 }
220
221 qCDebug(VideoManagerLog) << "_initAfterQmlIsReady";
222
223#ifdef QGC_GST_STREAMING
224 switch (_initState) {
225 case InitState::Pending:
226 _initState = InitState::QmlReady;
227 qCDebug(VideoManagerLog) << "QML ready, waiting for GStreamer";
228 return;
229 case InitState::GstReady:
230 _initState = InitState::Running;
231 qCDebug(VideoManagerLog) << "QML ready, GStreamer already done — creating receivers";
232 break;
233 case InitState::Failed:
234 qCWarning(VideoManagerLog) << "QML ready but GStreamer init failed";
235 return;
236 default:
237 qCWarning(VideoManagerLog) << "_initAfterQmlIsReady: unexpected state" << static_cast<int>(_initState);
238 return;
239 }
240#endif
241 _createVideoReceivers();
242}
243
244void VideoManager::_onGstInitComplete(bool success)
245{
246 if (!success) {
247 _initState = InitState::Failed;
248 qCCritical(VideoManagerLog) << "GStreamer initialization failed";
249 return;
250 }
251
252#ifdef QGC_GST_STREAMING
253 if (_videoSettings) {
254 const auto decoderOption = static_cast<GStreamer::VideoDecoderOptions>(
255 _videoSettings->forceVideoDecoder()->rawValue().toInt());
256 GStreamer::setCodecPriorities(decoderOption);
257 }
258#endif
259
260 switch (_initState) {
261 case InitState::Pending:
262 _initState = InitState::GstReady;
263 qCDebug(VideoManagerLog) << "GStreamer ready, waiting for QML";
264 return;
265 case InitState::QmlReady:
266 _initState = InitState::Running;
267 qCDebug(VideoManagerLog) << "GStreamer ready, QML already done — creating receivers";
268 _createVideoReceivers();
269 return;
270 default:
271 qCWarning(VideoManagerLog) << "_onGstInitComplete: unexpected state" << static_cast<int>(_initState);
272 return;
273 }
274}
275
276void VideoManager::_createVideoReceivers()
277{
278#ifdef QGC_UNITTEST_BUILD
279 if (_createVideoReceiversForTest) {
280 _createVideoReceiversForTest();
281 return;
282 }
283#endif
284 static const QStringList videoStreamList = {
285 "videoContent",
286 "thermalVideo"
287 };
288 for (const QString &streamName : videoStreamList) {
290 if (!receiver) {
291 continue;
292 }
293 receiver->setName(streamName);
294
295 _initVideoReceiver(receiver, _mainWindow);
296 }
297}
298
300{
301 for (VideoReceiver *receiver : std::as_const(_videoReceivers)) {
303 }
304}
305
306void VideoManager::_cleanupOldVideos()
307{
308 if (!SettingsManager::instance()->videoSettings()->enableStorageLimit()->rawValue().toBool()) {
309 return;
310 }
311
312 const QString savePath = SettingsManager::instance()->appSettings()->videoSavePath();
313 QDir videoDir = QDir(savePath);
314 videoDir.setFilter(QDir::Files | QDir::Readable | QDir::NoSymLinks | QDir::Writable);
315 videoDir.setSorting(QDir::Time);
316
317 QStringList nameFilters;
318 for (size_t i = 0; i < std::size(kFileExtension); i++) {
319 nameFilters << QStringLiteral("*.") + kFileExtension[i];
320 }
321
322 videoDir.setNameFilters(nameFilters);
323 QFileInfoList vidList = videoDir.entryInfoList();
324 if (vidList.isEmpty()) {
325 return;
326 }
327
328 uint64_t total = 0;
329 for (const QFileInfo &video : std::as_const(vidList)) {
330 total += video.size();
331 }
332
333 const uint64_t maxSize = SettingsManager::instance()->videoSettings()->maxVideoSize()->rawValue().toUInt() * qPow(1024, 2);
334 while ((total >= maxSize) && !vidList.isEmpty()) {
335 const QFileInfo info = vidList.takeLast();
336 total -= info.size();
337 const QString path = info.filePath();
338 qCDebug(VideoManagerLog) << "Removing old video file:" << path;
339 (void) QFile::remove(path);
340 }
341}
342
343void VideoManager::startRecording(const QString &videoFile)
344{
345 const VideoReceiver::FILE_FORMAT fileFormat = static_cast<VideoReceiver::FILE_FORMAT>(_videoSettings->recordingFormat()->rawValue().toInt());
346 if (!VideoReceiver::isValidFileFormat(fileFormat)) {
347 QGC::showAppMessage(tr("Invalid video format defined."));
348 return;
349 }
350
351 _cleanupOldVideos();
352
353 const QString savePath = SettingsManager::instance()->appSettings()->videoSavePath();
354 if (savePath.isEmpty()) {
355 QGC::showAppMessage(tr("Unabled to record video. Video save path must be specified in Settings."));
356 return;
357 }
358
359 const QString videoFileUrl = videoFile.isEmpty() ? QDateTime::currentDateTime().toString("yyyy-MM-dd_hh.mm.ss") : videoFile;
360 const QString ext = kFileExtension[fileFormat];
361
362 const QString videoFileNameTemplate = savePath + "/" + videoFileUrl + ".%1" + ext;
363
364 for (VideoReceiver *receiver : std::as_const(_videoReceivers)) {
365 if (!receiver->started()) {
366 qCDebug(VideoManagerLog) << "Video receiver is not ready.";
367 continue;
368 }
369 const QString streamName = (receiver->name() == QStringLiteral("videoContent")) ? "" : (receiver->name() + ".");
370 const QString videoFileName = videoFileNameTemplate.arg(streamName);
371 receiver->startRecording(videoFileName, fileFormat);
372 }
373}
374
376{
377 for (VideoReceiver *receiver : std::as_const(_videoReceivers)) {
378 receiver->stopRecording();
379 }
380}
381
382void VideoManager::grabImage(const QString &imageFile)
383{
384 if (imageFile.isEmpty()) {
386 _imageFile += QStringLiteral("/") + QDateTime::currentDateTime().toString("yyyy-MM-dd_hh.mm.ss.zzz") + QStringLiteral(".jpg");
387 } else {
388 _imageFile = imageFile;
389 }
390
391 emit imageFileChanged(_imageFile);
392
393 for (VideoReceiver *receiver : std::as_const(_videoReceivers)) {
394 receiver->takeScreenshot(_imageFile);
395 // QSharedPointer<QQuickItemGrabResult> result = receiver->widget()->grabToImage(const QSize &targetSize = QSize())
396 }
397}
398
400{
401 for (VideoReceiver *receiver : _videoReceivers) {
402 QGCVideoStreamInfo *pInfo = receiver->videoStreamInfo();
403 if (!receiver->isThermal() && pInfo && !pInfo->isThermal()) {
404 return pInfo->aspectRatio();
405 }
406 }
407
408 // FIXME: use _videoReceiver->videoSize() to calculate AR (if AR is not specified in the settings?)
409 return _videoSettings->aspectRatio()->rawValue().toDouble();
410}
411
413{
414 for (VideoReceiver *receiver : _videoReceivers) {
415 QGCVideoStreamInfo *pInfo = receiver->videoStreamInfo();
416 if (receiver->isThermal() && pInfo && pInfo->isThermal()) {
417 return pInfo->aspectRatio();
418 }
419 }
420
421 return 1.0;
422}
423
424double VideoManager::hfov() const
425{
426 for (VideoReceiver *receiver : _videoReceivers) {
427 QGCVideoStreamInfo *pInfo = receiver->videoStreamInfo();
428 if (!receiver->isThermal() && pInfo && !pInfo->isThermal()) {
429 return pInfo->hfov();
430 }
431 }
432
433 return 1.0;
434}
435
437{
438 for (VideoReceiver *receiver : _videoReceivers) {
439 QGCVideoStreamInfo *pInfo = receiver->videoStreamInfo();
440 if (receiver->isThermal() && pInfo && pInfo->isThermal()) {
441 return pInfo->hfov();
442 }
443 }
444
445 return _videoSettings->aspectRatio()->rawValue().toDouble();
446}
447
449{
450 for (VideoReceiver *receiver : _videoReceivers) {
451 QGCVideoStreamInfo *pInfo = receiver->videoStreamInfo();
452 if (receiver->isThermal() && pInfo && pInfo->isThermal()) {
453 return true;
454 }
455 }
456
457 return false;
458}
459
461{
462 return (_videoSettings->streamEnabled()->rawValue().toBool() && _videoSettings->streamConfigured());
463}
464
466{
467 return (!_uvcVideoSourceID.isEmpty() && uvcEnabled() && hasVideo());
468}
469
471{
472#ifdef QGC_GST_STREAMING
473 return true;
474#else
475 return false;
476#endif
477}
478
480{
481 return UVCReceiver::enabled();
482}
483
488
490{
491 if (on) {
492 if (!_activeVehicle || _activeVehicle->vehicleLinkManager()->communicationLost()) {
493 on = false;
494 }
495 }
496
497 if (on != _fullScreen) {
498 _fullScreen = on;
499 emit fullScreenChanged();
500 }
501}
502
504{
505 static const QStringList videoSourceList = {
516 };
517 const QString videoSource = _videoSettings->videoSource()->rawValue().toString();
518 return (videoSourceList.contains(videoSource) || autoStreamConfigured());
519}
520
521void VideoManager::_videoSourceChanged()
522{
523 bool changed = false;
524 if (_activeVehicle) {
525 QGCCameraManager* camMgr = _activeVehicle->cameraManager();
526 for (VideoReceiver *receiver : std::as_const(_videoReceivers)) {
527 QGCVideoStreamInfo* info = nullptr;
528 if (receiver->isThermal()) {
529 info = camMgr ? camMgr->thermalStreamInstance() : nullptr;
530 } else {
531 info = camMgr ? camMgr->currentStreamInstance() : nullptr;
532 }
533 receiver->setVideoStreamInfo(info);
534 changed |= _updateSettings(receiver);
535 }
536 } else {
537 for (VideoReceiver *receiver : std::as_const(_videoReceivers)) {
538 receiver->setVideoStreamInfo(nullptr);
539 changed |= _updateSettings(receiver);
540 }
541 }
542
543 if (changed) {
544 emit hasVideoChanged();
546 emit isAutoStreamChanged();
547
548 if (hasVideo()) {
549 _restartAllVideos();
550 } else {
551 stopVideo();
552 }
553
554 qCDebug(VideoManagerLog) << "New Video Source:" << _videoSettings->videoSource()->rawValue().toString();
555 }
556}
557
558bool VideoManager::_updateUVC(VideoReceiver * /*receiver*/)
559{
560 bool result = false;
561
562 const QString oldUvcVideoSrcID = _uvcVideoSourceID;
563
564 if (!uvcEnabled() || !hasVideo() || isStreamSource()) {
565 _uvcVideoSourceID = QString();
566 } else {
567 _uvcVideoSourceID = UVCReceiver::getSourceId();
568 }
569
570 if (oldUvcVideoSrcID != _uvcVideoSourceID) {
571 qCDebug(VideoManagerLog) << "UVC changed from [" << oldUvcVideoSrcID << "] to [" << _uvcVideoSourceID << "]";
572 if (!_uvcVideoSourceID.isEmpty()) {
574 }
575 result = true;
577 emit isUvcChanged();
578 }
579
580 return result;
581}
582
584{
585 for (VideoReceiver *receiver : _videoReceivers) {
586 QGCVideoStreamInfo *pInfo = receiver->videoStreamInfo();
587 if (!receiver->isThermal() && pInfo && !pInfo->isThermal()) {
588 return !pInfo->uri().isEmpty();
589 }
590 }
591
592 return false;
593}
594
595bool VideoManager::_updateAutoStream(VideoReceiver *receiver)
596{
597 const QGCVideoStreamInfo *pInfo = receiver->videoStreamInfo();
598 if (!pInfo) {
599 return false;
600 }
601
602 qCDebug(VideoManagerLog) << QString("Configure stream (%1):").arg(receiver->name()) << pInfo->uri();
603
604 QString source, url;
605 switch (pInfo->type()) {
606 case VIDEO_STREAM_TYPE_RTSP:
608 url = pInfo->uri();
609 if (source == VideoSettings::videoSourceRTSP) {
610 _videoSettings->rtspUrl()->setRawValue(url);
611 }
612 break;
613 case VIDEO_STREAM_TYPE_TCP_MPEG:
615 url = pInfo->uri();
616 break;
617 case VIDEO_STREAM_TYPE_RTPUDP:
618 if (pInfo->encoding() == VIDEO_STREAM_ENCODING_H265) {
620 url = pInfo->uri().contains("udp265://") ? pInfo->uri() : QStringLiteral("udp265://0.0.0.0:%1").arg(pInfo->uri());
621 } else {
623 url = pInfo->uri().contains("udp://") ? pInfo->uri() : QStringLiteral("udp://0.0.0.0:%1").arg(pInfo->uri());
624 }
625 break;
626 case VIDEO_STREAM_TYPE_MPEG_TS:
628 url = pInfo->uri().contains("mpegts://") ? pInfo->uri() : QStringLiteral("mpegts://0.0.0.0:%1").arg(pInfo->uri());
629 break;
630 default:
631 qCWarning(VideoManagerLog) << "Unknown VIDEO_STREAM_TYPE";
633 url = pInfo->uri();
634 break;
635 }
636
637 const bool settingsChanged = _updateVideoUri(receiver, url);
638 if (settingsChanged) {
639 if (!receiver->isThermal()) {
640 _videoSettings->videoSource()->setRawValue(source);
641 }
642
644 }
645
646 return settingsChanged;
647}
648
649bool VideoManager::_updateVideoUri(VideoReceiver *receiver, const QString &uri)
650{
651 if (!receiver) {
652 qCDebug(VideoManagerLog) << "VideoReceiver is NULL";
653 return false;
654 }
655
656 if ((uri == receiver->uri()) && !receiver->uri().isNull()) {
657 return false;
658 }
659
660 qCDebug(VideoManagerLog) << "New Video URI" << uri;
661
662 receiver->setUri(uri);
663
664 return true;
665}
666
667bool VideoManager::_updateSettings(VideoReceiver *receiver)
668{
669 if (!receiver) {
670 qCDebug(VideoManagerLog) << "VideoReceiver is NULL";
671 return false;
672 }
673
674 bool settingsChanged = false;
675
676 const bool lowLatency = _videoSettings->lowLatencyMode()->rawValue().toBool();
677 if (lowLatency != receiver->lowLatency()) {
678 receiver->setLowLatency(lowLatency);
679 settingsChanged = true;
680 }
681
682 if (receiver->isThermal()) {
683 return settingsChanged;
684 }
685
686 settingsChanged |= _updateUVC(receiver);
687 settingsChanged |= _updateAutoStream(receiver);
688
689 const QString source = _videoSettings->videoSource()->rawValue().toString();
690 if (source == VideoSettings::videoSourceUDPH264) {
691 settingsChanged |= _updateVideoUri(receiver, QStringLiteral("udp://%1").arg(_videoSettings->udpUrl()->rawValue().toString()));
692 } else if (source == VideoSettings::videoSourceUDPH265) {
693 settingsChanged |= _updateVideoUri(receiver, QStringLiteral("udp265://%1").arg(_videoSettings->udpUrl()->rawValue().toString()));
694 } else if (source == VideoSettings::videoSourceMPEGTS) {
695 settingsChanged |= _updateVideoUri(receiver, QStringLiteral("mpegts://%1").arg(_videoSettings->udpUrl()->rawValue().toString()));
696 } else if (source == VideoSettings::videoSourceRTSP) {
697 settingsChanged |= _updateVideoUri(receiver, _videoSettings->rtspUrl()->rawValue().toString());
698 } else if (source == VideoSettings::videoSourceTCP) {
699 settingsChanged |= _updateVideoUri(receiver, QStringLiteral("tcp://%1").arg(_videoSettings->tcpUrl()->rawValue().toString()));
700 } else if (source == VideoSettings::videoSource3DRSolo) {
701 settingsChanged |= _updateVideoUri(receiver, QStringLiteral("udp://0.0.0.0:5600"));
702 } else if (source == VideoSettings::videoSourceParrotDiscovery) {
703 settingsChanged |= _updateVideoUri(receiver, QStringLiteral("udp://0.0.0.0:8888"));
704 } else if (source == VideoSettings::videoSourceYuneecMantisG) {
705 settingsChanged |= _updateVideoUri(receiver, QStringLiteral("rtsp://192.168.42.1:554/live"));
706 } else if (source == VideoSettings::videoSourceHerelinkAirUnit) {
707 settingsChanged |= _updateVideoUri(receiver, QStringLiteral("rtsp://192.168.0.10:8554/H264Video"));
708 } else if (source == VideoSettings::videoSourceHerelinkHotspot) {
709 settingsChanged |= _updateVideoUri(receiver, QStringLiteral("rtsp://192.168.43.1:8554/fpv_stream"));
710 } else if ((source == VideoSettings::videoDisabled) || (source == VideoSettings::videoSourceNoVideo)) {
711 settingsChanged |= _updateVideoUri(receiver, QString());
712 } else {
713 settingsChanged |= _updateVideoUri(receiver, QString());
714 if (!isUvc()) {
715 qCCritical(VideoManagerLog) << "Video source URI \"" << source << "\" is not supported. Please add support!";
716 }
717 }
718
719 return settingsChanged;
720}
721
722void VideoManager::_setActiveVehicle(Vehicle *vehicle)
723{
724 qCDebug(VideoManagerLog) << Q_FUNC_INFO << "new vehicle" << vehicle << "old active vehicle" << _activeVehicle;
725
726 if (_activeVehicle) {
727 (void) disconnect(_activeVehicle->vehicleLinkManager(), &VehicleLinkManager::communicationLostChanged, this, &VideoManager::_communicationLostChanged);
728 auto cameraManager = _activeVehicle->cameraManager();
729 if (cameraManager) {
730 MavlinkCameraControlInterface *pCamera = cameraManager->currentCameraInstance();
731 if (pCamera) {
732 pCamera->stopStream();
733 }
734 (void) disconnect(cameraManager, &QGCCameraManager::streamChanged, this, &VideoManager::_videoSourceChanged);
735 }
736
737 for (VideoReceiver *receiver : std::as_const(_videoReceivers)) {
738 // disconnect(receiver->videoStreamInfo(), &QGCVideoStreamInfo::infoChanged, ))
739 receiver->setVideoStreamInfo(nullptr);
740 }
741 }
742
743 _activeVehicle = vehicle;
744 if (_activeVehicle) {
745 (void) connect(_activeVehicle->vehicleLinkManager(), &VehicleLinkManager::communicationLostChanged, this, &VideoManager::_communicationLostChanged);
746 if (_activeVehicle->cameraManager()) {
747 (void) connect(_activeVehicle->cameraManager(), &QGCCameraManager::streamChanged, this, &VideoManager::_videoSourceChanged);
748 MavlinkCameraControlInterface *pCamera = _activeVehicle->cameraManager()->currentCameraInstance();
749 if (pCamera) {
750 pCamera->resumeStream();
751 }
752 }
753
754 for (VideoReceiver *receiver : std::as_const(_videoReceivers)) {
755 if (_activeVehicle->cameraManager()) {
756 if (receiver->isThermal()) {
757 receiver->setVideoStreamInfo(_activeVehicle->cameraManager()->thermalStreamInstance());
758 } else {
759 receiver->setVideoStreamInfo(_activeVehicle->cameraManager()->currentStreamInstance());
760 }
761 } else {
762 receiver->setVideoStreamInfo(nullptr);
763 }
764 // connect(receiver->videoStreamInfo(), &QGCVideoStreamInfo::infoChanged, ))
765 }
766 } else {
767 setfullScreen(false);
768 }
769}
770
771void VideoManager::_communicationLostChanged(bool connectionLost)
772{
773 if (connectionLost) {
774 setfullScreen(false);
775 }
776}
777
778void VideoManager::_restartAllVideos()
779{
780 for (VideoReceiver *videoReceiver : std::as_const(_videoReceivers)) {
781 _restartVideo(videoReceiver);
782 }
783}
784
785void VideoManager::_restartVideo(VideoReceiver *receiver)
786{
787 if (!receiver) {
788 qCDebug(VideoManagerLog) << "VideoReceiver is NULL";
789 return;
790 }
791
792 qCDebug(VideoManagerLog) << "Restart video receiver" << receiver->name();
793
794 if (receiver->started()) {
795 _stopReceiver(receiver);
796 // onStopComplete Signal Will Restart It
797 } else {
798 _startReceiver(receiver);
799 }
800}
801
802void VideoManager::_stopReceiver(VideoReceiver *receiver)
803{
804 if (!receiver) {
805 qCDebug(VideoManagerLog) << "VideoReceiver is NULL";
806 return;
807 }
808
809 if (receiver->started()) {
810 receiver->stop();
811 }
812}
813
815{
816 for (VideoReceiver *receiver : std::as_const(_videoReceivers)) {
817 _stopReceiver(receiver);
818 }
819}
820
821void VideoManager::_startReceiver(VideoReceiver *receiver)
822{
823 if (!receiver) {
824 qCDebug(VideoManagerLog) << "VideoReceiver is NULL";
825 return;
826 }
827
828 if (receiver->started()) {
829 qCDebug(VideoManagerLog) << "VideoReceiver is already started" << receiver->name();
830 return;
831 }
832
833 if (receiver->uri().isEmpty()) {
834 qCDebug(VideoManagerLog) << "VideoUri is NULL" << receiver->name();
835 return;
836 }
837
838 const QString source = _videoSettings->videoSource()->rawValue().toString();
839 /* The gstreamer rtsp source will switch to tcp if udp is not available after 5 seconds.
840 So we should allow for some negotiation time for rtsp */
841
842 const uint32_t timeout = ((source == VideoSettings::videoSourceRTSP) ? _videoSettings->rtspTimeout()->rawValue().toUInt() : 3);
843
844 receiver->start(timeout);
845}
846
847void VideoManager::_initVideoReceiver(VideoReceiver *receiver, QQuickWindow *window)
848{
849 if (_videoReceivers.contains(receiver)) {
850 qCWarning(VideoManagerLog) << "Receiver already initialized";
851 }
852
853 QQuickItem *widget = window->findChild<QQuickItem*>(receiver->name());
854 if (!widget) {
855 qCCritical(VideoManagerLog) << "stream widget not found" << receiver->name();
856 }
857 receiver->setWidget(widget);
858
859 void *sink = QGCCorePlugin::instance()->createVideoSink(receiver->widget(), receiver);
860 if (!sink) {
861 qCCritical(VideoManagerLog) << "createVideoSink() failed" << receiver->name();
862 }
863 receiver->setSink(sink);
864
865#ifdef QGC_GST_STREAMING
866 if (sink && widget) {
867 auto *videoOutput = qobject_cast<QQuickVideoOutput *>(widget);
868 if (videoOutput) {
869 QVideoSink *videoSink = videoOutput->videoSink();
870 if (!GStreamer::setupAppSinkAdapter(sink, videoSink, receiver)) {
871 qCWarning(VideoManagerLog) << "setupAppSinkAdapter failed" << receiver->name();
872 }
873 // Visibility gate: drop frames at the appsink while the host window is hidden
874 // or minimized. The decoder still runs (cheap with HW accel) but render-thread
875 // and copy work disappears. Connector handles late window attachment via
876 // QQuickItem::windowChanged.
877 auto applyVisibility = [receiver](QWindow *win) {
878 if (!win) return;
879 const QWindow::Visibility v = win->visibility();
880 const bool active = (v != QWindow::Hidden && v != QWindow::Minimized);
881 GStreamer::setAppSinkAdaptersActive(receiver, active);
882 };
883 // Track the previous connection so windowChanged can drop it before wiring the
884 // new window. Without this, an old hidden/minimized window keeps gating the
885 // live receiver after the video output reparents to a new window.
886 auto prevConn = std::make_shared<QMetaObject::Connection>();
887 auto wireWindow = [receiver, applyVisibility, prevConn](QQuickWindow *qw) {
888 if (*prevConn) {
889 QObject::disconnect(*prevConn);
890 *prevConn = QMetaObject::Connection{};
891 }
892 if (!qw) return;
893 applyVisibility(qw);
894 *prevConn = QObject::connect(qw, &QWindow::visibilityChanged, receiver,
895 [applyVisibility, qw](QWindow::Visibility) { applyVisibility(qw); });
896 };
897 if (QQuickWindow *qw = videoOutput->window()) wireWindow(qw);
898 QObject::connect(videoOutput, &QQuickVideoOutput::windowChanged, receiver, wireWindow);
899 } else {
900 qCWarning(VideoManagerLog) << "Widget is not a VideoOutput, cannot connect appsink" << receiver->name();
901 }
902 }
903#endif
904
905 (void) connect(receiver, &VideoReceiver::onStartComplete, this, [this, receiver](VideoReceiver::STATUS status) {
906 qCDebug(VideoManagerLog) << "Video" << receiver->name() << "Start complete, status:" << status;
907 switch (status) {
909 receiver->setStarted(true);
910 if (receiver->sink()) {
911 receiver->startDecoding(receiver->sink());
912 }
913 break;
916 break;
917 default:
918 _restartVideo(receiver);
919 break;
920 }
921 });
922
923 (void) connect(receiver, &VideoReceiver::onStopComplete, this, [this, receiver](VideoReceiver::STATUS status) {
924 qCDebug(VideoManagerLog) << "Stop complete" << receiver->name() << receiver->uri() << ", status:" << status;
925 receiver->setStarted(false);
926 if (status == VideoReceiver::STATUS_INVALID_URL) {
927 qCDebug(VideoManagerLog) << "Invalid video URL. Not restarting";
928 } else {
929 QTimer::singleShot(1000, receiver, [this, receiver]() {
930 qCDebug(VideoManagerLog) << "Restarting video receiver" << receiver->name() << receiver->uri();
931 _startReceiver(receiver);
932 });
933 }
934 });
935
936 (void) connect(receiver, &VideoReceiver::streamingChanged, this, [this, receiver](bool active) {
937 qCDebug(VideoManagerLog) << "Video" << receiver->name() << "streaming changed, active:" << (active ? "yes" : "no");
938 if (!receiver->isThermal()) {
939 _streaming = active;
940 emit streamingChanged();
941 }
942 });
943
944 (void) connect(receiver, &VideoReceiver::decodingChanged, this, [this, receiver](bool active) {
945 qCDebug(VideoManagerLog) << "Video" << receiver->name() << "decoding changed, active:" << (active ? "yes" : "no");
946 if (!receiver->isThermal()) {
947 _decoding = active;
948 emit decodingChanged();
949 }
950 });
951
952 (void) connect(receiver, &VideoReceiver::recordingChanged, this, [this, receiver](bool active) {
953 qCDebug(VideoManagerLog) << "Video" << receiver->name() << "recording changed, active:" << (active ? "yes" : "no");
954 if (!receiver->isThermal()) {
955 _recording = active;
956 if (!active) {
957 _subtitleWriter->stopCapturingTelemetry();
958 }
959 emit recordingChanged(_recording);
960 }
961 });
962
963 (void) connect(receiver, &VideoReceiver::recordingStarted, this, [this, receiver](const QString &filename) {
964 qCDebug(VideoManagerLog) << "Video" << receiver->name() << "recording started";
965 if (!receiver->isThermal()) {
966 _subtitleWriter->startCapturingTelemetry(filename, videoSize());
967 }
968 });
969
970 (void) connect(receiver, &VideoReceiver::videoSizeChanged, this, [this, receiver](QSize size) {
971 qCDebug(VideoManagerLog) << "Video" << receiver->name() << "resized. New resolution:" << size.width() << "x" << size.height();
972 if (!receiver->isThermal()) {
973 _videoSize = size;
974 emit videoSizeChanged();
975 }
976 });
977
978 (void) connect(receiver, &VideoReceiver::onTakeScreenshotComplete, this, [receiver](VideoReceiver::STATUS status) {
979 if (status == VideoReceiver::STATUS_OK) {
980 qCDebug(VideoManagerLog) << "Video" << receiver->name() << "screenshot taken";
981 } else {
982 qCWarning(VideoManagerLog) << "Video" << receiver->name() << "screenshot failed";
983 }
984 });
985
986 (void) connect(receiver, &VideoReceiver::videoStreamInfoChanged, this, [this, receiver]() {
987 const QGCVideoStreamInfo *videoStreamInfo = receiver->videoStreamInfo();
988 qCDebug(VideoManagerLog) << "Video" << receiver->name() << "stream info:" << (videoStreamInfo ? "received" : "lost");
989
990 (void) _updateAutoStream(receiver);
991 });
992
993 (void) _updateSettings(receiver);
994
995 _videoReceivers.append(receiver);
996
997 if (hasVideo()) {
998 _startReceiver(receiver);
999 }
1000}
1001
1003{
1004 qCDebug(VideoManagerLog) << "startVideo";
1005
1006 if (!hasVideo()) {
1007 qCDebug(VideoManagerLog) << "Stream not enabled/configured";
1008 return;
1009 }
1010
1011 _restartAllVideos();
1012}
#define qgcApp()
#define QGC_LOGGING_CATEGORY(name, categoryStr)
static constexpr const char * kFileExtension[VideoReceiver::FILE_FORMAT_MAX+1]
Q_APPLICATION_STATIC(VideoManager, _videoManagerInstance)
QString videoSavePath()
QString photoSavePath()
void rawValueChanged(const QVariant &value)
Abstract base class for all camera controls: real and simulated.
virtual Q_INVOKABLE void stopStream()=0
virtual Q_INVOKABLE void resumeStream()=0
static MultiVehicleManager * instance()
void activeVehicleChanged(Vehicle *activeVehicle)
Camera Manager.
QGCVideoStreamInfo * currentStreamInstance()
QGCVideoStreamInfo * thermalStreamInstance()
virtual void * createVideoSink(QQuickItem *widget, QObject *parent)
Allows the plugin to override the creation of VideoSink.
virtual VideoReceiver * createVideoReceiver(QObject *parent)
Allows the plugin to override the creation of VideoReceiver.
virtual void releaseVideoSink(void *sink)
Allows the plugin to override the release of VideoSink.
static QGCCorePlugin * instance()
Encapsulates the contents of a VIDEO_STREAM_INFORMATION message.
quint8 encoding() const
Provides access to all app settings.
static SettingsManager * instance()
VideoSettings * videoSettings() const
AppSettings * appSettings() const
void stopCapturingTelemetry()
void startCapturingTelemetry(const QString &videoFile, QSize size)
static bool enabled()
static QString getSourceId()
static void checkPermission()
void communicationLostChanged(bool communicationLost)
bool communicationLost() const
QGCCameraManager * cameraManager()
Definition Vehicle.h:1288
VehicleLinkManager * vehicleLinkManager()
Definition Vehicle.h:575
bool isStreamSource() const
void decodingChanged()
static bool gstreamerEnabled()
bool isUvc() const
void setfullScreen(bool on)
static bool uvcEnabled()
double hfov() const
static bool qtmultimediaEnabled()
Q_INVOKABLE void stopRecording()
void hasVideoChanged()
void uvcVideoSourceIDChanged()
Q_INVOKABLE void startVideo()
bool hasThermal() const
bool autoStreamConfigured() const
Q_INVOKABLE void startRecording(const QString &videoFile=QString())
double thermalAspectRatio() const
void isStreamSourceChanged()
static VideoManager * instance()
VideoManager(QObject *parent=nullptr)
void autoStreamConfiguredChanged()
void startGStreamerInit()
void streamingChanged()
void fullScreenChanged()
bool hasVideo() const
void init(QQuickWindow *mainWindow)
Q_INVOKABLE void stopVideo()
double aspectRatio() const
void isUvcChanged()
double thermalHfov() const
void imageFileChanged(const QString &filename)
bool waitForGStreamerInit(int timeoutMs=60000)
QSize videoSize() const
void recordingChanged(bool recording)
void isAutoStreamChanged()
void videoSizeChanged()
QString imageFile() const
void aspectRatioChanged()
Q_INVOKABLE void grabImage(const QString &imageFile=QString())
void recordingStarted(const QString &filename)
bool lowLatency() const
void setLowLatency(bool lowLatency)
void setName(const QString &name)
void videoSizeChanged(QSize size)
void streamingChanged(bool active)
virtual void stopRecording()=0
virtual void startRecording(const QString &videoFile, FILE_FORMAT format)=0
bool started() const
QQuickItem * widget()
QString uri() const
void recordingChanged(bool active)
void videoStreamInfoChanged()
virtual void setSink(void *sink)
bool isThermal() const
virtual void start(uint32_t timeout)=0
void onTakeScreenshotComplete(STATUS status)
void decodingChanged(bool active)
void onStartComplete(STATUS status)
void setStarted(bool started)
void setUri(const QString &uri)
static bool isValidFileFormat(FILE_FORMAT format)
QString name() const
virtual void setWidget(QQuickItem *widget)
virtual void startDecoding(void *sink)=0
void setVideoStreamInfo(QGCVideoStreamInfo *videoStreamInfo)
void onStopComplete(STATUS status)
virtual void stop()=0
virtual void takeScreenshot(const QString &imageFile)=0
QGCVideoStreamInfo * videoStreamInfo()
static constexpr const char * videoSource3DRSolo
static constexpr const char * videoSourceParrotDiscovery
static constexpr const char * videoSourceTCP
static constexpr const char * videoSourceUDPH264
static constexpr const char * videoSourceHerelinkHotspot
bool streamConfigured()
static constexpr const char * videoSourceRTSP
static constexpr const char * videoDisabled
static constexpr const char * videoSourceYuneecMantisG
static constexpr const char * videoSourceUDPH265
static constexpr const char * videoSourceNoVideo
static constexpr const char * videoSourceMPEGTS
static constexpr const char * videoSourceHerelinkAirUnit
void setDebugLevel(int level)
Definition GStreamer.cc:726
void setCodecPriorities(VideoDecoderOptions option)
VideoDecoderOptions
Definition GStreamer.h:10
void setAppSinkAdaptersActive(QObject *adapterParent, bool active)
Definition GStreamer.cc:971
bool initialize()
Definition GStreamer.cc:836
void prepareEnvironment()
Definition GStreamer.cc:736
bool setupAppSinkAdapter(void *sinkBin, QVideoSink *videoSink, QObject *adapterParent)
Connect the appsink inside sinkBin to videoSink. Returns true on success.
Definition GStreamer.cc:909
void connectWindow(QQuickWindow *window)
bool runningUnitTests()
void showAppMessage(const QString &message, const QString &title)
Modal application message. Queued if the UI isn't ready yet.
Definition AppMessages.cc:9