Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

VideoManager: Convert to Singleton #12104

Merged
merged 1 commit into from
Nov 23, 2024
Merged
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
13 changes: 6 additions & 7 deletions src/Camera/SimulatedCameraControl.cc
Original file line number Diff line number Diff line change
Expand Up @@ -19,11 +19,10 @@
SimulatedCameraControl::SimulatedCameraControl(Vehicle* vehicle, QObject* parent)
: MavlinkCameraControl (parent)
, _vehicle (vehicle)
, _videoManager (qgcApp()->toolbox()->videoManager())
{
QQmlEngine::setObjectOwnership(this, QQmlEngine::CppOwnership);

connect(_videoManager, &VideoManager::recordingChanged, this, &SimulatedCameraControl::videoCaptureStatusChanged);
connect(VideoManager::instance(), &VideoManager::recordingChanged, this, &SimulatedCameraControl::videoCaptureStatusChanged);

auto flyViewSettings = qgcApp()->toolbox()->settingsManager()->flyViewSettings();
connect(flyViewSettings->showSimpleCameraControl(), &Fact::rawValueChanged, this, &SimulatedCameraControl::infoChanged);
Expand All @@ -44,7 +43,7 @@ QString SimulatedCameraControl::recordTimeStr()

SimulatedCameraControl::VideoCaptureStatus SimulatedCameraControl::videoCaptureStatus()
{
return _videoCaptureStatus = _videoManager->recording() ? VIDEO_CAPTURE_STATUS_RUNNING : VIDEO_CAPTURE_STATUS_STOPPED;
return _videoCaptureStatus = VideoManager::instance()->recording() ? VIDEO_CAPTURE_STATUS_RUNNING : VIDEO_CAPTURE_STATUS_STOPPED;
}

void SimulatedCameraControl::setCameraMode(CameraMode mode)
Expand Down Expand Up @@ -163,7 +162,7 @@ bool SimulatedCameraControl::startVideoRecording()

_videoRecordTimeUpdateTimer.start();
_videoRecordTimeElapsedTimer.start();
_videoManager->startRecording();
VideoManager::instance()->startRecording();
return false;
}

Expand All @@ -177,7 +176,7 @@ bool SimulatedCameraControl::stopVideoRecording()
}

_videoRecordTimeUpdateTimer.stop();
_videoManager->stopRecording();
VideoManager::instance()->stopRecording();
return true;
}

Expand All @@ -192,7 +191,7 @@ quint32 SimulatedCameraControl::recordTime()

bool SimulatedCameraControl::capturesVideo()
{
return _videoManager->hasVideo();
return VideoManager::instance()->hasVideo();
}

void SimulatedCameraControl::setPhotoLapse(double)
Expand All @@ -207,7 +206,7 @@ bool SimulatedCameraControl::capturesPhotos()

bool SimulatedCameraControl::hasVideoStream()
{
return _videoManager->hasVideo();
return VideoManager::instance()->hasVideo();
}

void SimulatedCameraControl::setPhotoLapseCount(int)
Expand Down
4 changes: 1 addition & 3 deletions src/Camera/SimulatedCameraControl.h
Original file line number Diff line number Diff line change
Expand Up @@ -14,7 +14,6 @@
#include <QtCore/QTimer>
#include <QtCore/QElapsedTimer>

class VideoManager;
class Vehicle;

