Skip to content

Commit

Permalink
Convert SettingsManager to Singleton
Browse files Browse the repository at this point in the history
  • Loading branch information
HTRamsey committed Nov 29, 2024
1 parent 4508bb3 commit 4797dd7
Show file tree
Hide file tree
Showing 78 changed files with 426 additions and 361 deletions.
8 changes: 4 additions & 4 deletions CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -229,6 +229,10 @@ if(QGC_DISABLE_APM_MAVLINK)
add_compile_definitions(NO_ARDUPILOT_DIALECT)
endif()

if(QGC_VIEWER3D)
add_compile_definitions(QGC_VIEWER3D)
endif()

if("${CMAKE_OSX_ARCHITECTURES}" MATCHES "arm64;x86_64" OR "${CMAKE_OSX_ARCHITECTURES}" MATCHES "x86_64;arm64")
set(MACOS_UNIVERSAL_BUILD ON CACHE INTERNAL "" FORCE)
endif()
Expand All @@ -246,10 +250,6 @@ if(QGC_CUSTOM_BUILD)
add_subdirectory(custom)
endif()

if(QGC_DISABLE_APM_MAVLINK)
add_compile_definitions(NO_ARDUPILOT_DIALECT)
endif()

#######################################################
# QGroundControl Resources
#######################################################
Expand Down
3 changes: 1 addition & 2 deletions src/ADSB/ADSBVehicleManager.cc
Original file line number Diff line number Diff line change
Expand Up @@ -9,7 +9,6 @@

#include "ADSBVehicleManager.h"
#include "QGCApplication.h"
#include "QGCToolbox.h"
#include "SettingsManager.h"
#include "ADSBVehicleManagerSettings.h"
#include "ADSBTCPLink.h"
Expand All @@ -23,7 +22,7 @@

QGC_LOGGING_CATEGORY(ADSBVehicleManagerLog, "qgc.adsb.adsbvehiclemanager")

Q_APPLICATION_STATIC(ADSBVehicleManager, _adsbVehicleManager, qgcApp()->toolbox()->settingsManager()->adsbVehicleManagerSettings());
Q_APPLICATION_STATIC(ADSBVehicleManager, _adsbVehicleManager, SettingsManager::instance()->adsbVehicleManagerSettings());

ADSBVehicleManager::ADSBVehicleManager(ADSBVehicleManagerSettings *settings, QObject *parent)
: QObject(parent)
Expand Down
3 changes: 2 additions & 1 deletion src/API/QGCCorePlugin.cc
Original file line number Diff line number Diff line change
Expand Up @@ -13,6 +13,7 @@
#include "QmlComponentInfo.h"
#include "FactMetaData.h"
#include "SettingsManager.h"
#include "AppSettings.h"
#include "AppMessages.h"
#include "QmlObjectListModel.h"
#include "JoystickManager.h"
Expand Down Expand Up @@ -400,7 +401,7 @@ QVariantList QGCCorePlugin::firstRunPromptsToShow(void)
rgIdsToShow.append(firstRunPromptStdIds());
rgIdsToShow.append(firstRunPromptCustomIds());

QList<int> rgAlreadyShownIds = AppSettings::firstRunPromptsIdsVariantToList(_toolbox->settingsManager()->appSettings()->firstRunPromptIdsShown()->rawValue());
QList<int> rgAlreadyShownIds = AppSettings::firstRunPromptsIdsVariantToList(SettingsManager::instance()->appSettings()->firstRunPromptIdsShown()->rawValue());

