/**************************************************************************** * * (c) 2009-2020 QGROUNDCONTROL PROJECT * * QGroundControl is licensed according to the terms in the file * COPYING.md in the root of the source code directory. * ****************************************************************************/ #include "AppSettings.h" #include "QGCPalette.h" #include "QGCApplication.h" #include "ParameterManager.h" #include #include #include const char* AppSettings::parameterFileExtension = "params"; const char* AppSettings::planFileExtension = "plan"; const char* AppSettings::missionFileExtension = "mission"; const char* AppSettings::waypointsFileExtension = "waypoints"; const char* AppSettings::fenceFileExtension = "fence"; const char* AppSettings::rallyPointFileExtension = "rally"; const char* AppSettings::telemetryFileExtension = "tlog"; const char* AppSettings::kmlFileExtension = "kml"; const char* AppSettings::shpFileExtension = "shp"; const char* AppSettings::logFileExtension = "ulg"; const char* AppSettings::parameterDirectory = "Parameters"; const char* AppSettings::telemetryDirectory = "Telemetry"; const char* AppSettings::missionDirectory = "Missions"; const char* AppSettings::logDirectory = "Logs"; const char* AppSettings::videoDirectory = "Video"; const char* AppSettings::crashDirectory = "CrashLogs"; DECLARE_SETTINGGROUP(App, "") { qmlRegisterUncreatableType("QGroundControl.SettingsManager", 1, 0, "AppSettings", "Reference only"); QGCPalette::setGlobalTheme(indoorPalette()->rawValue().toBool() ? QGCPalette::Dark : QGCPalette::Light); // virtualJoystickCentralized -> virtualJoystickAutoCenterThrottle QSettings settings; settings.beginGroup(_settingsGroup); QString deprecatedVirtualJoystickCentralizedKey("virtualJoystickCentralized"); if (settings.contains(deprecatedVirtualJoystickCentralizedKey)) { settings.setValue(virtualJoystickAutoCenterThrottleName, settings.value(deprecatedVirtualJoystickCentralizedKey)); settings.remove(deprecatedVirtualJoystickCentralizedKey); } // Instantiate savePath so we can check for override and setup default path if needed SettingsFact* savePathFact = qobject_cast(savePath()); QString appName = qgcApp()->applicationName(); #ifdef __mobile__ // Mobile builds always use the runtime generated location for savePath. bool userHasModifiedSavePath = false; #else bool userHasModifiedSavePath = !savePathFact->rawValue().toString().isEmpty() || !_nameToMetaDataMap[savePathName]->rawDefaultValue().toString().isEmpty(); #endif if (!userHasModifiedSavePath) { #ifdef __mobile__ #ifdef __ios__ // This will expose the directories directly to the File iOs app QDir rootDir = QDir(QStandardPaths::writableLocation(QStandardPaths::DocumentsLocation)); savePathFact->setRawValue(rootDir.absolutePath()); #else QDir rootDir = QDir(QStandardPaths::writableLocation(QStandardPaths::GenericDataLocation)); savePathFact->setRawValue(rootDir.filePath(appName)); #endif savePathFact->setVisible(false); #else QDir rootDir = QDir(QStandardPaths::writableLocation(QStandardPaths::DocumentsLocation)); savePathFact->setRawValue(rootDir.filePath(appName)); #endif } connect(savePathFact, &Fact::rawValueChanged, this, &AppSettings::savePathsChanged); connect(savePathFact, &Fact::rawValueChanged, this, &AppSettings::_checkSavePathDirectories); _checkSavePathDirectories(); //-- Keep track of language changes SettingsFact* languageFact = qobject_cast(language()); connect(languageFact, &Fact::rawValueChanged, this, &AppSettings::_languageChanged); } DECLARE_SETTINGSFACT(AppSettings, offlineEditingFirmwareType) DECLARE_SETTINGSFACT(AppSettings, offlineEditingVehicleType) DECLARE_SETTINGSFACT(AppSettings, offlineEditingCruiseSpeed) DECLARE_SETTINGSFACT(AppSettings, offlineEditingHoverSpeed) DECLARE_SETTINGSFACT(AppSettings, offlineEditingAscentSpeed) DECLARE_SETTINGSFACT(AppSettings, offlineEditingDescentSpeed) DECLARE_SETTINGSFACT(AppSettings, batteryPercentRemainingAnnounce) DECLARE_SETTINGSFACT(AppSettings, defaultMissionItemAltitude) DECLARE_SETTINGSFACT(AppSettings, telemetrySave) DECLARE_SETTINGSFACT(AppSettings, telemetrySaveNotArmed) DECLARE_SETTINGSFACT(AppSettings, audioMuted) DECLARE_SETTINGSFACT(AppSettings, checkInternet) DECLARE_SETTINGSFACT(AppSettings, virtualJoystick) DECLARE_SETTINGSFACT(AppSettings, virtualJoystickAutoCenterThrottle) DECLARE_SETTINGSFACT(AppSettings, appFontPointSize) DECLARE_SETTINGSFACT(AppSettings, showLargeCompass) DECLARE_SETTINGSFACT(AppSettings, savePath) DECLARE_SETTINGSFACT(AppSettings, autoLoadMissions) DECLARE_SETTINGSFACT(AppSettings, useChecklist) DECLARE_SETTINGSFACT(AppSettings, enforceChecklist) DECLARE_SETTINGSFACT(AppSettings, mapboxToken) DECLARE_SETTINGSFACT(AppSettings, esriToken) DECLARE_SETTINGSFACT(AppSettings, defaultFirmwareType) DECLARE_SETTINGSFACT(AppSettings, gstDebugLevel) DECLARE_SETTINGSFACT(AppSettings, followTarget) DECLARE_SETTINGSFACT(AppSettings, apmStartMavlinkStreams) DECLARE_SETTINGSFACT(AppSettings, enableTaisync) DECLARE_SETTINGSFACT(AppSettings, enableTaisyncVideo) DECLARE_SETTINGSFACT(AppSettings, enableMicrohard) DECLARE_SETTINGSFACT(AppSettings, language) DECLARE_SETTINGSFACT(AppSettings, disableAllPersistence) DECLARE_SETTINGSFACT(AppSettings, usePairing) DECLARE_SETTINGSFACT(AppSettings, saveCsvTelemetry) DECLARE_SETTINGSFACT(AppSettings, firstRunPromptIdsShown) DECLARE_SETTINGSFACT(AppSettings, forwardMavlink) DECLARE_SETTINGSFACT(AppSettings, forwardMavlinkHostName) DECLARE_SETTINGSFACT_NO_FUNC(AppSettings, indoorPalette) { if (!_indoorPaletteFact) { _indoorPaletteFact = _createSettingsFact(indoorPaletteName); connect(_indoorPaletteFact, &Fact::rawValueChanged, this, &AppSettings::_indoorPaletteChanged); } return _indoorPaletteFact; } void AppSettings::_languageChanged() { qgcApp()->setLanguage(); } void AppSettings::_checkSavePathDirectories(void) { QDir savePathDir(savePath()->rawValue().toString()); if (!savePathDir.exists()) { QDir().mkpath(savePathDir.absolutePath()); } if (savePathDir.exists()) { savePathDir.mkdir(parameterDirectory); savePathDir.mkdir(telemetryDirectory); savePathDir.mkdir(missionDirectory); savePathDir.mkdir(logDirectory); savePathDir.mkdir(videoDirectory); savePathDir.mkdir(crashDirectory); } } void AppSettings::_indoorPaletteChanged(void) { QGCPalette::setGlobalTheme(indoorPalette()->rawValue().toBool() ? QGCPalette::Dark : QGCPalette::Light); } QString AppSettings::missionSavePath(void) { QString path = savePath()->rawValue().toString(); if (!path.isEmpty() && QDir(path).exists()) { QDir dir(path); return dir.filePath(missionDirectory); } return QString(); } QString AppSettings::parameterSavePath(void) { QString path = savePath()->rawValue().toString(); if (!path.isEmpty() && QDir(path).exists()) { QDir dir(path); return dir.filePath(parameterDirectory); } return QString(); } QString AppSettings::telemetrySavePath(void) { QString path = savePath()->rawValue().toString(); if (!path.isEmpty() && QDir(path).exists()) { QDir dir(path); return dir.filePath(telemetryDirectory); } return QString(); } QString AppSettings::logSavePath(void) { QString path = savePath()->rawValue().toString(); if (!path.isEmpty() && QDir(path).exists()) { QDir dir(path); return dir.filePath(logDirectory); } return QString(); } QString AppSettings::videoSavePath(void) { QString path = savePath()->rawValue().toString(); if (!path.isEmpty() && QDir(path).exists()) { QDir dir(path); return dir.filePath(videoDirectory); } return QString(); } QString AppSettings::crashSavePath(void) { QString path = savePath()->rawValue().toString(); if (!path.isEmpty() && QDir(path).exists()) { QDir dir(path); return dir.filePath(crashDirectory); } return QString(); } MAV_AUTOPILOT AppSettings::offlineEditingFirmwareTypeFromFirmwareType(MAV_AUTOPILOT firmwareType) { if (firmwareType != MAV_AUTOPILOT_PX4 && firmwareType != MAV_AUTOPILOT_ARDUPILOTMEGA) { firmwareType = MAV_AUTOPILOT_GENERIC; } return firmwareType; } MAV_TYPE AppSettings::offlineEditingVehicleTypeFromVehicleType(MAV_TYPE vehicleType) { if (QGCMAVLink::isRover(vehicleType)) { return MAV_TYPE_GROUND_ROVER; } else if (QGCMAVLink::isSub(vehicleType)) { return MAV_TYPE_SUBMARINE; } else if (QGCMAVLink::isVTOL(vehicleType)) { return MAV_TYPE_VTOL_QUADROTOR; } else if (QGCMAVLink::isFixedWing(vehicleType)) { return MAV_TYPE_FIXED_WING; } else { return MAV_TYPE_QUADROTOR; } } QList AppSettings::firstRunPromptsIdsVariantToList(const QVariant& firstRunPromptIds) { QList rgIds; QStringList strIdList = firstRunPromptIds.toString().split(",", QString::SkipEmptyParts); for (const QString& strId: strIdList) { rgIds.append(strId.toInt()); } return rgIds; } QVariant AppSettings::firstRunPromptsIdsListToVariant(const QList& rgIds) { QStringList strList; for (int id: rgIds) { strList.append(QString::number(id)); } return QVariant(strList.join(",")); } void AppSettings::firstRunPromptIdsMarkIdAsShown(int id) { QList rgIds = firstRunPromptsIdsVariantToList(firstRunPromptIdsShown()->rawValue()); if (!rgIds.contains(id)) { rgIds.append(id); firstRunPromptIdsShown()->setRawValue(firstRunPromptsIdsListToVariant(rgIds)); } } int AppSettings::_languageID(void) { // Hack to provide language settings as early in the boot process as possible. Must be know // prior to loading any json files. QSettings settings; return settings.value("language", 0).toInt(); }