/// Creates a simulated Camera Control which supports:
Expand Down Expand Up @@ -141,7 +140,6 @@ protected slots:
PhotoCaptureMode _photoCaptureMode = PHOTO_CAPTURE_SINGLE;
qreal _photoLapse = 1.0;
int _photoLapseCount = 0;
VideoManager* _videoManager = nullptr;
QTimer _videoRecordTimeUpdateTimer;
QElapsedTimer _videoRecordTimeElapsedTimer;
};
};
14 changes: 5 additions & 9 deletions src/Camera/VehicleCameraControl.cc
Original file line number Diff line number Diff line change
Expand Up @@ -360,9 +360,7 @@ VehicleCameraControl::takePhoto()
_setPhotoStatus(PHOTO_CAPTURE_IN_PROGRESS);
_captureInfoRetries = 0;
//-- Capture local image as well
if(qgcApp()->toolbox()->videoManager()) {
qgcApp()->toolbox()->videoManager()->grabImage();
}
VideoManager::instance()->grabImage();
return true;
}
}
Expand Down Expand Up @@ -1563,12 +1561,10 @@ VehicleCameraControl::handleCaptureStatus(const mavlink_camera_capture_status_t&
//-- Time Lapse
if(photoCaptureStatus() == PHOTO_CAPTURE_INTERVAL_IDLE || photoCaptureStatus() == PHOTO_CAPTURE_INTERVAL_IN_PROGRESS) {
//-- Capture local image as well
if(qgcApp()->toolbox()->videoManager()) {
QString photoPath = qgcApp()->toolbox()->settingsManager()->appSettings()->savePath()->rawValue().toString() + QStringLiteral("/Photo");
QDir().mkpath(photoPath);
photoPath += + "/" + QDateTime::currentDateTime().toString("yyyy-MM-dd_hh.mm.ss.zzz") + ".jpg";
qgcApp()->toolbox()->videoManager()->grabImage(photoPath);
}
QString photoPath = qgcApp()->toolbox()->settingsManager()->appSettings()->savePath()->rawValue().toString() + QStringLiteral("/Photo");
QDir().mkpath(photoPath);
photoPath += + "/" + QDateTime::currentDateTime().toString("yyyy-MM-dd_hh.mm.ss.zzz") + ".jpg";
VideoManager::instance()->grabImage(photoPath);
}
}

Expand Down
8 changes: 3 additions & 5 deletions src/QGCApplication.cc
Original file line number Diff line number Diff line change
Expand Up @@ -316,6 +316,8 @@ void QGCApplication::_initForNormalAppBoot()
QQuickWindow::setGraphicsApi(QSGRendererInterface::OpenGL);
#endif

VideoManager::instance(); // GStreamer must be initialized before QmlEngine

QQuickStyle::setStyle("Basic");
_qmlAppEngine = _toolbox->corePlugin()->createQmlApplicationEngine(this);
QObject::connect(_qmlAppEngine, &QQmlApplicationEngine::objectCreationFailed, this, QCoreApplication::quit, Qt::QueuedConnection);
Expand All @@ -328,11 +330,7 @@ void QGCApplication::_initForNormalAppBoot()
// Image provider for Optical Flow
_qmlAppEngine->addImageProvider(qgcImageProviderId, new QGCImageProvider());

QQuickWindow* rootWindow = mainRootWindow();
if (rootWindow) {
rootWindow->scheduleRenderJob(new FinishVideoInitialization(_toolbox->videoManager()),
QQuickWindow::BeforeSynchronizingStage);
}
VideoManager::instance()->init();

// Safe to show popup error messages now that main window is created
_showErrorsInToolbar = true;
Expand Down
3 changes: 0 additions & 3 deletions src/QGCToolbox.cc
Original file line number Diff line number Diff line change
Expand Up @@ -11,7 +11,6 @@
#include "LinkManager.h"
#include "MAVLinkProtocol.h"
#include "MultiVehicleManager.h"
#include "VideoManager.h"
#include "QGCCorePlugin.h"
#include "SettingsManager.h"
#include "QGCApplication.h"
Expand All @@ -31,7 +30,6 @@ QGCToolbox::QGCToolbox(QGCApplication* app)
_linkManager = new LinkManager (app, this);
_mavlinkProtocol = new MAVLinkProtocol (app, this);
_multiVehicleManager = new MultiVehicleManager (app, this);
_videoManager = new VideoManager (app, this);
}

void QGCToolbox::setChildToolboxes(void)
Expand All @@ -43,7 +41,6 @@ void QGCToolbox::setChildToolboxes(void)
_linkManager->setToolbox(this);
_mavlinkProtocol->setToolbox(this);
_multiVehicleManager->setToolbox(this);
_videoManager->setToolbox(this);
}

void QGCToolbox::_scanAndLoadPlugins(QGCApplication* app)
Expand Down
3 changes: 0 additions & 3 deletions src/QGCToolbox.h
Original file line number Diff line number Diff line change
Expand Up @@ -17,7 +17,6 @@ class LinkManager;
class MAVLinkProtocol;
class MultiVehicleManager;
class QGCApplication;
class VideoManager;
class QGCCorePlugin;
class SettingsManager;

