Newer
Older
/****************************************************************************
*
* (c) 2009-2020 QGROUNDCONTROL PROJECT <http://www.qgroundcontrol.org>
*
* QGroundControl is licensed according to the terms in the file
* COPYING.md in the root of the source code directory.
*
****************************************************************************/
#include <QQmlContext>
#include <QQmlEngine>
#include <QSettings>
#include "ScreenToolsController.h"
#include "VideoManager.h"
#include "QGCToolbox.h"
#include "QGCCorePlugin.h"
#include "QGCOptions.h"
#include "Settings/SettingsManager.h"
#include "QGCCameraManager.h"
#if defined(QGC_GST_STREAMING)
#include "GStreamer.h"
#else
#include "GLVideoItemStub.h"
#endif
#ifdef QGC_GST_TAISYNC_ENABLED
#include "TaisyncHandler.h"
#endif
QGC_LOGGING_CATEGORY(VideoManagerLog, "VideoManagerLog")
static const char* kFileExtension[VideoReceiver::FILE_FORMAT_MAX - VideoReceiver::FILE_FORMAT_MIN] = {
"mkv",
"mov",
"mp4"
};
//-----------------------------------------------------------------------------
VideoManager::VideoManager(QGCApplication* app, QGCToolbox* toolbox)
: QGCTool(app, toolbox)
#if !defined(QGC_GST_STREAMING)
static bool once = false;
if (!once) {
qmlRegisterType<GLVideoItemStub>("org.freedesktop.gstreamer.GLVideoItem", 1, 0, "GstGLVideoItem");
once = true;
}
#endif
}
//-----------------------------------------------------------------------------
VideoManager::~VideoManager()
{
delete _videoReceiver;
_videoReceiver = nullptr;
delete _thermalVideoReceiver;
_thermalVideoReceiver = nullptr;
#if defined(QGC_GST_STREAMING)
GStreamer::releaseVideoSink(_thermalVideoSink);
_thermalVideoSink = nullptr;
GStreamer::releaseVideoSink(_videoSink);
_videoSink = nullptr;
}
//-----------------------------------------------------------------------------
void
VideoManager::setToolbox(QGCToolbox *toolbox)
{
QGCTool::setToolbox(toolbox);
QQmlEngine::setObjectOwnership(this, QQmlEngine::CppOwnership);
qmlRegisterUncreatableType<VideoManager> ("QGroundControl.VideoManager", 1, 0, "VideoManager", "Reference only");
qmlRegisterUncreatableType<VideoReceiver>("QGroundControl", 1, 0, "VideoReceiver","Reference only");
// TODO: Those connections should be Per Video, not per VideoManager.
_videoSettings = toolbox->settingsManager()->videoSettings();
QString videoSource = _videoSettings->videoSource()->rawValue().toString();
connect(_videoSettings->videoSource(), &Fact::rawValueChanged, this, &VideoManager::_videoSourceChanged);
connect(_videoSettings->udpPort(), &Fact::rawValueChanged, this, &VideoManager::_udpPortChanged);
connect(_videoSettings->rtspUrl(), &Fact::rawValueChanged, this, &VideoManager::_rtspUrlChanged);
connect(_videoSettings->tcpUrl(), &Fact::rawValueChanged, this, &VideoManager::_tcpUrlChanged);
connect(_videoSettings->aspectRatio(), &Fact::rawValueChanged, this, &VideoManager::_aspectRatioChanged);
connect(_videoSettings->lowLatencyMode(),&Fact::rawValueChanged, this, &VideoManager::_lowLatencyModeChanged);
MultiVehicleManager *pVehicleMgr = qgcApp()->toolbox()->multiVehicleManager();
connect(pVehicleMgr, &MultiVehicleManager::activeVehicleChanged, this, &VideoManager::_setActiveVehicle);
#if defined(QGC_GST_STREAMING)
#ifndef QGC_DISABLE_UVC
// If we are using a UVC camera setup the device name
emit isGStreamerChanged();
qCDebug(VideoManagerLog) << "New Video Source:" << videoSource;
_videoReceiver = toolbox->corePlugin()->createVideoReceiver(this);
_thermalVideoReceiver = toolbox->corePlugin()->createVideoReceiver(this);
connect(_videoReceiver, &VideoReceiver::timeout, this, [this](){
if (!_enableVideoRestart) return;
_startReceiver(0);
});
connect(_videoReceiver, &VideoReceiver::streamingChanged, this, [this](){
if (!_enableVideoRestart || _videoReceiver->streaming()) return;
_startReceiver(0);
});
connect(_videoReceiver, &VideoReceiver::recordingStarted, this, &VideoManager::_recordingStarted);
connect(_videoReceiver, &VideoReceiver::recordingChanged, this, &VideoManager::_recordingChanged);
connect(_videoReceiver, &VideoReceiver::onTakeScreenshotComplete, this, &VideoManager::_onTakeScreenshotComplete);
// FIXME: AV: I believe _thermalVideoReceiver should be handled just like _videoReceiver in terms of event
// and I expect that it will be changed during multiple video stream activity
if (_thermalVideoReceiver != nullptr) {
connect(_thermalVideoReceiver, &VideoReceiver::timeout, this, [this](){
if (!_enableVideoRestart) return;
_startReceiver(1);
});
connect(_thermalVideoReceiver, &VideoReceiver::streamingChanged, this, [this](){
if (!_enableVideoRestart) return;
_startReceiver(1);
});
}
_updateSettings();
if(isGStreamer()) {
#endif
void VideoManager::_cleanupOldVideos()
{
#if defined(QGC_GST_STREAMING)
//-- Only perform cleanup if storage limit is enabled
if(!_videoSettings->enableStorageLimit()->rawValue().toBool()) {
return;
}
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 < sizeof(kFileExtension) / sizeof(kFileExtension[0]); i += 1) {
nameFilters << QString("*.") + kFileExtension[i];
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
uint64_t maxSize = _videoSettings->maxVideoSize()->rawValue().toUInt() * 1024 * 1024;
//-- 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();
}
}
#endif
}
//-----------------------------------------------------------------------------
void
VideoManager::startVideo()
{
if (qgcApp()->runningUnitTests()) {
return;
}
if(!_videoSettings->streamEnabled()->rawValue().toBool() || !_videoSettings->streamConfigured()) {
qCDebug(VideoManagerLog) << "Stream not enabled/configured";
_startReceiver(0);
_startReceiver(1);
}
//-----------------------------------------------------------------------------
void
VideoManager::stopVideo()
{
if (qgcApp()->runningUnitTests()) {
return;
}
_stopReceiver(1);
_stopReceiver(0);
void
VideoManager::startRecording(const QString& videoFile)
{
if (qgcApp()->runningUnitTests()) {
return;
}
if (!_videoReceiver) {
return;
}
const VideoReceiver::FILE_FORMAT fileFormat = static_cast<VideoReceiver::FILE_FORMAT>(_videoSettings->recordingFormat()->rawValue().toInt());
if(fileFormat < VideoReceiver::FILE_FORMAT_MIN || fileFormat >= VideoReceiver::FILE_FORMAT_MAX) {
return;
}
//-- Disk usage maintenance
_cleanupOldVideos();
QString savePath = qgcApp()->toolbox()->settingsManager()->appSettings()->videoSavePath();
if(savePath.isEmpty()) {
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)
+ "." + kFileExtension[fileFormat - VideoReceiver::FILE_FORMAT_MIN];
_videoReceiver->startRecording(_videoFile, fileFormat);
#else
Q_UNUSED(videoFile)
#endif
}
void
VideoManager::stopRecording()
{
if (qgcApp()->runningUnitTests()) {
return;
}
if (!_videoReceiver) {
return;
}
_videoReceiver->stopRecording();
}
void
VideoManager::grabImage(const QString& imageFile)
{
if (qgcApp()->runningUnitTests()) {
return;
}
if (!_videoReceiver) {
return;
}
_imageFile = imageFile;
emit imageFileChanged();
_videoReceiver->takeScreenshot(_imageFile);
#else
Q_UNUSED(imageFile)
#endif
//-----------------------------------------------------------------------------
double VideoManager::aspectRatio()
{
if(_activeVehicle && _activeVehicle->dynamicCameras()) {
QGCVideoStreamInfo* pInfo = _activeVehicle->dynamicCameras()->currentStreamInstance();
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?)
310
311
312
313
314
315
316
317
318
319
320
321
322
323
324
325
326
327
328
329
330
331
332
333
334
335
336
337
338
339
340
341
342
return _videoSettings->aspectRatio()->rawValue().toDouble();
}
//-----------------------------------------------------------------------------
double VideoManager::thermalAspectRatio()
{
if(_activeVehicle && _activeVehicle->dynamicCameras()) {
QGCVideoStreamInfo* pInfo = _activeVehicle->dynamicCameras()->thermalStreamInstance();
if(pInfo) {
qCDebug(VideoManagerLog) << "Thermal AR: " << pInfo->aspectRatio();
return pInfo->aspectRatio();
}
}
return 1.0;
}
//-----------------------------------------------------------------------------
double VideoManager::hfov()
{
if(_activeVehicle && _activeVehicle->dynamicCameras()) {
QGCVideoStreamInfo* pInfo = _activeVehicle->dynamicCameras()->currentStreamInstance();
if(pInfo) {
return pInfo->hfov();
}
}
return 1.0;
}
//-----------------------------------------------------------------------------
double VideoManager::thermalHfov()
{
if(_activeVehicle && _activeVehicle->dynamicCameras()) {
QGCVideoStreamInfo* pInfo = _activeVehicle->dynamicCameras()->thermalStreamInstance();
if(pInfo) {
return pInfo->aspectRatio();
}
}
return _videoSettings->aspectRatio()->rawValue().toDouble();
}
//-----------------------------------------------------------------------------
bool
VideoManager::hasThermal()
{
if(_activeVehicle && _activeVehicle->dynamicCameras()) {
QGCVideoStreamInfo* pInfo = _activeVehicle->dynamicCameras()->thermalStreamInstance();
if(pInfo) {
return true;
}
}
return false;
}
//-----------------------------------------------------------------------------
QString
VideoManager::imageFile()
{
return _imageFile;
}
//-----------------------------------------------------------------------------
bool
VideoManager::autoStreamConfigured()
{
if(_activeVehicle && _activeVehicle->dynamicCameras()) {
QGCVideoStreamInfo* pInfo = _activeVehicle->dynamicCameras()->currentStreamInstance();
if(pInfo) {
return !pInfo->uri().isEmpty();
//-----------------------------------------------------------------------------
void
VideoManager::_updateUVC()
{
#ifndef QGC_DISABLE_UVC
QString videoSource = _videoSettings->videoSource()->rawValue().toString();
QList<QCameraInfo> cameras = QCameraInfo::availableCameras();
for (const QCameraInfo &cameraInfo: cameras) {
if(cameraInfo.description() == videoSource) {
_videoSourceID = cameraInfo.deviceName();
emit videoSourceIDChanged();
qCDebug(VideoManagerLog) << "Found USB source:" << _videoSourceID << " Name:" << videoSource;
break;
}
}
#endif
}
//-----------------------------------------------------------------------------
void
VideoManager::_videoSourceChanged()
emit hasVideoChanged();
emit isGStreamerChanged();
//-----------------------------------------------------------------------------
void
VideoManager::_udpPortChanged()
//-----------------------------------------------------------------------------
void
//-----------------------------------------------------------------------------
void
VideoManager::_tcpUrlChanged()
{
//-----------------------------------------------------------------------------
void
VideoManager::_lowLatencyModeChanged()
{
//-----------------------------------------------------------------------------
bool
VideoManager::hasVideo()
{
if(autoStreamConfigured()) {
return true;
}
QString videoSource = _videoSettings->videoSource()->rawValue().toString();
return !videoSource.isEmpty() && videoSource != VideoSettings::videoSourceNoVideo && videoSource != VideoSettings::videoDisabled;
}
//-----------------------------------------------------------------------------
bool
VideoManager::isGStreamer()
{
#if defined(QGC_GST_STREAMING)
QString videoSource = _videoSettings->videoSource()->rawValue().toString();
videoSource == VideoSettings::videoSourceUDPH264 ||
videoSource == VideoSettings::videoSourceUDPH265 ||
videoSource == VideoSettings::videoSourceRTSP ||
videoSource == VideoSettings::videoSourceTCP ||
videoSource == VideoSettings::videoSourceMPEGTS ||
autoStreamConfigured();
#else
return false;
#endif
}
//-----------------------------------------------------------------------------
#ifndef QGC_DISABLE_UVC
bool
VideoManager::uvcEnabled()
{
return QCameraInfo::availableCameras().count() > 0;
}
#endif
//-----------------------------------------------------------------------------
void
VideoManager::setfullScreen(bool f)
{
if(f) {
//-- No can do if no vehicle or connection lost
if(!_activeVehicle || _activeVehicle->connectionLost()) {
f = false;
}
}
_fullScreen = f;
emit fullScreenChanged();
}
void
VideoManager::_initVideo()
{
#if defined(QGC_GST_STREAMING)
Andrew Voznytsa
committed
QQuickItem* root = qgcApp()->mainRootWindow();
if (root == nullptr) {
qCDebug(VideoManagerLog) << "mainRootWindow() failed. No root window";
Andrew Voznytsa
committed
return;
}
QQuickItem* widget = root->findChild<QQuickItem*>("videoContent");
if (widget != nullptr && _videoReceiver != nullptr) {
if ((_videoSink = qgcApp()->toolbox()->corePlugin()->createVideoSink(this, widget)) != nullptr) {
_videoReceiver->startDecoding(_videoSink);
} else {
qCDebug(VideoManagerLog) << "createVideoSink() failed";
Andrew Voznytsa
committed
} else {
qCDebug(VideoManagerLog) << "video receiver disabled";
Andrew Voznytsa
committed
}
widget = root->findChild<QQuickItem*>("thermalVideo");
if (widget != nullptr && _thermalVideoReceiver != nullptr) {
if ((_thermalVideoSink = qgcApp()->toolbox()->corePlugin()->createVideoSink(this, widget)) != nullptr) {
_thermalVideoReceiver->startDecoding(_thermalVideoSink);
} else {
qCDebug(VideoManagerLog) << "createVideoSink() failed";
Andrew Voznytsa
committed
} else {
qCDebug(VideoManagerLog) << "thermal video receiver disabled";
Andrew Voznytsa
committed
}
//-----------------------------------------------------------------------------
if(_activeVehicle && _activeVehicle->dynamicCameras()) {
Matej Frančeškin
committed
QGCVideoStreamInfo* pInfo = _activeVehicle->dynamicCameras()->currentStreamInstance();
qCDebug(VideoManagerLog) << "Configure primary stream: " << pInfo->uri();
switch(pInfo->type()) {
case VIDEO_STREAM_TYPE_RTSP:
if (status = _updateVideoUri(pInfo->uri())) {
_toolbox->settingsManager()->videoSettings()->videoSource()->setRawValue(VideoSettings::videoSourceRTSP);
}
Gus Grubba
committed
break;
case VIDEO_STREAM_TYPE_TCP_MPEG:
if (status = _updateVideoUri(pInfo->uri())) {
_toolbox->settingsManager()->videoSettings()->videoSource()->setRawValue(VideoSettings::videoSourceTCP);
}
break;
case VIDEO_STREAM_TYPE_RTPUDP:
if (status = _updateVideoUri(QStringLiteral("udp://0.0.0.0:%1").arg(pInfo->uri()))) {
_toolbox->settingsManager()->videoSettings()->videoSource()->setRawValue(VideoSettings::videoSourceUDPH264);
}
break;
case VIDEO_STREAM_TYPE_MPEG_TS_H264:
if (status = _updateVideoUri(QStringLiteral("mpegts://0.0.0.0:%1").arg(pInfo->uri()))) {
_toolbox->settingsManager()->videoSettings()->videoSource()->setRawValue(VideoSettings::videoSourceMPEGTS);
}
status = _updateVideoUri(pInfo->uri());
//-- Thermal stream (if any)
QGCVideoStreamInfo* pTinfo = _activeVehicle->dynamicCameras()->thermalStreamInstance();
if(pTinfo) {
qCDebug(VideoManagerLog) << "Configure secondary stream: " << pTinfo->uri();
switch(pTinfo->type()) {
case VIDEO_STREAM_TYPE_RTSP:
case VIDEO_STREAM_TYPE_TCP_MPEG:
status |= _updateThermalVideoUri(pTinfo->uri());
break;
case VIDEO_STREAM_TYPE_RTPUDP:
status |= _updateThermalVideoUri(QStringLiteral("udp://0.0.0.0:%1").arg(pTinfo->uri()));
break;
case VIDEO_STREAM_TYPE_MPEG_TS_H264:
status |= _updateThermalVideoUri(QStringLiteral("mpegts://0.0.0.0:%1").arg(pTinfo->uri()));
status |= _updateThermalVideoUri(pTinfo->uri());
QString source = _videoSettings->videoSource()->rawValue().toString();
return _updateVideoUri(QStringLiteral("udp://0.0.0.0:%1").arg(_videoSettings->udpPort()->rawValue().toInt()));
else if (source == VideoSettings::videoSourceUDPH265)
return _updateVideoUri(QStringLiteral("udp265://0.0.0.0:%1").arg(_videoSettings->udpPort()->rawValue().toInt()));
else if (source == VideoSettings::videoSourceMPEGTS)
return _updateVideoUri(QStringLiteral("mpegts://0.0.0.0:%1").arg(_videoSettings->udpPort()->rawValue().toInt()));
else if (source == VideoSettings::videoSourceRTSP)
return _updateVideoUri(_videoSettings->rtspUrl()->rawValue().toString());
else if (source == VideoSettings::videoSourceTCP)
return _updateVideoUri(QStringLiteral("tcp://%1").arg(_videoSettings->tcpUrl()->rawValue().toString()));
bool
VideoManager::_updateVideoUri(const QString& uri)
{
#if defined(QGC_GST_TAISYNC_ENABLED) && (defined(__android__) || defined(__ios__))
//-- Taisync on iOS or Android sends a raw h.264 stream
if (isTaisync()) {
return _updateVideoUri(QString("tsusb://0.0.0.0:%1").arg(TAISYNC_VIDEO_UDP_PORT));
if (uri == _videoUri) {
return false;
}
VideoManager::_updateThermalVideoUri(const QString& uri)
{
#if defined(QGC_GST_TAISYNC_ENABLED) && (defined(__android__) || defined(__ios__))
//-- Taisync on iOS or Android sends a raw h.264 stream
if (isTaisync()) {
// FIXME: AV: TAISYNC_VIDEO_UDP_PORT is used by video stream, thermal stream should go via its own proxy
if (!_thermalVideoUri.isEmpty()) {
_thermalVideoUri.clear();
return true;
} else {
return false;
}
if (uri == _thermalVideoUri) {
return false;
//-----------------------------------------------------------------------------
VideoManager::_restartVideo()
if (!_updateSettings()) {
qCDebug(VideoManagerLog) << "No sense to restart video streaming, skipped";
return;
}
qCDebug(VideoManagerLog) << "Restart video streaming";
if (!_enableVideoRestart) {
_enableVideoRestart = true;
_startReceiver(0);
_startReceiver(1);
} else {
_stopReceiver(1);
_stopReceiver(0);
}
//-----------------------------------------------------------------------------
void
VideoManager::_recordingStarted()
{
_subtitleWriter.startCapturingTelemetry(_videoFile);
}
//-----------------------------------------------------------------------------
void
VideoManager::_recordingChanged()
{
if (_videoReceiver && !_videoReceiver->recording()) {
_subtitleWriter.stopCapturingTelemetry();
}
}
//----------------------------------------------------------------------------------------
void
VideoManager::_onTakeScreenshotComplete(VideoReceiver::STATUS status)
695
696
697
698
699
700
701
702
703
704
705
706
707
708
709
710
711
712
713
714
715
716
717
718
719
720
721
722
723
724
725
726
727
728
729
730
731
732
//----------------------------------------------------------------------------------------
void
VideoManager::_startReceiver(unsigned id)
{
#if defined(QGC_GST_STREAMING)
const unsigned timeout = _videoSettings->rtspTimeout()->rawValue().toUInt();
if (id == 0 && _videoReceiver != nullptr) {
_videoReceiver->start(_videoUri, timeout);
if (_videoSink != nullptr) {
_videoReceiver->startDecoding(_videoSink);
}
} else if (id == 1 && _thermalVideoReceiver != nullptr) {
_thermalVideoReceiver->start(_thermalVideoUri, timeout);
if (_thermalVideoSink != nullptr) {
_thermalVideoReceiver->startDecoding(_thermalVideoSink);
}
} else if (id > 1) {
qCDebug(VideoManagerLog) << "Unsupported receiver id" << id;
}
#endif
}
//----------------------------------------------------------------------------------------
void
VideoManager::_stopReceiver(unsigned id)
{
#if defined(QGC_GST_STREAMING)
if (id == 0 && _videoReceiver != nullptr) {
_videoReceiver->stop();
} else if (id == 1 && _thermalVideoReceiver != nullptr){
_thermalVideoReceiver->stop();
} else if (id > 1) {
qCDebug(VideoManagerLog) << "Unsupported receiver id" << id;
}
#endif
}
//----------------------------------------------------------------------------------------
void
VideoManager::_setActiveVehicle(Vehicle* vehicle)
{
if(_activeVehicle) {
disconnect(_activeVehicle, &Vehicle::connectionLostChanged, this, &VideoManager::_connectionLostChanged);
if(_activeVehicle->dynamicCameras()) {
QGCCameraControl* pCamera = _activeVehicle->dynamicCameras()->currentCameraInstance();
if(pCamera) {
pCamera->stopStream();
}
disconnect(_activeVehicle->dynamicCameras(), &QGCCameraManager::streamChanged, this, &VideoManager::_restartVideo);
}
_activeVehicle = vehicle;
if(_activeVehicle) {
connect(_activeVehicle, &Vehicle::connectionLostChanged, this, &VideoManager::_connectionLostChanged);
if(_activeVehicle->dynamicCameras()) {
connect(_activeVehicle->dynamicCameras(), &QGCCameraManager::streamChanged, this, &VideoManager::_restartVideo);
QGCCameraControl* pCamera = _activeVehicle->dynamicCameras()->currentCameraInstance();
if(pCamera) {
pCamera->resumeStream();
}
} else {
//-- Disable full screen video if vehicle is gone
setfullScreen(false);
emit autoStreamConfiguredChanged();
//----------------------------------------------------------------------------------------
void
VideoManager::_connectionLostChanged(bool connectionLost)
{
if(connectionLost) {
//-- Disable full screen video if connection is lost
setfullScreen(false);
}
}
//----------------------------------------------------------------------------------------
void
VideoManager::_aspectRatioChanged()
emit aspectRatioChanged();