for (int idToRemove: rgAlreadyShownIds) {
rgIdsToShow.removeOne(idToRemove);
Expand Down
4 changes: 2 additions & 2 deletions src/AnalyzeView/LogDownloadController.cc
Original file line number Diff line number Diff line change
Expand Up @@ -10,10 +10,10 @@
#include "LogDownloadController.h"
#include "MultiVehicleManager.h"
#include "QGCApplication.h"
#include "QGCToolbox.h"
#include "ParameterManager.h"
#include "Vehicle.h"
#include "SettingsManager.h"
#include "AppSettings.h"
#include "MAVLinkProtocol.h"
#include "LogEntry.h"
#include "QGCLoggingCategory.h"
Expand Down Expand Up @@ -445,7 +445,7 @@ LogDownloadController::download(QString path)
{
QString dir = path;
if (dir.isEmpty()) {
dir = qgcApp()->toolbox()->settingsManager()->appSettings()->logSavePath();
dir = SettingsManager::instance()->appSettings()->logSavePath();
}
downloadToDirectory(dir);
}
Expand Down
5 changes: 3 additions & 2 deletions src/Camera/SimulatedCameraControl.cc
Original file line number Diff line number Diff line change
Expand Up @@ -11,6 +11,7 @@
#include "VideoManager.h"
#include "QGCApplication.h"
#include "SettingsManager.h"
#include "FlyViewSettings.h"
#include "Vehicle.h"

#include <QtQml/QQmlEngine>
Expand All @@ -24,7 +25,7 @@ SimulatedCameraControl::SimulatedCameraControl(Vehicle* vehicle, QObject* parent

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

auto flyViewSettings = qgcApp()->toolbox()->settingsManager()->flyViewSettings();
auto flyViewSettings = SettingsManager::instance()->flyViewSettings();
connect(flyViewSettings->showSimpleCameraControl(), &Fact::rawValueChanged, this, &SimulatedCameraControl::infoChanged);

_videoRecordTimeUpdateTimer.setInterval(1000);
Expand Down Expand Up @@ -201,7 +202,7 @@ void SimulatedCameraControl::setPhotoLapse(double)

bool SimulatedCameraControl::capturesPhotos()
{
return qgcApp()->toolbox()->settingsManager()->flyViewSettings()->showSimpleCameraControl()->rawValue().toBool();
return SettingsManager::instance()->flyViewSettings()->showSimpleCameraControl()->rawValue().toBool();
}

bool SimulatedCameraControl::hasVideoStream()
Expand Down
7 changes: 4 additions & 3 deletions src/Camera/VehicleCameraControl.cc
Original file line number Diff line number Diff line change
Expand Up @@ -18,6 +18,7 @@
#include "QGCCameraIO.h"
#include "QGCApplication.h"
#include "SettingsManager.h"
#include "AppSettings.h"
#include "VideoManager.h"
#include "QGCCameraManager.h"
#include "FTPManager.h"
Expand Down Expand Up @@ -130,7 +131,7 @@ VehicleCameraControl::VehicleCameraControl(const mavlink_camera_information_t *i
_modelName = QString(reinterpret_cast<const char*>(info->model_name));
int ver = static_cast<int>(_info.cam_definition_version);
_cacheFile = QString::asprintf("%s/%s_%s_%03d.xml",
qgcApp()->toolbox()->settingsManager()->appSettings()->parameterSavePath().toStdString().c_str(),
SettingsManager::instance()->appSettings()->parameterSavePath().toStdString().c_str(),
_vendor.toStdString().c_str(),
_modelName.toStdString().c_str(),
ver);
Expand Down Expand Up @@ -1560,7 +1561,7 @@ 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
QString photoPath = qgcApp()->toolbox()->settingsManager()->appSettings()->savePath()->rawValue().toString() + QStringLiteral("/Photo");
QString photoPath = SettingsManager::instance()->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 Expand Up @@ -2038,7 +2039,7 @@ VehicleCameraControl::_handleDefinitionFile(const QString &url)
ext.toStdString().c_str());
connect(_vehicle->ftpManager(), &FTPManager::downloadComplete, this, &VehicleCameraControl::_ftpDownloadComplete);
_vehicle->ftpManager()->download(_compID, url,
qgcApp()->toolbox()->settingsManager()->appSettings()->parameterSavePath().toStdString().c_str(),
SettingsManager::instance()->appSettings()->parameterSavePath().toStdString().c_str(),
fileName);
return;
}
Expand Down
2 changes: 1 addition & 1 deletion src/Comms/AirLink/AirLinkLink.cc
Original file line number Diff line number Diff line change
Expand Up @@ -183,7 +183,7 @@ void AirLinkConfiguration::setModemName(const QString &modemName)

void AirLinkConfiguration::loadSettings(QSettings &settings, const QString &root)
{
AppSettings *const appSettings = qgcApp()->toolbox()->settingsManager()->appSettings();
AppSettings *const appSettings = SettingsManager::instance()->appSettings();

settings.beginGroup(root);

Expand Down
4 changes: 2 additions & 2 deletions src/Comms/AirLink/AirLinkManager.cc
Original file line number Diff line number Diff line change
Expand Up @@ -47,8 +47,8 @@ bool AirLinkManager::isOnline(const QString &drone)

void AirLinkManager::updateCredentials(const QString &login, const QString &pass)
{
qgcApp()->toolbox()->settingsManager()->appSettings()->loginAirLink()->setRawValue(login);
qgcApp()->toolbox()->settingsManager()->appSettings()->passAirLink()->setRawValue(pass);
SettingsManager::instance()->appSettings()->loginAirLink()->setRawValue(login);
SettingsManager::instance()->appSettings()->passAirLink()->setRawValue(pass);
}

void AirLinkManager::_connectToAirLinkServer(const QString &login, const QString &pass)
Expand Down
2 changes: 1 addition & 1 deletion src/Comms/LinkInterface.cc
Original file line number Diff line number Diff line change
Expand Up @@ -56,7 +56,7 @@ bool LinkInterface::mavlinkChannelIsSet() const
bool LinkInterface::initMavlinkSigning(void)
{
if (!isSecureConnection()) {
auto appSettings = qgcApp()->toolbox()->settingsManager()->appSettings();
auto appSettings = SettingsManager::instance()->appSettings();
QByteArray signingKeyBytes = appSettings->mavlink2SigningKey()->rawValue().toByteArray();
if (MAVLinkSigning::initSigning(static_cast<mavlink_channel_t>(_mavlinkChannel), signingKeyBytes, MAVLinkSigning::insecureConnectionAccceptUnsignedCallback)) {
if (signingKeyBytes.isEmpty()) {
Expand Down
10 changes: 6 additions & 4 deletions src/Comms/LinkManager.cc
Original file line number Diff line number Diff line change
Expand Up @@ -16,6 +16,8 @@
#include "QGCLoggingCategory.h"
#include "QmlObjectListModel.h"
#include "SettingsManager.h"
#include "AppSettings.h"
#include "AutoConnectSettings.h"
#include "TCPLink.h"
#include "UDPLink.h"

Expand Down Expand Up @@ -96,7 +98,7 @@ void LinkManager::registerQmlTypes()

void LinkManager::init()
{
_autoConnectSettings = qgcApp()->toolbox()->settingsManager()->autoConnectSettings();
_autoConnectSettings = SettingsManager::instance()->autoConnectSettings();

if (!qgcApp()->runningUnitTests()) {
(void) connect(_portListTimer, &QTimer::timeout, this, &LinkManager::_updateAutoConnectLinks);
Expand Down Expand Up @@ -398,7 +400,7 @@ void LinkManager::_addUDPAutoConnectLink()

void LinkManager::_addMAVLinkForwardingLink()
{
if (!qgcApp()->toolbox()->settingsManager()->appSettings()->forwardMavlink()->rawValue().toBool()) {
if (!SettingsManager::instance()->appSettings()->forwardMavlink()->rawValue().toBool()) {
return;
}

Expand All @@ -410,7 +412,7 @@ void LinkManager::_addMAVLinkForwardingLink()
}
}

const QString hostName = qgcApp()->toolbox()->settingsManager()->appSettings()->forwardMavlinkHostName()->rawValue().toString();
const QString hostName = SettingsManager::instance()->appSettings()->forwardMavlinkHostName()->rawValue().toString();
_createDynamicForwardLink(_mavlinkForwardingLinkName, hostName);
}

Expand Down Expand Up @@ -615,7 +617,7 @@ void LinkManager::removeConfiguration(LinkConfiguration *config)

void LinkManager::createMavlinkForwardingSupportLink()
{
const QString hostName = qgcApp()->toolbox()->settingsManager()->appSettings()->forwardMavlinkAPMSupportHostName()->rawValue().toString();
const QString hostName = SettingsManager::instance()->appSettings()->forwardMavlinkAPMSupportHostName()->rawValue().toString();
_createDynamicForwardLink(_mavlinkForwardingSupportLinkName, hostName);
_mavlinkSupportForwardingEnabled = true;
emit mavlinkSupportForwardingEnabledChanged();
Expand Down
12 changes: 6 additions & 6 deletions src/Comms/MAVLinkProtocol.cc
Original file line number Diff line number Diff line change
Expand Up @@ -13,8 +13,8 @@
#include "QGCApplication.h"
#include "QGCLoggingCategory.h"
#include "QGCTemporaryFile.h"
#include "QGCToolbox.h"
#include "SettingsManager.h"
#include "AppSettings.h"
#include "QmlObjectListModel.h"

#include <QtCore/qapplicationstatic.h>
Expand Down Expand Up @@ -220,7 +220,7 @@ void MAVLinkProtocol::_forward(const mavlink_message_t &message)
return;
}

if (!qgcApp()->toolbox()->settingsManager()->appSettings()->forwardMavlink()->rawValue().toBool()) {
if (!SettingsManager::instance()->appSettings()->forwardMavlink()->rawValue().toBool()) {
return;
}

Expand Down Expand Up @@ -343,7 +343,7 @@ void MAVLinkProtocol::_startLogging()
return;
}

AppSettings *const appSettings = qgcApp()->toolbox()->settingsManager()->appSettings();
AppSettings *const appSettings = SettingsManager::instance()->appSettings();
if (appSettings->disableAllPersistence()->rawValue().toBool()) {
return;
}
Expand Down Expand Up @@ -379,7 +379,7 @@ void MAVLinkProtocol::_startLogging()
void MAVLinkProtocol::_stopLogging()
{
if (_tempLogFile->isOpen() && _closeLogFile()) {
AppSettings *const appSettings = qgcApp()->toolbox()->settingsManager()->appSettings();
AppSettings *const appSettings = SettingsManager::instance()->appSettings();
if ((_vehicleWasArmed || appSettings->telemetrySaveNotArmed()->rawValue().toBool()) && appSettings->telemetrySave()->rawValue().toBool() && !appSettings->disableAllPersistence()->rawValue().toBool()) {
_saveTelemetryLog(_tempLogFile->fileName());
} else {
Expand Down Expand Up @@ -426,7 +426,7 @@ void MAVLinkProtocol::deleteTempLogFiles()
void MAVLinkProtocol::_saveTelemetryLog(const QString &tempLogfile)
{
if (_checkTelemetrySavePath()) {
const QString saveDirPath = qgcApp()->toolbox()->settingsManager()->appSettings()->telemetrySavePath();
const QString saveDirPath = SettingsManager::instance()->appSettings()->telemetrySavePath();
const QDir saveDir(saveDirPath);

const QString nameFormat("%1%2.%3");
Expand All @@ -451,7 +451,7 @@ void MAVLinkProtocol::_saveTelemetryLog(const QString &tempLogfile)

bool MAVLinkProtocol::_checkTelemetrySavePath()
{
const QString saveDirPath = qgcApp()->toolbox()->settingsManager()->appSettings()->telemetrySavePath();
const QString saveDirPath = SettingsManager::instance()->appSettings()->telemetrySavePath();
if (saveDirPath.isEmpty()) {
const QString error = tr("Unable to save telemetry log. Application save directory is not set.");
qgcApp()->showAppMessage(error);
Expand Down
4 changes: 2 additions & 2 deletions src/Comms/UDPLink.cc
Original file line number Diff line number Diff line change
Expand Up @@ -315,7 +315,7 @@ bool UDPLink::isSecureConnection()

UDPConfiguration::UDPConfiguration(const QString& name) : LinkConfiguration(name)
{
AutoConnectSettings* settings = qgcApp()->toolbox()->settingsManager()->autoConnectSettings();
AutoConnectSettings* settings = SettingsManager::instance()->autoConnectSettings();
_localPort = settings->udpListenPort()->rawValue().toInt();
QString targetHostIP = settings->udpTargetHostIP()->rawValue().toString();
if (!targetHostIP.isEmpty()) {
Expand Down Expand Up @@ -434,7 +434,7 @@ void UDPConfiguration::saveSettings(QSettings& settings, const QString& root)

void UDPConfiguration::loadSettings(QSettings& settings, const QString& root)
{
AutoConnectSettings* acSettings = qgcApp()->toolbox()->settingsManager()->autoConnectSettings();
AutoConnectSettings* acSettings = SettingsManager::instance()->autoConnectSettings();
_clearTargetHosts();
settings.beginGroup(root);
_localPort = (quint16)settings.value("port", acSettings->udpListenPort()->rawValue().toInt()).toUInt();
Expand Down
6 changes: 3 additions & 3 deletions src/FactSystem/FactMetaData.cc
Original file line number Diff line number Diff line change
Expand Up @@ -9,8 +9,8 @@

#include "FactMetaData.h"
#include "SettingsManager.h"
#include "UnitsSettings.h"
#include "JsonHelper.h"
#include "QGCApplication.h"
#include <MAVLinkLib.h>

#include <QtCore/QtMath>
Expand Down Expand Up @@ -908,7 +908,7 @@ void FactMetaData::_setAppSettingsTranslators(void)
continue;
}

UnitsSettings* settings = qgcApp()->toolbox()->settingsManager()->unitsSettings();
UnitsSettings* settings = SettingsManager::instance()->unitsSettings();
uint settingsUnits = 0;

switch (pAppSettingsTranslation->unitType) {
Expand Down Expand Up @@ -953,7 +953,7 @@ const FactMetaData::AppSettingsTranslation_s* FactMetaData::_findAppSettingsUnit
}

uint unitOption = 0;
auto unitsSettings = qgcApp()->toolbox()->settingsManager()->unitsSettings();
auto unitsSettings = SettingsManager::instance()->unitsSettings();
switch (type) {
case UnitHorizontalDistance:
unitOption = unitsSettings->horizontalDistanceUnits()->rawValue().toUInt();
Expand Down
10 changes: 6 additions & 4 deletions src/FirmwarePlugin/APM/APMFirmwarePlugin.cc
Original file line number Diff line number Diff line change
Expand Up @@ -20,6 +20,8 @@
#include "ParameterManager.h"
#include "SettingsManager.h"
#include "AppSettings.h"
#include "PlanViewSettings.h"
#include "VideoSettings.h"
#include "APMMavlinkStreamRateSettings.h"
#include "ArduPlaneFirmwarePlugin.h"
#include "ArduCopterFirmwarePlugin.h"
Expand Down Expand Up @@ -411,9 +413,9 @@ void APMFirmwarePlugin::initializeStreamRates(Vehicle* vehicle)
vehicle->setFirmwarePluginInstanceData(instanceData);
}

if (qgcApp()->toolbox()->settingsManager()->appSettings()->apmStartMavlinkStreams()->rawValue().toBool()) {
if (SettingsManager::instance()->appSettings()->apmStartMavlinkStreams()->rawValue().toBool()) {

APMMavlinkStreamRateSettings* streamRates = qgcApp()->toolbox()->settingsManager()->apmMavlinkStreamRateSettings();
APMMavlinkStreamRateSettings* streamRates = SettingsManager::instance()->apmMavlinkStreamRateSettings();

struct StreamInfo_s {
MAV_DATA_STREAM mavStream;
Expand Down Expand Up @@ -487,7 +489,7 @@ void APMFirmwarePlugin::initializeVehicle(Vehicle* vehicle)
initializeStreamRates(vehicle);
}

if (qgcApp()->toolbox()->settingsManager()->videoSettings()->videoSource()->rawValue() == VideoSettings::videoSource3DRSolo) {
if (SettingsManager::instance()->videoSettings()->videoSource()->rawValue() == VideoSettings::videoSource3DRSolo) {
_soloVideoHandshake();
}
}
Expand Down Expand Up @@ -573,7 +575,7 @@ QList<MAV_CMD> APMFirmwarePlugin::supportedMissionCommands(QGCMAVLink::VehicleCl
supportedCommands += flightCommands;
}

if (qgcApp()->toolbox()->settingsManager()->planViewSettings()->useConditionGate()->rawValue().toBool()) {
if (SettingsManager::instance()->planViewSettings()->useConditionGate()->rawValue().toBool()) {
supportedCommands.append(MAV_CMD_CONDITION_GATE);
}

Expand Down
2 changes: 1 addition & 1 deletion src/FirmwarePlugin/PX4/PX4FirmwarePlugin.cc
Original file line number Diff line number Diff line change
Expand Up @@ -304,7 +304,7 @@ QList<MAV_CMD> PX4FirmwarePlugin::supportedMissionCommands(QGCMAVLink::VehicleCl
supportedCommands += flightCommands;
}

if (qgcApp()->toolbox()->settingsManager()->planViewSettings()->useConditionGate()->rawValue().toBool()) {
if (SettingsManager::instance()->planViewSettings()->useConditionGate()->rawValue().toBool()) {
supportedCommands.append(MAV_CMD_CONDITION_GATE);
}

Expand Down
1 change: 0 additions & 1 deletion src/FollowMe/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -10,7 +10,6 @@ target_link_libraries(FollowMe
Qt6::Positioning
FirmwarePlugin
PositionManager
QGC
Settings
Utilities
Vehicle
Expand Down
5 changes: 2 additions & 3 deletions src/FollowMe/FollowMe.cc
Original file line number Diff line number Diff line change
Expand Up @@ -8,7 +8,6 @@
****************************************************************************/

#include "FollowMe.h"
#include "QGCApplication.h"
#include "MultiVehicleManager.h"
#include "FirmwarePlugin.h"
#include "Vehicle.h"
Expand Down Expand Up @@ -47,9 +46,9 @@ void FollowMe::init()
static bool once = false;
if (!once) {
(void) connect(_gcsMotionReportTimer, &QTimer::timeout, this, &FollowMe::_sendGCSMotionReport);
(void) connect(qgcApp()->toolbox()->settingsManager()->appSettings()->followTarget(), &Fact::rawValueChanged, this, &FollowMe::_settingsChanged);
(void) connect(SettingsManager::instance()->appSettings()->followTarget(), &Fact::rawValueChanged, this, &FollowMe::_settingsChanged);

_settingsChanged(qgcApp()->toolbox()->settingsManager()->appSettings()->followTarget()->rawValue());
_settingsChanged(SettingsManager::instance()->appSettings()->followTarget()->rawValue());
}
once = true;
}
Expand Down
1 change: 0 additions & 1 deletion src/GPS/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -69,7 +69,6 @@ target_link_libraries(GPS
PRIVATE
Comms
MAVLink
QGC
Settings
Utilities
Vehicle
Expand Down
Loading

0 comments on commit 4797dd7

Please sign in to comment.