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 "QGCApplication.h"
6#include "QGCCameraManager.h"
7#include "QGCCorePlugin.h"
9#include "SettingsManager.h"
10#include "SubtitleWriter.h"
11#include "Vehicle.h"
12#include "VideoReceiver.h"
13#include "VideoSettings.h"
14#ifdef QGC_GST_STREAMING
15#include "GStreamer.h"
16#include "VideoItemStub.h"
17#else
18#include "VideoItemStub.h"
19#endif
21#include "UVCReceiver.h"
22
23#include <QtCore/QApplicationStatic>
24#include <QtCore/QDir>
25#include <QtQml/QQmlEngine>
26#include <QtQuick/QQuickItem>
27#include <QtQuick/QQuickWindow>
28#include <QtCore/QTimer>
29
30QGC_LOGGING_CATEGORY(VideoManagerLog, "Video.VideoManager")
31
32static constexpr const char *kFileExtension[VideoReceiver::FILE_FORMAT_MAX + 1] = {
33 "mkv",
34 "mov",
35 "mp4"
36};
37
38Q_APPLICATION_STATIC(VideoManager, _videoManagerInstance);
39
40VideoManager::VideoManager(QObject *parent)
41 : QObject(parent)
42 , _subtitleWriter(new SubtitleWriter(this))
43 , _videoSettings(SettingsManager::instance()->videoSettings())
44{
45 qCDebug(VideoManagerLog) << this;
46
47 (void) qRegisterMetaType<VideoReceiver::STATUS>("STATUS");
48
49#ifdef QGC_GST_STREAMING
50 const bool skipGStreamerForUnitTests =
51 qgcApp() && qgcApp()->runningUnitTests() && !qEnvironmentVariableIsSet("QGC_TEST_ENABLE_GSTREAMER");
52
53 if (skipGStreamerForUnitTests) {
54 (void) qmlRegisterType<VideoItemStub>("org.freedesktop.gstreamer.Qt6GLVideoItem", 1, 0, "GstGLQt6VideoItem");
55 qCInfo(VideoManagerLog) << "Skipping GStreamer initialization for unit tests";
56 } else if (!GStreamer::initialize()) {
57 qCCritical(VideoManagerLog) << "Failed To Initialize GStreamer";
58 }
59#else
60 (void) qmlRegisterType<VideoItemStub>("org.freedesktop.gstreamer.Qt6GLVideoItem", 1, 0, "GstGLQt6VideoItem");
61#endif
62}
63
64VideoManager::~VideoManager()
65{
66 qCDebug(VideoManagerLog) << this;
67}
68
69VideoManager *VideoManager::instance()
70{
71 return _videoManagerInstance();
72}
73
74void VideoManager::init(QQuickWindow *mainWindow)
75{
76 if (_initialized) {
77 qCDebug(VideoManagerLog) << "Video Manager already initialized";
78 return;
79 }
80
81 if (!mainWindow) {
82 qCCritical(VideoManagerLog) << "Failed To Init Video Manager - mainWindow is NULL";
83 return;
84 }
85 _mainWindow = mainWindow;
86
87 // TODO: VideoSettings _configChanged/streamConfiguredChanged
88 (void) connect(_videoSettings->videoSource(), &Fact::rawValueChanged, this, &VideoManager::_videoSourceChanged);
89 (void) connect(_videoSettings->udpUrl(), &Fact::rawValueChanged, this, &VideoManager::_videoSourceChanged);
90 (void) connect(_videoSettings->rtspUrl(), &Fact::rawValueChanged, this, &VideoManager::_videoSourceChanged);
91 (void) connect(_videoSettings->tcpUrl(), &Fact::rawValueChanged, this, &VideoManager::_videoSourceChanged);
92 (void) connect(_videoSettings->aspectRatio(), &Fact::rawValueChanged, this, &VideoManager::aspectRatioChanged);
93 (void) connect(_videoSettings->lowLatencyMode(), &Fact::rawValueChanged, this, [this](const QVariant &value) { Q_UNUSED(value); _restartAllVideos(); });
94 (void) connect(MultiVehicleManager::instance(), &MultiVehicleManager::activeVehicleChanged, this, &VideoManager::_setActiveVehicle);
95
96 (void) connect(this, &VideoManager::autoStreamConfiguredChanged, this, &VideoManager::_videoSourceChanged);
97
98 _mainWindow->scheduleRenderJob(new FinishVideoInitialization(), QQuickWindow::AfterSynchronizingStage);
99
100 _initialized = true;
101}
102
103void VideoManager::_initAfterQmlIsReady()
104{
105 if (_initAfterQmlIsReadyDone) {
106 qCWarning(VideoManagerLog) << "_initAfterQmlIsReady called multiple times";
107 return;
108 }
109 if (!_mainWindow) {
110 qCCritical(VideoManagerLog) << "_initAfterQmlIsReady called with NULL mainWindow";
111 return;
112 }
113 _initAfterQmlIsReadyDone = true;
114
115 qCDebug(VideoManagerLog) << "_initAfterQmlIsReady";
116
117 static const QStringList videoStreamList = {
118 "videoContent",
119 "thermalVideo"
120 };
121 for (const QString &streamName : videoStreamList) {
122 VideoReceiver *receiver = QGCCorePlugin::instance()->createVideoReceiver(this);
123 if (!receiver) {
124 continue;
125 }
126 receiver->setName(streamName);
127
128 _initVideoReceiver(receiver, _mainWindow);
129 }
130}
131
132void VideoManager::cleanup()
133{
134 for (VideoReceiver *receiver : std::as_const(_videoReceivers)) {
135 QGCCorePlugin::instance()->releaseVideoSink(receiver->sink());
136 }
137}
138
139void VideoManager::_cleanupOldVideos()
140{
141 if (!SettingsManager::instance()->videoSettings()->enableStorageLimit()->rawValue().toBool()) {
142 return;
143 }
144
145 const QString savePath = SettingsManager::instance()->appSettings()->videoSavePath();
146 QDir videoDir = QDir(savePath);
147 videoDir.setFilter(QDir::Files | QDir::Readable | QDir::NoSymLinks | QDir::Writable);
148 videoDir.setSorting(QDir::Time);
149
150 QStringList nameFilters;
151 for (size_t i = 0; i < std::size(kFileExtension); i++) {
152 nameFilters << QStringLiteral("*.") + kFileExtension[i];
153 }
154
155 videoDir.setNameFilters(nameFilters);
156 QFileInfoList vidList = videoDir.entryInfoList();
157 if (vidList.isEmpty()) {
158 return;
159 }
160
161 uint64_t total = 0;
162 for (const QFileInfo &video : std::as_const(vidList)) {
163 total += video.size();
164 }
165
166 const uint64_t maxSize = SettingsManager::instance()->videoSettings()->maxVideoSize()->rawValue().toUInt() * qPow(1024, 2);
167 while ((total >= maxSize) && !vidList.isEmpty()) {
168 const QFileInfo info = vidList.takeLast();
169 total -= info.size();
170 const QString path = info.filePath();
171 qCDebug(VideoManagerLog) << "Removing old video file:" << path;
172 (void) QFile::remove(path);
173 }
174}
175
176void VideoManager::startRecording(const QString &videoFile)
177{
178 const VideoReceiver::FILE_FORMAT fileFormat = static_cast<VideoReceiver::FILE_FORMAT>(_videoSettings->recordingFormat()->rawValue().toInt());
179 if (!VideoReceiver::isValidFileFormat(fileFormat)) {
180 qgcApp()->showAppMessage(tr("Invalid video format defined."));
181 return;
182 }
183
184 _cleanupOldVideos();
185
186 const QString savePath = SettingsManager::instance()->appSettings()->videoSavePath();
187 if (savePath.isEmpty()) {
188 qgcApp()->showAppMessage(tr("Unabled to record video. Video save path must be specified in Settings."));
189 return;
190 }
191
192 const QString videoFileUrl = videoFile.isEmpty() ? QDateTime::currentDateTime().toString("yyyy-MM-dd_hh.mm.ss") : videoFile;
193 const QString ext = kFileExtension[fileFormat];
194
195 const QString videoFileNameTemplate = savePath + "/" + videoFileUrl + ".%1" + ext;
196
197 for (VideoReceiver *receiver : std::as_const(_videoReceivers)) {
198 if (!receiver->started()) {
199 qCDebug(VideoManagerLog) << "Video receiver is not ready.";
200 continue;
201 }
202 const QString streamName = (receiver->name() == QStringLiteral("videoContent")) ? "" : (receiver->name() + ".");
203 const QString videoFileName = videoFileNameTemplate.arg(streamName);
204 receiver->startRecording(videoFileName, fileFormat);
205 }
206}
207
208void VideoManager::stopRecording()
209{
210 for (VideoReceiver *receiver : std::as_const(_videoReceivers)) {
211 receiver->stopRecording();
212 }
213}
214
215void VideoManager::grabImage(const QString &imageFile)
216{
217 if (imageFile.isEmpty()) {
218 _imageFile = SettingsManager::instance()->appSettings()->photoSavePath();
219 _imageFile += QStringLiteral("/") + QDateTime::currentDateTime().toString("yyyy-MM-dd_hh.mm.ss.zzz") + QStringLiteral(".jpg");
220 } else {
221 _imageFile = imageFile;
222 }
223
224 emit imageFileChanged(_imageFile);
225
226 for (VideoReceiver *receiver : std::as_const(_videoReceivers)) {
227 receiver->takeScreenshot(_imageFile);
228 // QSharedPointer<QQuickItemGrabResult> result = receiver->widget()->grabToImage(const QSize &targetSize = QSize())
229 }
230}
231
232double VideoManager::aspectRatio() const
233{
234 for (VideoReceiver *receiver : _videoReceivers) {
235 QGCVideoStreamInfo *pInfo = receiver->videoStreamInfo();
236 if (!receiver->isThermal() && pInfo && !pInfo->isThermal()) {
237 return pInfo->aspectRatio();
238 }
239 }
240
241 // FIXME: use _videoReceiver->videoSize() to calculate AR (if AR is not specified in the settings?)
242 return _videoSettings->aspectRatio()->rawValue().toDouble();
243}
244
245double VideoManager::thermalAspectRatio() const
246{
247 for (VideoReceiver *receiver : _videoReceivers) {
248 QGCVideoStreamInfo *pInfo = receiver->videoStreamInfo();
249 if (receiver->isThermal() && pInfo && pInfo->isThermal()) {
250 return pInfo->aspectRatio();
251 }
252 }
253
254 return 1.0;
255}
256
257double VideoManager::hfov() const
258{
259 for (VideoReceiver *receiver : _videoReceivers) {
260 QGCVideoStreamInfo *pInfo = receiver->videoStreamInfo();
261 if (!receiver->isThermal() && pInfo && !pInfo->isThermal()) {
262 return pInfo->hfov();
263 }
264 }
265
266 return 1.0;
267}
268
269double VideoManager::thermalHfov() const
270{
271 for (VideoReceiver *receiver : _videoReceivers) {
272 QGCVideoStreamInfo *pInfo = receiver->videoStreamInfo();
273 if (receiver->isThermal() && pInfo && pInfo->isThermal()) {
274 return pInfo->hfov();
275 }
276 }
277
278 return _videoSettings->aspectRatio()->rawValue().toDouble();
279}
280
281bool VideoManager::hasThermal() const
282{
283 for (VideoReceiver *receiver : _videoReceivers) {
284 QGCVideoStreamInfo *pInfo = receiver->videoStreamInfo();
285 if (receiver->isThermal() && pInfo && pInfo->isThermal()) {
286 return true;
287 }
288 }
289
290 return false;
291}
292
293bool VideoManager::hasVideo() const
294{
295 return (_videoSettings->streamEnabled()->rawValue().toBool() && _videoSettings->streamConfigured());
296}
297
298bool VideoManager::isUvc() const
299{
300 return (!_uvcVideoSourceID.isEmpty() && uvcEnabled() && hasVideo());
301}
302
303bool VideoManager::gstreamerEnabled()
304{
305#ifdef QGC_GST_STREAMING
306 return true;
307#else
308 return false;
309#endif
310}
311
312bool VideoManager::uvcEnabled()
313{
314 return UVCReceiver::enabled();
315}
316
317bool VideoManager::qtmultimediaEnabled()
318{
320}
321
322void VideoManager::setfullScreen(bool on)
323{
324 if (on) {
325 if (!_activeVehicle || _activeVehicle->vehicleLinkManager()->communicationLost()) {
326 on = false;
327 }
328 }
329
330 if (on != _fullScreen) {
331 _fullScreen = on;
332 emit fullScreenChanged();
333 }
334}
335
336bool VideoManager::isStreamSource() const
337{
338 static const QStringList videoSourceList = {
349 };
350 const QString videoSource = _videoSettings->videoSource()->rawValue().toString();
351 return (videoSourceList.contains(videoSource) || autoStreamConfigured());
352}
353
354void VideoManager::_videoSourceChanged()
355{
356 bool changed = false;
357 if (_activeVehicle) {
358 QGCCameraManager* camMgr = _activeVehicle->cameraManager();
359 for (VideoReceiver *receiver : std::as_const(_videoReceivers)) {
360 QGCVideoStreamInfo* info = nullptr;
361 if (receiver->isThermal()) {
362 info = camMgr ? camMgr->thermalStreamInstance() : nullptr;
363 } else {
364 info = camMgr ? camMgr->currentStreamInstance() : nullptr;
365 }
366 // Assign stream info
367 receiver->setVideoStreamInfo(info);
368 changed |= _updateSettings(receiver);
369 }
370 } else {
371 for (VideoReceiver *receiver : std::as_const(_videoReceivers)) {
372 receiver->setVideoStreamInfo(nullptr);
373 changed |= _updateSettings(receiver);
374 }
375 }
376
377 if (changed) {
378 emit hasVideoChanged();
380 emit isAutoStreamChanged();
381
382 if (hasVideo()) {
383 _restartAllVideos();
384 } else {
385 stopVideo();
386 }
387
388 qCDebug(VideoManagerLog) << "New Video Source:" << _videoSettings->videoSource()->rawValue().toString();
389 }
390}
391
392bool VideoManager::_updateUVC(VideoReceiver * /*receiver*/)
393{
394 bool result = false;
395
396 const QString oldUvcVideoSrcID = _uvcVideoSourceID;
397
398 if (!uvcEnabled() || !hasVideo() || isStreamSource()) {
399 _uvcVideoSourceID = QString();
400 } else {
401 _uvcVideoSourceID = UVCReceiver::getSourceId();
402 }
403
404 if (oldUvcVideoSrcID != _uvcVideoSourceID) {
405 qCDebug(VideoManagerLog) << "UVC changed from [" << oldUvcVideoSrcID << "] to [" << _uvcVideoSourceID << "]";
406 if (!_uvcVideoSourceID.isEmpty()) {
408 }
409 result = true;
411 emit isUvcChanged();
412 }
413
414 return result;
415}
416
417bool VideoManager::autoStreamConfigured() const
418{
419 for (VideoReceiver *receiver : _videoReceivers) {
420 QGCVideoStreamInfo *pInfo = receiver->videoStreamInfo();
421 if (!receiver->isThermal() && pInfo && !pInfo->isThermal()) {
422 return !pInfo->uri().isEmpty();
423 }
424 }
425
426 return false;
427}
428
429bool VideoManager::_updateAutoStream(VideoReceiver *receiver)
430{
431 const QGCVideoStreamInfo *pInfo = receiver->videoStreamInfo();
432 if (!pInfo) {
433 return false;
434 }
435
436 qCDebug(VideoManagerLog) << QString("Configure stream (%1):").arg(receiver->name()) << pInfo->uri();
437
438 QString source, url;
439 switch (pInfo->type()) {
440 case VIDEO_STREAM_TYPE_RTSP:
442 url = pInfo->uri();
443 if (source == VideoSettings::videoSourceRTSP) {
444 _videoSettings->rtspUrl()->setRawValue(url);
445 }
446 break;
447 case VIDEO_STREAM_TYPE_TCP_MPEG:
449 url = pInfo->uri();
450 break;
451 case VIDEO_STREAM_TYPE_RTPUDP:
452 if (pInfo->encoding() == VIDEO_STREAM_ENCODING_H265) {
454 url = pInfo->uri().contains("udp265://") ? pInfo->uri() : QStringLiteral("udp265://0.0.0.0:%1").arg(pInfo->uri());
455 } else {
457 url = pInfo->uri().contains("udp://") ? pInfo->uri() : QStringLiteral("udp://0.0.0.0:%1").arg(pInfo->uri());
458 }
459 break;
460 case VIDEO_STREAM_TYPE_MPEG_TS:
462 url = pInfo->uri().contains("mpegts://") ? pInfo->uri() : QStringLiteral("mpegts://0.0.0.0:%1").arg(pInfo->uri());
463 break;
464 default:
465 qCWarning(VideoManagerLog) << "Unknown VIDEO_STREAM_TYPE";
467 url = pInfo->uri();
468 break;
469 }
470
471 const bool settingsChanged = _updateVideoUri(receiver, url);
472 if (settingsChanged) {
473 if (!receiver->isThermal()) {
474 _videoSettings->videoSource()->setRawValue(source);
475 }
476
478 }
479
480 return settingsChanged;
481}
482
483bool VideoManager::_updateVideoUri(VideoReceiver *receiver, const QString &uri)
484{
485 if (!receiver) {
486 qCDebug(VideoManagerLog) << "VideoReceiver is NULL";
487 return false;
488 }
489
490 if ((uri == receiver->uri()) && !receiver->uri().isNull()) {
491 return false;
492 }
493
494 qCDebug(VideoManagerLog) << "New Video URI" << uri;
495
496 receiver->setUri(uri);
497
498 return true;
499}
500
501bool VideoManager::_updateSettings(VideoReceiver *receiver)
502{
503 if (!receiver) {
504 qCDebug(VideoManagerLog) << "VideoReceiver is NULL";
505 return false;
506 }
507
508 bool settingsChanged = false;
509
510 const bool lowLatency = _videoSettings->lowLatencyMode()->rawValue().toBool();
511 if (lowLatency != receiver->lowLatency()) {
512 receiver->setLowLatency(lowLatency);
513 settingsChanged = true;
514 }
515
516 if (receiver->isThermal()) {
517 return settingsChanged;
518 }
519
520 settingsChanged |= _updateUVC(receiver);
521 settingsChanged |= _updateAutoStream(receiver);
522
523 const QString source = _videoSettings->videoSource()->rawValue().toString();
524 if (source == VideoSettings::videoSourceUDPH264) {
525 settingsChanged |= _updateVideoUri(receiver, QStringLiteral("udp://%1").arg(_videoSettings->udpUrl()->rawValue().toString()));
526 } else if (source == VideoSettings::videoSourceUDPH265) {
527 settingsChanged |= _updateVideoUri(receiver, QStringLiteral("udp265://%1").arg(_videoSettings->udpUrl()->rawValue().toString()));
528 } else if (source == VideoSettings::videoSourceMPEGTS) {
529 settingsChanged |= _updateVideoUri(receiver, QStringLiteral("mpegts://%1").arg(_videoSettings->udpUrl()->rawValue().toString()));
530 } else if (source == VideoSettings::videoSourceRTSP) {
531 settingsChanged |= _updateVideoUri(receiver, _videoSettings->rtspUrl()->rawValue().toString());
532 } else if (source == VideoSettings::videoSourceTCP) {
533 settingsChanged |= _updateVideoUri(receiver, QStringLiteral("tcp://%1").arg(_videoSettings->tcpUrl()->rawValue().toString()));
534 } else if (source == VideoSettings::videoSource3DRSolo) {
535 settingsChanged |= _updateVideoUri(receiver, QStringLiteral("udp://0.0.0.0:5600"));
536 } else if (source == VideoSettings::videoSourceParrotDiscovery) {
537 settingsChanged |= _updateVideoUri(receiver, QStringLiteral("udp://0.0.0.0:8888"));
538 } else if (source == VideoSettings::videoSourceYuneecMantisG) {
539 settingsChanged |= _updateVideoUri(receiver, QStringLiteral("rtsp://192.168.42.1:554/live"));
540 } else if (source == VideoSettings::videoSourceHerelinkAirUnit) {
541 settingsChanged |= _updateVideoUri(receiver, QStringLiteral("rtsp://192.168.0.10:8554/H264Video"));
542 } else if (source == VideoSettings::videoSourceHerelinkHotspot) {
543 settingsChanged |= _updateVideoUri(receiver, QStringLiteral("rtsp://192.168.43.1:8554/fpv_stream"));
544 } else if ((source == VideoSettings::videoDisabled) || (source == VideoSettings::videoSourceNoVideo)) {
545 settingsChanged |= _updateVideoUri(receiver, QString());
546 } else {
547 settingsChanged |= _updateVideoUri(receiver, QString());
548 if (!isUvc()) {
549 qCCritical(VideoManagerLog) << "Video source URI \"" << source << "\" is not supported. Please add support!";
550 }
551 }
552
553 return settingsChanged;
554}
555
556void VideoManager::_setActiveVehicle(Vehicle *vehicle)
557{
558 qCDebug(VideoManagerLog) << Q_FUNC_INFO << "new vehicle" << vehicle << "old active vehicle" << _activeVehicle;
559
560 if (_activeVehicle) {
561 (void) disconnect(_activeVehicle->vehicleLinkManager(), &VehicleLinkManager::communicationLostChanged, this, &VideoManager::_communicationLostChanged);
562 auto cameraManager = _activeVehicle->cameraManager();
563 if (cameraManager) {
564 MavlinkCameraControl *pCamera = cameraManager->currentCameraInstance();
565 if (pCamera) {
566 pCamera->stopStream();
567 }
568 (void) disconnect(cameraManager, &QGCCameraManager::streamChanged, this, &VideoManager::_videoSourceChanged);
569 }
570
571 for (VideoReceiver *receiver : std::as_const(_videoReceivers)) {
572 // disconnect(receiver->videoStreamInfo(), &QGCVideoStreamInfo::infoChanged, ))
573 receiver->setVideoStreamInfo(nullptr);
574 }
575 }
576
577 _activeVehicle = vehicle;
578 if (_activeVehicle) {
579 (void) connect(_activeVehicle->vehicleLinkManager(), &VehicleLinkManager::communicationLostChanged, this, &VideoManager::_communicationLostChanged);
580 if (_activeVehicle->cameraManager()) {
581 (void) connect(_activeVehicle->cameraManager(), &QGCCameraManager::streamChanged, this, &VideoManager::_videoSourceChanged);
582 MavlinkCameraControl *pCamera = _activeVehicle->cameraManager()->currentCameraInstance();
583 if (pCamera) {
584 pCamera->resumeStream();
585 }
586 }
587
588 for (VideoReceiver *receiver : std::as_const(_videoReceivers)) {
589 if (_activeVehicle->cameraManager()) {
590 if (receiver->isThermal()) {
591 receiver->setVideoStreamInfo(_activeVehicle->cameraManager()->thermalStreamInstance());
592 } else {
593 receiver->setVideoStreamInfo(_activeVehicle->cameraManager()->currentStreamInstance());
594 }
595 } else {
596 receiver->setVideoStreamInfo(nullptr);
597 }
598 // connect(receiver->videoStreamInfo(), &QGCVideoStreamInfo::infoChanged, ))
599 }
600 } else {
601 setfullScreen(false);
602 }
603}
604
605void VideoManager::_communicationLostChanged(bool connectionLost)
606{
607 if (connectionLost) {
608 setfullScreen(false);
609 }
610}
611
612void VideoManager::_restartAllVideos()
613{
614 for (VideoReceiver *videoReceiver : std::as_const(_videoReceivers)) {
615 _restartVideo(videoReceiver);
616 }
617}
618
619void VideoManager::_restartVideo(VideoReceiver *receiver)
620{
621 if (!receiver) {
622 qCDebug(VideoManagerLog) << "VideoReceiver is NULL";
623 return;
624 }
625
626 qCDebug(VideoManagerLog) << "Restart video receiver" << receiver->name();
627
628 if (receiver->started()) {
629 _stopReceiver(receiver);
630 // onStopComplete Signal Will Restart It
631 } else {
632 _startReceiver(receiver);
633 }
634}
635
636void VideoManager::_stopReceiver(VideoReceiver *receiver)
637{
638 if (!receiver) {
639 qCDebug(VideoManagerLog) << "VideoReceiver is NULL";
640 return;
641 }
642
643 if (receiver->started()) {
644 receiver->stop();
645 }
646}
647
648void VideoManager::stopVideo()
649{
650 for (VideoReceiver *receiver : std::as_const(_videoReceivers)) {
651 _stopReceiver(receiver);
652 }
653}
654
655void VideoManager::_startReceiver(VideoReceiver *receiver)
656{
657 if (!receiver) {
658 qCDebug(VideoManagerLog) << "VideoReceiver is NULL";
659 return;
660 }
661
662 if (receiver->started()) {
663 qCDebug(VideoManagerLog) << "VideoReceiver is already started" << receiver->name();
664 return;
665 }
666
667 if (receiver->uri().isEmpty()) {
668 qCDebug(VideoManagerLog) << "VideoUri is NULL" << receiver->name();
669 return;
670 }
671
672 const QString source = _videoSettings->videoSource()->rawValue().toString();
673 /* The gstreamer rtsp source will switch to tcp if udp is not available after 5 seconds.
674 So we should allow for some negotiation time for rtsp */
675
676 const uint32_t timeout = ((source == VideoSettings::videoSourceRTSP) ? _videoSettings->rtspTimeout()->rawValue().toUInt() : 3);
677
678 receiver->start(timeout);
679}
680
681void VideoManager::_initVideoReceiver(VideoReceiver *receiver, QQuickWindow *window)
682{
683 if (_videoReceivers.contains(receiver)) {
684 qCWarning(VideoManagerLog) << "Receiver already initialized";
685 }
686
687 QQuickItem *widget = window->findChild<QQuickItem*>(receiver->name());
688 if (!widget) {
689 qCCritical(VideoManagerLog) << "stream widget not found" << receiver->name();
690 }
691 receiver->setWidget(widget);
692
693 void *sink = QGCCorePlugin::instance()->createVideoSink(receiver->widget(), receiver);
694 if (!sink) {
695 qCCritical(VideoManagerLog) << "createVideoSink() failed" << receiver->name();
696 }
697 receiver->setSink(sink);
698
699 (void) connect(receiver, &VideoReceiver::onStartComplete, this, [this, receiver](VideoReceiver::STATUS status) {
700 if (!receiver) {
701 return;
702 }
703
704 qCDebug(VideoManagerLog) << "Video" << receiver->name() << "Start complete, status:" << status;
705 switch (status) {
707 receiver->setStarted(true);
708 if (receiver->sink()) {
709 receiver->startDecoding(receiver->sink());
710 }
711 break;
714 break;
715 default:
716 _restartVideo(receiver);
717 break;
718 }
719 });
720
721 (void) connect(receiver, &VideoReceiver::onStopComplete, this, [this, receiver](VideoReceiver::STATUS status) {
722 qCDebug(VideoManagerLog) << "Stop complete" << receiver->name() << receiver->uri() << ", status:" << status;
723 receiver->setStarted(false);
724 if (status == VideoReceiver::STATUS_INVALID_URL) {
725 qCDebug(VideoManagerLog) << "Invalid video URL. Not restarting";
726 } else {
727 QTimer::singleShot(1000, receiver, [this, receiver]() {
728 qCDebug(VideoManagerLog) << "Restarting video receiver" << receiver->name() << receiver->uri();
729 _startReceiver(receiver);
730 });
731 }
732 });
733
734 (void) connect(receiver, &VideoReceiver::streamingChanged, this, [this, receiver](bool active) {
735 qCDebug(VideoManagerLog) << "Video" << receiver->name() << "streaming changed, active:" << (active ? "yes" : "no");
736 if (!receiver->isThermal()) {
737 _streaming = active;
738 emit streamingChanged();
739 }
740 });
741
742 (void) connect(receiver, &VideoReceiver::decodingChanged, this, [this, receiver](bool active) {
743 qCDebug(VideoManagerLog) << "Video" << receiver->name() << "decoding changed, active:" << (active ? "yes" : "no");
744 if (!receiver->isThermal()) {
745 _decoding = active;
746 emit decodingChanged();
747 }
748 });
749
750 (void) connect(receiver, &VideoReceiver::recordingChanged, this, [this, receiver](bool active) {
751 qCDebug(VideoManagerLog) << "Video" << receiver->name() << "recording changed, active:" << (active ? "yes" : "no");
752 if (!receiver->isThermal()) {
753 _recording = active;
754 if (!active) {
755 _subtitleWriter->stopCapturingTelemetry();
756 }
757 emit recordingChanged(_recording);
758 }
759 });
760
761 (void) connect(receiver, &VideoReceiver::recordingStarted, this, [this, receiver](const QString &filename) {
762 qCDebug(VideoManagerLog) << "Video" << receiver->name() << "recording started";
763 if (!receiver->isThermal()) {
764 _subtitleWriter->startCapturingTelemetry(filename, videoSize());
765 }
766 });
767
768 (void) connect(receiver, &VideoReceiver::videoSizeChanged, this, [this, receiver](QSize size) {
769 qCDebug(VideoManagerLog) << "Video" << receiver->name() << "resized. New resolution:" << size.width() << "x" << size.height();
770 if (!receiver->isThermal()) {
771 _videoSize = size;
772 emit videoSizeChanged();
773 }
774 });
775
776 (void) connect(receiver, &VideoReceiver::onTakeScreenshotComplete, this, [receiver](VideoReceiver::STATUS status) {
777 if (status == VideoReceiver::STATUS_OK) {
778 qCDebug(VideoManagerLog) << "Video" << receiver->name() << "screenshot taken";
779 } else {
780 qCWarning(VideoManagerLog) << "Video" << receiver->name() << "screenshot failed";
781 }
782 });
783
784 (void) connect(receiver, &VideoReceiver::videoStreamInfoChanged, this, [this, receiver]() {
785 const QGCVideoStreamInfo *videoStreamInfo = receiver->videoStreamInfo();
786 qCDebug(VideoManagerLog) << "Video" << receiver->name() << "stream info:" << (videoStreamInfo ? "received" : "lost");
787
788 (void) _updateAutoStream(receiver);
789 });
790
791 (void) _updateSettings(receiver);
792
793 _videoReceivers.append(receiver);
794
795 if (hasVideo()) {
796 _startReceiver(receiver);
797 }
798}
799
800void VideoManager::startVideo()
801{
802 qCDebug(VideoManagerLog) << "startVideo";
803
804 if (!hasVideo()) {
805 qCDebug(VideoManagerLog) << "Stream not enabled/configured";
806 return;
807 }
808
809 _restartAllVideos();
810}
811
812/*===========================================================================*/
813
815 : QRunnable()
816{
817 // qCDebug(VideoManagerLog) << this;
818}
819
821{
822 // qCDebug(VideoManagerLog) << this;
823}
824
826{
827 qCDebug(VideoManagerLog) << "FinishVideoInitialization::run";
828 QMetaObject::invokeMethod(VideoManager::instance(), &VideoManager::_initAfterQmlIsReady, Qt::QueuedConnection);
829}
#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 void resumeStream()=0
virtual void stopStream()=0
void activeVehicleChanged(Vehicle *activeVehicle)
Camera Manager.
Encapsulates the contents of a VIDEO_STREAM_INFORMATION message.
Provides access to all app settings.
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
VehicleLinkManager * vehicleLinkManager()
Definition Vehicle.h:580
void decodingChanged()
friend class FinishVideoInitialization
void hasVideoChanged()
void uvcVideoSourceIDChanged()
void isStreamSourceChanged()
void autoStreamConfiguredChanged()
void streamingChanged()
void fullScreenChanged()
void isUvcChanged()
void imageFileChanged(const QString &filename)
void recordingChanged(bool recording)
void isAutoStreamChanged()
void videoSizeChanged()
void aspectRatioChanged()
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
Fact *rtspUrl READ rtspUrl CONSTANT Fact * rtspUrl()
static constexpr const char * videoSourceParrotDiscovery
static constexpr const char * videoSourceTCP
Fact *recordingFormat READ recordingFormat CONSTANT Fact * recordingFormat()
static constexpr const char * videoSourceUDPH264
static constexpr const char * videoSourceHerelinkHotspot
Fact *aspectRatio READ aspectRatio CONSTANT Fact * aspectRatio()
static constexpr const char * videoSourceRTSP
Fact *streamEnabled READ streamEnabled CONSTANT Fact * streamEnabled()
Fact *rtspTimeout READ rtspTimeout CONSTANT Fact * rtspTimeout()
static constexpr const char * videoDisabled
Fact *maxVideoSize READ maxVideoSize CONSTANT Fact * maxVideoSize()
Fact *udpUrl READ udpUrl CONSTANT Fact * udpUrl()
Fact *tcpUrl READ tcpUrl CONSTANT Fact * tcpUrl()
Fact *videoSource READ videoSource CONSTANT Fact * videoSource()
static constexpr const char * videoSourceYuneecMantisG
static constexpr const char * videoSourceUDPH265
static constexpr const char * videoSourceNoVideo
Fact *lowLatencyMode READ lowLatencyMode CONSTANT Fact * lowLatencyMode()
static constexpr const char * videoSourceMPEGTS
static constexpr const char * videoSourceHerelinkAirUnit
bool initialize()
Definition GStreamer.cc:490