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()
{
for (int i = 0; i < 2; i++) {
if (_videoReceiver[i] != nullptr) {
delete _videoReceiver[i];
_videoReceiver[i] = nullptr;
}
#if defined(QGC_GST_STREAMING)
Andrew Voznytsa
committed
// FIXME: AV: we need some interaface for video sink with .release() call
// Currently VideoManager is destroyed after corePlugin() and we are crashing on app exit
// calling qgcApp()->toolbox()->corePlugin()->releaseVideoSink(_videoSink[i]);
// As for now let's call GStreamer::releaseVideoSink() directly
GStreamer::releaseVideoSink(_videoSink[i]);
}
//-----------------------------------------------------------------------------
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[0] = toolbox->corePlugin()->createVideoReceiver(this);
_videoReceiver[1] = toolbox->corePlugin()->createVideoReceiver(this);
connect(_videoReceiver[0], &VideoReceiver::streamingChanged, this, [this](bool active){
_streaming = active;
emit streamingChanged();
});
connect(_videoReceiver[0], &VideoReceiver::onStartComplete, this, [this](VideoReceiver::STATUS status) {
if (status == VideoReceiver::STATUS_OK) {
_videoStarted[0] = true;
if (_videoSink[0] != nullptr) {
// It is absolytely ok to have video receiver active (streaming) and decoding not active
// It should be handy for cases when you have many streams and want to show only some of them
// NOTE that even if decoder did not start it is still possible to record video
_videoReceiver[0]->startDecoding(_videoSink[0]);
}
} else if (status == VideoReceiver::STATUS_INVALID_URL) {
// Invalid URL - don't restart
} else if (status == VideoReceiver::STATUS_INVALID_STATE) {
// Already running
} else {
_restartVideo(0);
}
});
connect(_videoReceiver[0], &VideoReceiver::onStopComplete, this, [this](VideoReceiver::STATUS) {
_videoStarted[0] = false;
connect(_videoReceiver[0], &VideoReceiver::decodingChanged, this, [this](bool active){
_decoding = active;
emit decodingChanged();
});
connect(_videoReceiver[0], &VideoReceiver::recordingChanged, this, [this](bool active){
_recording = active;
if (!active) {
_subtitleWriter.stopCapturingTelemetry();
}
emit recordingChanged();
});
connect(_videoReceiver[0], &VideoReceiver::recordingStarted, this, [this](){
_subtitleWriter.startCapturingTelemetry(_videoFile);
});
connect(_videoReceiver[0], &VideoReceiver::videoSizeChanged, this, [this](QSize size){
_videoSize = ((quint32)size.width() << 16) | (quint32)size.height();
emit videoSizeChanged();
});
//connect(_videoReceiver, &VideoReceiver::onTakeScreenshotComplete, this, [this](VideoReceiver::STATUS status){
// if (status == VideoReceiver::STATUS_OK) {
// }
//});
// 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 (_videoReceiver[1] != nullptr) {
connect(_videoReceiver[1], &VideoReceiver::onStartComplete, this, [this](VideoReceiver::STATUS status) {
if (status == VideoReceiver::STATUS_OK) {
_videoStarted[1] = true;
if (_videoSink[1] != nullptr) {
_videoReceiver[1]->startDecoding(_videoSink[1]);
}
} else if (status == VideoReceiver::STATUS_INVALID_URL) {
// Invalid URL - don't restart
} else if (status == VideoReceiver::STATUS_INVALID_STATE) {
// Already running
} else {
_restartVideo(1);
}
connect(_videoReceiver[1], &VideoReceiver::onStopComplete, this, [this](VideoReceiver::STATUS) {
_videoStarted[1] = false;
}
_updateSettings(0);
_updateSettings(1);
#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;
}
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) {
QString ext = kFileExtension[fileFormat - VideoReceiver::FILE_FORMAT_MIN];
//-- 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)
+ ".";
QString videoFile2 = _videoFile + "2." + ext;
_videoFile += ext;
if (_videoReceiver[0] && _videoStarted[0]) {
_videoReceiver[0]->startRecording(_videoFile, fileFormat);
}
if (_videoReceiver[1] && _videoStarted[1]) {
_videoReceiver[1]->startRecording(videoFile2, fileFormat);
}
#else
Q_UNUSED(videoFile)
#endif
}
void
VideoManager::stopRecording()
{
if (qgcApp()->runningUnitTests()) {
return;
}
for (int i = 0; i < 2; i++) {
if (_videoReceiver[i]) {
_videoReceiver[i]->stopRecording();
}
}
}
void
VideoManager::grabImage(const QString& imageFile)
{
if (qgcApp()->runningUnitTests()) {
return;
}
if (imageFile.isEmpty()) {
_imageFile = qgcApp()->toolbox()->settingsManager()->appSettings()->photoSavePath();
_imageFile += + "/" + QDateTime::currentDateTime().toString("yyyy-MM-dd_hh.mm.ss.zzz") + ".jpg";
} else {
_imageFile = imageFile;
}
emit imageFileChanged();
_videoReceiver[0]->takeScreenshot(_imageFile);
#else
Q_UNUSED(imageFile)
#endif
//-----------------------------------------------------------------------------
double VideoManager::aspectRatio()
{
if(_activeVehicle && _activeVehicle->cameraManager()) {
QGCVideoStreamInfo* pInfo = _activeVehicle->cameraManager()->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?)
return _videoSettings->aspectRatio()->rawValue().toDouble();
}
//-----------------------------------------------------------------------------
double VideoManager::thermalAspectRatio()
{
if(_activeVehicle && _activeVehicle->cameraManager()) {
QGCVideoStreamInfo* pInfo = _activeVehicle->cameraManager()->thermalStreamInstance();
if(pInfo) {
qCDebug(VideoManagerLog) << "Thermal AR: " << pInfo->aspectRatio();
return pInfo->aspectRatio();
}
}
return 1.0;
}
//-----------------------------------------------------------------------------
double VideoManager::hfov()
{
if(_activeVehicle && _activeVehicle->cameraManager()) {
QGCVideoStreamInfo* pInfo = _activeVehicle->cameraManager()->currentStreamInstance();
if(pInfo) {
return pInfo->hfov();
}
}
return 1.0;
}
//-----------------------------------------------------------------------------
double VideoManager::thermalHfov()
{
if(_activeVehicle && _activeVehicle->cameraManager()) {
QGCVideoStreamInfo* pInfo = _activeVehicle->cameraManager()->thermalStreamInstance();
if(pInfo) {
return pInfo->aspectRatio();
}
}
return _videoSettings->aspectRatio()->rawValue().toDouble();
}
//-----------------------------------------------------------------------------
bool
VideoManager::hasThermal()
{
if(_activeVehicle && _activeVehicle->cameraManager()) {
QGCVideoStreamInfo* pInfo = _activeVehicle->cameraManager()->thermalStreamInstance();
if(pInfo) {
return true;
}
}
return false;
}
//-----------------------------------------------------------------------------
QString
VideoManager::imageFile()
{
return _imageFile;
}
//-----------------------------------------------------------------------------
bool
VideoManager::autoStreamConfigured()
{
if(_activeVehicle && _activeVehicle->cameraManager()) {
QGCVideoStreamInfo* pInfo = _activeVehicle->cameraManager()->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[0] != nullptr) {
_videoSink[0] = qgcApp()->toolbox()->corePlugin()->createVideoSink(this, widget);
if (_videoSink[0] != nullptr) {
if (_videoStarted[0]) {
_videoReceiver[0]->startDecoding(_videoSink[0]);
}
} 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 && _videoReceiver[1] != nullptr) {
_videoSink[1] = qgcApp()->toolbox()->corePlugin()->createVideoSink(this, widget);
if (_videoSink[1] != nullptr) {
if (_videoStarted[1]) {
_videoReceiver[1]->startDecoding(_videoSink[1]);
}
} else {
qCDebug(VideoManagerLog) << "createVideoSink() failed";
Andrew Voznytsa
committed
} else {
qCDebug(VideoManagerLog) << "thermal video receiver disabled";
Andrew Voznytsa
committed
}
//-----------------------------------------------------------------------------
VideoManager::_updateSettings(unsigned id)
const bool lowLatencyStreaming =_videoSettings->lowLatencyMode()->rawValue().toBool();
bool settingsChanged = _lowLatencyStreaming[id] != lowLatencyStreaming;
_lowLatencyStreaming[id] = lowLatencyStreaming;
if(_activeVehicle && _activeVehicle->cameraManager()) {
QGCVideoStreamInfo* pInfo = _activeVehicle->cameraManager()->currentStreamInstance();
if (id == 0) {
qCDebug(VideoManagerLog) << "Configure primary stream:" << pInfo->uri();
switch(pInfo->type()) {
if ((settingsChanged |= _updateVideoUri(id, pInfo->uri()))) {
_toolbox->settingsManager()->videoSettings()->videoSource()->setRawValue(VideoSettings::videoSourceRTSP);
}
break;
if ((settingsChanged |= _updateVideoUri(id, pInfo->uri()))) {
_toolbox->settingsManager()->videoSettings()->videoSource()->setRawValue(VideoSettings::videoSourceTCP);
}
break;
case VIDEO_STREAM_TYPE_RTPUDP:
if ((settingsChanged |= _updateVideoUri(id, 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 ((settingsChanged |= _updateVideoUri(id, QStringLiteral("mpegts://0.0.0.0:%1").arg(pInfo->uri())))) {
_toolbox->settingsManager()->videoSettings()->videoSource()->setRawValue(VideoSettings::videoSourceMPEGTS);
}
settingsChanged |= _updateVideoUri(id, pInfo->uri());
else if (id == 1) { //-- Thermal stream (if any)
QGCVideoStreamInfo* pTinfo = _activeVehicle->cameraManager()->thermalStreamInstance();
if (pTinfo) {
qCDebug(VideoManagerLog) << "Configure secondary stream:" << pTinfo->uri();
switch(pTinfo->type()) {
case VIDEO_STREAM_TYPE_RTSP:
case VIDEO_STREAM_TYPE_TCP_MPEG:
settingsChanged |= _updateVideoUri(id, pTinfo->uri());
break;
case VIDEO_STREAM_TYPE_RTPUDP:
settingsChanged |= _updateVideoUri(id, QStringLiteral("udp://0.0.0.0:%1").arg(pTinfo->uri()));
break;
case VIDEO_STREAM_TYPE_MPEG_TS_H264:
settingsChanged |= _updateVideoUri(id, QStringLiteral("mpegts://0.0.0.0:%1").arg(pTinfo->uri()));
settingsChanged |= _updateVideoUri(id, pTinfo->uri());
QString source = _videoSettings->videoSource()->rawValue().toString();
settingsChanged |= _updateVideoUri(0, QStringLiteral("udp://0.0.0.0:%1").arg(_videoSettings->udpPort()->rawValue().toInt()));
else if (source == VideoSettings::videoSourceUDPH265)
settingsChanged |= _updateVideoUri(0, QStringLiteral("udp265://0.0.0.0:%1").arg(_videoSettings->udpPort()->rawValue().toInt()));
else if (source == VideoSettings::videoSourceMPEGTS)
settingsChanged |= _updateVideoUri(0, QStringLiteral("mpegts://0.0.0.0:%1").arg(_videoSettings->udpPort()->rawValue().toInt()));
else if (source == VideoSettings::videoSourceRTSP)
settingsChanged |= _updateVideoUri(0, _videoSettings->rtspUrl()->rawValue().toString());
else if (source == VideoSettings::videoSourceTCP)
settingsChanged |= _updateVideoUri(0, QStringLiteral("tcp://%1").arg(_videoSettings->tcpUrl()->rawValue().toString()));
//-----------------------------------------------------------------------------
VideoManager::_updateVideoUri(unsigned id, 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()) {
if (id == 0) {
return _updateVideoUri(0, QString("tsusb://0.0.0.0:%1").arg(TAISYNC_VIDEO_UDP_PORT));
} if (id == 1) {
// FIXME: AV: TAISYNC_VIDEO_UDP_PORT is used by video stream, thermal stream should go via its own proxy
if (!_videoUri[1].isEmpty()) {
_videoUri[1].clear();
return true;
} else {
return false;
}
//-----------------------------------------------------------------------------
VideoManager::_restartVideo(unsigned id)
if (qgcApp()->runningUnitTests()) {
return;
}
bool oldLowLatencyStreaming = _lowLatencyStreaming[id];
QString oldUri = _videoUri[id];
_updateSettings(id);
bool newLowLatencyStreaming = _lowLatencyStreaming[id];
QString newUri = _videoUri[id];
// FIXME: AV: use _updateSettings() result to check if settings were changed
if (oldUri == newUri && oldLowLatencyStreaming == newLowLatencyStreaming && _videoStarted[id]) {
qCDebug(VideoManagerLog) << "No sense to restart video streaming, skipped" << id;
qCDebug(VideoManagerLog) << "Restart video streaming" << id;
if (_videoStarted[id]) {
_stopReceiver(id);
//-----------------------------------------------------------------------------
void
VideoManager::_restartAllVideos()
{
_restartVideo(0);
_restartVideo(1);
}
//----------------------------------------------------------------------------------------
void
VideoManager::_startReceiver(unsigned id)
{
#if defined(QGC_GST_STREAMING)
const unsigned timeout = _videoSettings->rtspTimeout()->rawValue().toUInt();
qCDebug(VideoManagerLog) << "Unsupported receiver id" << id;
} else if (_videoReceiver[id] != nullptr/* && _videoSink[id] != nullptr*/) {
if (!_videoUri[id].isEmpty()) {
_videoReceiver[id]->start(_videoUri[id], timeout, _lowLatencyStreaming[id] ? -1 : 0);
}
#endif
}
//----------------------------------------------------------------------------------------
void
VideoManager::_stopReceiver(unsigned id)
{
#if defined(QGC_GST_STREAMING)
qCDebug(VideoManagerLog) << "Unsupported receiver id" << id;
} else if (_videoReceiver[id] != nullptr) {
_videoReceiver[id]->stop();
//----------------------------------------------------------------------------------------
void
VideoManager::_setActiveVehicle(Vehicle* vehicle)
{
if(_activeVehicle) {
disconnect(_activeVehicle, &Vehicle::connectionLostChanged, this, &VideoManager::_connectionLostChanged);
if(_activeVehicle->cameraManager()) {
QGCCameraControl* pCamera = _activeVehicle->cameraManager()->currentCameraInstance();
if(pCamera) {
pCamera->stopStream();
}
disconnect(_activeVehicle->cameraManager(), &QGCCameraManager::streamChanged, this, &VideoManager::_restartAllVideos);
}
_activeVehicle = vehicle;
if(_activeVehicle) {
connect(_activeVehicle, &Vehicle::connectionLostChanged, this, &VideoManager::_connectionLostChanged);
if(_activeVehicle->cameraManager()) {
connect(_activeVehicle->cameraManager(), &QGCCameraManager::streamChanged, this, &VideoManager::_restartAllVideos);
QGCCameraControl* pCamera = _activeVehicle->cameraManager()->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();