Expand All @@ -31,7 +30,6 @@ class QGCToolbox : public QObject {
LinkManager* linkManager () { return _linkManager; }
MAVLinkProtocol* mavlinkProtocol () { return _mavlinkProtocol; }
MultiVehicleManager* multiVehicleManager () { return _multiVehicleManager; }
VideoManager* videoManager () { return _videoManager; }
QGCCorePlugin* corePlugin () { return _corePlugin; }
SettingsManager* settingsManager () { return _settingsManager; }

Expand All @@ -42,7 +40,6 @@ class QGCToolbox : public QObject {
LinkManager* _linkManager = nullptr;
MAVLinkProtocol* _mavlinkProtocol = nullptr;
MultiVehicleManager* _multiVehicleManager = nullptr;
VideoManager* _videoManager = nullptr;
QGCCorePlugin* _corePlugin = nullptr;
SettingsManager* _settingsManager = nullptr;
friend class QGCApplication;
Expand Down
4 changes: 2 additions & 2 deletions src/QmlControls/QGroundControlQmlGlobal.cc
Original file line number Diff line number Diff line change
Expand Up @@ -40,7 +40,7 @@
#include "TerrainProfile.h"
#include "ToolStripAction.h"
#include "ToolStripActionList.h"

#include "VideoManager.h"
#ifndef NO_SERIAL_LINK
#include "GPSManager.h"
#include "GPSRtk.h"
Expand Down Expand Up @@ -111,6 +111,7 @@ QGroundControlQmlGlobal::QGroundControlQmlGlobal(QGCApplication* app, QGCToolbox
, _adsbVehicleManager(ADSBVehicleManager::instance())
, _qgcPositionManager(QGCPositionManager::instance())
, _missionCommandTree(MissionCommandTree::instance())
, _videoManager(VideoManager::instance())
#ifndef QGC_AIRLINK_DISABLED
, _airlinkManager(AirLinkManager::instance())
#endif
Expand Down Expand Up @@ -159,7 +160,6 @@ void QGroundControlQmlGlobal::setToolbox(QGCToolbox* toolbox)

_linkManager = toolbox->linkManager();
_multiVehicleManager = toolbox->multiVehicleManager();
_videoManager = toolbox->videoManager();
_corePlugin = toolbox->corePlugin();
_settingsManager = toolbox->settingsManager();
#ifndef NO_SERIAL_LINK
Expand Down
2 changes: 1 addition & 1 deletion src/QmlControls/QGroundControlQmlGlobal.h
Original file line number Diff line number Diff line change
Expand Up @@ -256,6 +256,7 @@ class QGroundControlQmlGlobal : public QGCTool
ADSBVehicleManager* _adsbVehicleManager = nullptr;
QGCPositionManager* _qgcPositionManager = nullptr;
MissionCommandTree* _missionCommandTree = nullptr;
VideoManager* _videoManager = nullptr;
#ifndef QGC_AIRLINK_DISABLED
AirLinkManager* _airlinkManager = nullptr;
#endif
Expand All @@ -266,7 +267,6 @@ class QGroundControlQmlGlobal : public QGCTool
double _flightMapInitialZoom = 17.0;
LinkManager* _linkManager = nullptr;
MultiVehicleManager* _multiVehicleManager = nullptr;
VideoManager* _videoManager = nullptr;
QGCCorePlugin* _corePlugin = nullptr;
SettingsManager* _settingsManager = nullptr;
#ifndef NO_SERIAL_LINK
Expand Down
2 changes: 1 addition & 1 deletion src/Settings/VideoSettings.cc
Original file line number Diff line number Diff line change
Expand Up @@ -174,7 +174,7 @@ DECLARE_SETTINGSFACT_NO_FUNC(VideoSettings, tcpUrl)
bool VideoSettings::streamConfigured(void)
{
//-- First, check if it's autoconfigured
if(qgcApp()->toolbox()->videoManager()->autoStreamConfigured()) {
if(VideoManager::instance()->autoStreamConfigured()) {
qCDebug(VideoManagerLog) << "Stream auto configured";
return true;
}
Expand Down
2 changes: 1 addition & 1 deletion src/Vehicle/Vehicle.cc
Original file line number Diff line number Diff line change
Expand Up @@ -1113,7 +1113,7 @@ void Vehicle::_updateArmed(bool armed)
// Also handle Video Streaming
if(_settingsManager->videoSettings()->disableWhenDisarmed()->rawValue().toBool()) {
_settingsManager->videoSettings()->streamEnabled()->setRawValue(false);
qgcApp()->toolbox()->videoManager()->stopVideo();
VideoManager::instance()->stopVideo();
}
}
}
Expand Down
Loading
Loading