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"
QGC_LOGGING_CATEGORY(VideoManagerLog, "VideoManagerLog")
//-----------------------------------------------------------------------------
VideoManager::VideoManager(QGCApplication* app, QGCToolbox* toolbox)
: QGCTool(app, toolbox)
{
}
//-----------------------------------------------------------------------------
VideoManager::~VideoManager()
{
delete _videoReceiver;
_videoReceiver = nullptr;
delete _thermalVideoReceiver;
_thermalVideoReceiver = 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);
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);
_videoReceiver->setUnittestMode(qgcApp()->runningUnitTests());
_thermalVideoReceiver = toolbox->corePlugin()->createVideoReceiver(this);
79
80
81
82
83
84
85
86
87
88
89
90
91
92
93
94
95
96
97
98
99
100
101
102
103
104
105
106
107
108
109
110
111
112
113
114
115
116
117
118
119
120
121
122
123
124
125
126
127
128
129
130
131
132
133
134
135
136
137
138
139
_thermalVideoReceiver->setUnittestMode(qgcApp()->runningUnitTests());
_videoReceiver->moveToThread(qgcApp()->thread());
_thermalVideoReceiver->moveToThread(qgcApp()->thread());
// Those connects are temporary: In a perfect world those connections are going to be done on the Qml
// but because currently the videoReceiver is created in the C++ world, this is easier.
// The fact returning a QVariant is a quite annoying to use proper signal / slot connection.
_updateSettings();
auto appSettings = toolbox->settingsManager()->appSettings();
for (auto *videoReceiver : { _videoReceiver, _thermalVideoReceiver}) {
// First, Setup the current values from the settings.
videoReceiver->setRtspTimeout(_videoSettings->rtspTimeout()->rawValue().toInt());
videoReceiver->setMaxVideoSize(_videoSettings->maxVideoSize()->rawValue().toInt());
videoReceiver->setStreamEnabled(_videoSettings->streamEnabled()->rawValue().toBool());
videoReceiver->setRecordingFormatId(_videoSettings->recordingFormat()->rawValue().toInt());
videoReceiver->setStreamConfigured(_videoSettings->streamConfigured());
videoReceiver->setStorageLimit(_videoSettings->enableStorageLimit()->rawValue().toBool());
connect(_videoSettings->rtspTimeout(), &Fact::rawValueChanged,
videoReceiver, [videoReceiver](const QVariant &value) {
videoReceiver->setRtspTimeout(value.toInt());
}
);
connect(_videoSettings->maxVideoSize(), &Fact::rawValueChanged,
videoReceiver, [videoReceiver](const QVariant &value) {
videoReceiver->setMaxVideoSize(value.toInt());
}
);
connect(_videoSettings->streamEnabled(), &Fact::rawValueChanged,
videoReceiver, [videoReceiver](const QVariant &value) {
videoReceiver->setStreamEnabled(value.toBool());
}
);
connect(_videoSettings->recordingFormat(), &Fact::rawValueChanged,
videoReceiver, [videoReceiver](const QVariant &value) {
videoReceiver->setRecordingFormatId(value.toInt());
}
);
connect(_videoSettings->enableStorageLimit(), &Fact::rawValueChanged,
videoReceiver, [videoReceiver](const QVariant &value) {
videoReceiver->setStorageLimit(value.toInt());
}
);
// Why some options are facts while others aren't?
connect(_videoSettings, &VideoSettings::streamConfiguredChanged, videoReceiver, &VideoReceiver::setStreamConfigured);
// Fix those.
// connect(appSettings, &Fact::rawValueChanged, videoReceiver, &VideoReceiver::setVideoPath);
// connect(appSettings->videoSavePath(), &Fact::rawValueChanged, videoReceiver, &VideoReceiver::setImagePath);
// Connect the video receiver with the rest of the app.
connect(videoReceiver, &VideoReceiver::restartTimeout, this, &VideoManager::restartVideo);
connect(videoReceiver, &VideoReceiver::sendMessage, qgcApp(), &QGCApplication::showMessage);
}
_updateSettings();
if(isGStreamer()) {
_subtitleWriter.setVideoReceiver(_videoReceiver);
#endif
//-----------------------------------------------------------------------------
void
VideoManager::startVideo()
{
if(_videoReceiver) _videoReceiver->start();
if(_thermalVideoReceiver) _thermalVideoReceiver->start();
}
//-----------------------------------------------------------------------------
void
VideoManager::stopVideo()
{
if(_videoReceiver) _videoReceiver->stop();
if(_thermalVideoReceiver) _thermalVideoReceiver->stop();
}
//-----------------------------------------------------------------------------
double VideoManager::aspectRatio()
{
if(_activeVehicle && _activeVehicle->dynamicCameras()) {
QGCVideoStreamInfo* pInfo = _activeVehicle->dynamicCameras()->currentStreamInstance();
172
173
174
175
176
177
178
179
180
181
182
183
184
185
186
187
188
189
190
191
192
193
194
195
196
197
198
199
200
201
202
203
204
205
206
207
208
209
if(pInfo) {
qCDebug(VideoManagerLog) << "Primary AR: " << pInfo->aspectRatio();
return pInfo->aspectRatio();
}
}
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;
}
//-----------------------------------------------------------------------------
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();
Matej Frančeškin
committed
restartVideo();
//-----------------------------------------------------------------------------
void
VideoManager::_udpPortChanged()
Matej Frančeškin
committed
restartVideo();
//-----------------------------------------------------------------------------
void
Matej Frančeškin
committed
restartVideo();
//-----------------------------------------------------------------------------
void
VideoManager::_tcpUrlChanged()
{
Matej Frančeškin
committed
restartVideo();
//-----------------------------------------------------------------------------
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();
}
//-----------------------------------------------------------------------------
#if defined(QGC_GST_STREAMING)
GstElement*
Andrew Voznytsa
committed
VideoManager::_makeVideoSink(gpointer widget)
Andrew Voznytsa
committed
if ((sink = gst_element_factory_make("qgcvideosinkbin", nullptr)) != nullptr) {
g_object_set(sink, "widget", widget, NULL);
} else {
qCritical() << "VideoManager::_makeVideoSink() failed. Error with gst_element_factory_make('qgcvideosinkbin')";
}
return sink;
}
#endif
//-----------------------------------------------------------------------------
void
VideoManager::_initVideo()
{
#if defined(QGC_GST_STREAMING)
Andrew Voznytsa
committed
QQuickItem* root = qgcApp()->mainRootWindow();
if (root == nullptr) {
qCDebug(VideoManagerLog) << "VideoManager::_makeVideoSink() failed. No root window";
return;
}
QQuickItem* widget = root->findChild<QQuickItem*>("videoContent");
if (widget != nullptr) {
_videoReceiver->setVideoSink(_makeVideoSink(widget));
} else {
qCDebug(VideoManagerLog) << "VideoManager::_makeVideoSink() failed. 'videoContent' widget not found";
}
widget = root->findChild<QQuickItem*>("thermalVideo");
if (widget != nullptr) {
_thermalVideoReceiver->setVideoSink(_makeVideoSink(widget));
} else {
qCDebug(VideoManagerLog) << "VideoManager::_makeVideoSink() failed. 'thermalVideo' widget not found";
}
//-----------------------------------------------------------------------------
void
VideoManager::_updateSettings()
{
if(!_videoSettings || !_videoReceiver)
return;
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:
Gus Grubba
committed
_videoReceiver->setUri(pInfo->uri());
_toolbox->settingsManager()->videoSettings()->videoSource()->setRawValue(VideoSettings::videoSourceRTSP);
break;
case VIDEO_STREAM_TYPE_TCP_MPEG:
_videoReceiver->setUri(pInfo->uri());
Gus Grubba
committed
_toolbox->settingsManager()->videoSettings()->videoSource()->setRawValue(VideoSettings::videoSourceTCP);
break;
case VIDEO_STREAM_TYPE_RTPUDP:
_videoReceiver->setUri(QStringLiteral("udp://0.0.0.0:%1").arg(pInfo->uri()));
Gus Grubba
committed
_toolbox->settingsManager()->videoSettings()->videoSource()->setRawValue(VideoSettings::videoSourceUDPH264);
break;
case VIDEO_STREAM_TYPE_MPEG_TS_H264:
_videoReceiver->setUri(QStringLiteral("mpegts://0.0.0.0:%1").arg(pInfo->uri()));
Gus Grubba
committed
_toolbox->settingsManager()->videoSettings()->videoSource()->setRawValue(VideoSettings::videoSourceMPEGTS);
break;
default:
_videoReceiver->setUri(pInfo->uri());
break;
}
//-- 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:
_thermalVideoReceiver->setUri(pTinfo->uri());
break;
case VIDEO_STREAM_TYPE_RTPUDP:
_thermalVideoReceiver->setUri(QStringLiteral("udp://0.0.0.0:%1").arg(pTinfo->uri()));
break;
case VIDEO_STREAM_TYPE_MPEG_TS_H264:
_thermalVideoReceiver->setUri(QStringLiteral("mpegts://0.0.0.0:%1").arg(pTinfo->uri()));
break;
default:
_thermalVideoReceiver->setUri(pTinfo->uri());
break;
}
}
QString source = _videoSettings->videoSource()->rawValue().toString();
_videoReceiver->setUri(QStringLiteral("udp://0.0.0.0:%1").arg(_videoSettings->udpPort()->rawValue().toInt()));
else if (source == VideoSettings::videoSourceUDPH265)
_videoReceiver->setUri(QStringLiteral("udp265://0.0.0.0:%1").arg(_videoSettings->udpPort()->rawValue().toInt()));
else if (source == VideoSettings::videoSourceMPEGTS)
_videoReceiver->setUri(QStringLiteral("mpegts://0.0.0.0:%1").arg(_videoSettings->udpPort()->rawValue().toInt()));
else if (source == VideoSettings::videoSourceRTSP)
_videoReceiver->setUri(_videoSettings->rtspUrl()->rawValue().toString());
else if (source == VideoSettings::videoSourceTCP)
_videoReceiver->setUri(QStringLiteral("tcp://%1").arg(_videoSettings->tcpUrl()->rawValue().toString()));
//-----------------------------------------------------------------------------
Matej Frančeškin
committed
VideoManager::restartVideo()
qCDebug(VideoManagerLog) << "Restart video streaming";
emit aspectRatioChanged();
//----------------------------------------------------------------------------------------
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();
}
Matej Frančeškin
committed
disconnect(_activeVehicle->dynamicCameras(), &QGCCameraManager::streamChanged, this, &VideoManager::restartVideo);
}
_activeVehicle = vehicle;
if(_activeVehicle) {
connect(_activeVehicle, &Vehicle::connectionLostChanged, this, &VideoManager::_connectionLostChanged);
if(_activeVehicle->dynamicCameras()) {
Matej Frančeškin
committed
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();
Matej Frančeškin
committed
restartVideo();
//----------------------------------------------------------------------------------------
void
VideoManager::_connectionLostChanged(bool connectionLost)
{
if(connectionLost) {
//-- Disable full screen video if connection is lost
setfullScreen(false);
}
}
//----------------------------------------------------------------------------------------
void
VideoManager::_aspectRatioChanged()
emit aspectRatioChanged();