AppSettings.cc 14.2 KB
Newer Older
1 2 3 4 5 6 7 8 9 10
/****************************************************************************
 *
 *   (c) 2009-2016 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 "AppSettings.h"
11 12
#include "QGCPalette.h"
#include "QGCApplication.h"
13 14

#include <QQmlEngine>
Don Gagne's avatar
Don Gagne committed
15
#include <QtQml>
16
#include <QStandardPaths>
17

18
const char* AppSettings::appSettingsGroupName =                         "App";
19 20 21 22
const char* AppSettings::offlineEditingFirmwareTypeSettingsName =       "OfflineEditingFirmwareType";
const char* AppSettings::offlineEditingVehicleTypeSettingsName =        "OfflineEditingVehicleType";
const char* AppSettings::offlineEditingCruiseSpeedSettingsName =        "OfflineEditingCruiseSpeed";
const char* AppSettings::offlineEditingHoverSpeedSettingsName =         "OfflineEditingHoverSpeed";
23 24
const char* AppSettings::offlineEditingAscentSpeedSettingsName =        "OfflineEditingAscentSpeed";
const char* AppSettings::offlineEditingDescentSpeedSettingsName =       "OfflineEditingDescentSpeed";
25 26
const char* AppSettings::batteryPercentRemainingAnnounceSettingsName =  "batteryPercentRemainingAnnounce";
const char* AppSettings::defaultMissionItemAltitudeSettingsName =       "DefaultMissionItemAltitude";
27 28
const char* AppSettings::telemetrySaveName =                            "PromptFLightDataSave";
const char* AppSettings::telemetrySaveNotArmedName =                    "PromptFLightDataSaveNotArmed";
29
const char* AppSettings::audioMutedName =                               "AudioMuted";
30 31 32
const char* AppSettings::virtualJoystickName =                          "VirtualTabletJoystick";
const char* AppSettings::appFontPointSizeName =                         "BaseDeviceFontPointSize";
const char* AppSettings::indoorPaletteName =                            "StyleIsDark";
33
const char* AppSettings::showLargeCompassName =                         "ShowLargeCompass";
34 35
const char* AppSettings::savePathName =                                 "SavePath";
const char* AppSettings::autoLoadMissionsName =                         "AutoLoadMissions";
36
const char* AppSettings::useChecklistName =                             "UseChecklist";
37
const char* AppSettings::advancedLinkSettingsName =                     "AdvancedLinkSettings";
Gus Grubba's avatar
Gus Grubba committed
38
const char* AppSettings::mapboxTokenName =                              "MapboxToken";
39
const char* AppSettings::esriTokenName =                                "EsriToken";
40
const char* AppSettings::defaultFirmwareTypeName =                      "DefaultFirmwareType";
41
const char* AppSettings::gstDebugName =                                 "GstreamerDebugLevel";
42
const char* AppSettings::followTargetName =                             "FollowTarget";
43 44

const char* AppSettings::parameterFileExtension =   "params";
45
const char* AppSettings::planFileExtension =        "plan";
46
const char* AppSettings::missionFileExtension =     "mission";
47
const char* AppSettings::waypointsFileExtension =   "waypoints";
48 49 50
const char* AppSettings::fenceFileExtension =       "fence";
const char* AppSettings::rallyPointFileExtension =  "rally";
const char* AppSettings::telemetryFileExtension =   "tlog";
51
const char* AppSettings::kmlFileExtension =         "kml";
52
const char* AppSettings::logFileExtension =         "ulg";
53

54 55 56 57
const char* AppSettings::parameterDirectory =       "Parameters";
const char* AppSettings::telemetryDirectory =       "Telemetry";
const char* AppSettings::missionDirectory =         "Missions";
const char* AppSettings::logDirectory =             "Logs";
58
const char* AppSettings::videoDirectory =           "Video";
59
const char* AppSettings::crashDirectory =           "CrashLogs";
60 61

AppSettings::AppSettings(QObject* parent)
62 63 64 65 66 67 68 69 70 71 72 73 74 75 76 77 78 79
    : SettingsGroup                         (appSettingsGroupName, QString() /* root settings group */, parent)
    , _offlineEditingFirmwareTypeFact       (NULL)
    , _offlineEditingVehicleTypeFact        (NULL)
    , _offlineEditingCruiseSpeedFact        (NULL)
    , _offlineEditingHoverSpeedFact         (NULL)
    , _offlineEditingAscentSpeedFact        (NULL)
    , _offlineEditingDescentSpeedFact       (NULL)
    , _batteryPercentRemainingAnnounceFact  (NULL)
    , _defaultMissionItemAltitudeFact       (NULL)
    , _telemetrySaveFact                    (NULL)
    , _telemetrySaveNotArmedFact            (NULL)
    , _audioMutedFact                       (NULL)
    , _virtualJoystickFact                  (NULL)
    , _appFontPointSizeFact                 (NULL)
    , _indoorPaletteFact                    (NULL)
    , _showLargeCompassFact                 (NULL)
    , _savePathFact                         (NULL)
    , _autoLoadMissionsFact                 (NULL)
80
    , _useChecklistFact                     (NULL)
81 82 83 84
    , _mapboxTokenFact                      (NULL)
    , _esriTokenFact                        (NULL)
    , _defaultFirmwareTypeFact              (NULL)
    , _gstDebugFact                         (NULL)
85
    , _followTargetFact                     (NULL)
86 87
{
    QQmlEngine::setObjectOwnership(this, QQmlEngine::CppOwnership);
88
    qmlRegisterUncreatableType<AppSettings>("QGroundControl.SettingsManager", 1, 0, "AppSettings", "Reference only");
Don Gagne's avatar
Don Gagne committed
89
    QGCPalette::setGlobalTheme(indoorPalette()->rawValue().toBool() ? QGCPalette::Dark : QGCPalette::Light);
90 91 92

    // Instantiate savePath so we can check for override and setup default path if needed

DonLakeFlyer's avatar
DonLakeFlyer committed
93
    SettingsFact* savePathFact = qobject_cast<SettingsFact*>(savePath());
94 95 96
    QString appName = qgcApp()->applicationName();
    if (savePathFact->rawValue().toString().isEmpty() && _nameToMetaDataMap[savePathName]->rawDefaultValue().toString().isEmpty()) {
#ifdef __mobile__
DonLakeFlyer's avatar
DonLakeFlyer committed
97 98 99
#ifdef __ios__
        QDir rootDir = QDir(QStandardPaths::writableLocation(QStandardPaths::DocumentsLocation));
#else
100
        QDir rootDir = QDir(QStandardPaths::writableLocation(QStandardPaths::GenericDataLocation));
DonLakeFlyer's avatar
DonLakeFlyer committed
101
#endif
102 103 104 105 106 107 108 109 110 111 112 113 114 115 116 117 118 119 120 121 122 123 124
        savePathFact->setVisible(false);
#else
        QDir rootDir = QDir(QStandardPaths::writableLocation(QStandardPaths::DocumentsLocation));
#endif
        savePathFact->setRawValue(rootDir.filePath(appName));
    }

    connect(savePathFact, &Fact::rawValueChanged, this, &AppSettings::savePathsChanged);
    connect(savePathFact, &Fact::rawValueChanged, this, &AppSettings::_checkSavePathDirectories);

    _checkSavePathDirectories();
}

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);
125
        savePathDir.mkdir(logDirectory);
126
        savePathDir.mkdir(videoDirectory);
127
        savePathDir.mkdir(crashDirectory);
128
    }
129 130 131 132 133 134 135 136 137 138 139 140 141 142 143 144 145 146 147 148 149 150 151 152 153 154 155 156 157 158 159 160 161 162 163 164
}

Fact* AppSettings::offlineEditingFirmwareType(void)
{
    if (!_offlineEditingFirmwareTypeFact) {
        _offlineEditingFirmwareTypeFact = _createSettingsFact(offlineEditingFirmwareTypeSettingsName);
    }

    return _offlineEditingFirmwareTypeFact;
}

Fact* AppSettings::offlineEditingVehicleType(void)
{
    if (!_offlineEditingVehicleTypeFact) {
        _offlineEditingVehicleTypeFact = _createSettingsFact(offlineEditingVehicleTypeSettingsName);
    }

    return _offlineEditingVehicleTypeFact;
}

Fact* AppSettings::offlineEditingCruiseSpeed(void)
{
    if (!_offlineEditingCruiseSpeedFact) {
        _offlineEditingCruiseSpeedFact = _createSettingsFact(offlineEditingCruiseSpeedSettingsName);
    }
    return _offlineEditingCruiseSpeedFact;
}

Fact* AppSettings::offlineEditingHoverSpeed(void)
{
    if (!_offlineEditingHoverSpeedFact) {
        _offlineEditingHoverSpeedFact = _createSettingsFact(offlineEditingHoverSpeedSettingsName);
    }
    return _offlineEditingHoverSpeedFact;
}

165 166 167 168 169 170 171 172 173 174 175 176 177 178 179 180
Fact* AppSettings::offlineEditingAscentSpeed(void)
{
    if (!_offlineEditingAscentSpeedFact) {
        _offlineEditingAscentSpeedFact = _createSettingsFact(offlineEditingAscentSpeedSettingsName);
    }
    return _offlineEditingAscentSpeedFact;
}

Fact* AppSettings::offlineEditingDescentSpeed(void)
{
    if (!_offlineEditingDescentSpeedFact) {
        _offlineEditingDescentSpeedFact = _createSettingsFact(offlineEditingDescentSpeedSettingsName);
    }
    return _offlineEditingDescentSpeedFact;
}

181 182 183 184 185 186 187 188 189 190 191 192 193 194 195 196 197 198
Fact* AppSettings::batteryPercentRemainingAnnounce(void)
{
    if (!_batteryPercentRemainingAnnounceFact) {
        _batteryPercentRemainingAnnounceFact = _createSettingsFact(batteryPercentRemainingAnnounceSettingsName);
    }

    return _batteryPercentRemainingAnnounceFact;
}

Fact* AppSettings::defaultMissionItemAltitude(void)
{
    if (!_defaultMissionItemAltitudeFact) {
        _defaultMissionItemAltitudeFact = _createSettingsFact(defaultMissionItemAltitudeSettingsName);
    }

    return _defaultMissionItemAltitudeFact;
}

199
Fact* AppSettings::telemetrySave(void)
200
{
201 202
    if (!_telemetrySaveFact) {
        _telemetrySaveFact = _createSettingsFact(telemetrySaveName);
203 204
    }

205
    return _telemetrySaveFact;
206 207
}

208
Fact* AppSettings::telemetrySaveNotArmed(void)
209
{
210 211
    if (!_telemetrySaveNotArmedFact) {
        _telemetrySaveNotArmedFact = _createSettingsFact(telemetrySaveNotArmedName);
212 213
    }

214
    return _telemetrySaveNotArmedFact;
215 216 217 218
}

Fact* AppSettings::audioMuted(void)
{
219 220 221 222 223 224 225
    if (!_audioMutedFact) {
        _audioMutedFact = _createSettingsFact(audioMutedName);
    }

    return _audioMutedFact;
}

226 227 228 229 230 231 232 233 234
Fact* AppSettings::useChecklist(void)
{
    if (!_useChecklistFact) {
        _useChecklistFact = _createSettingsFact(useChecklistName);
    }

    return _useChecklistFact;
}

235 236 237 238
Fact* AppSettings::appFontPointSize(void)
{
    if (!_appFontPointSizeFact) {
        _appFontPointSizeFact = _createSettingsFact(appFontPointSizeName);
239 240
    }

241 242 243 244 245 246 247 248 249 250 251 252
    return _appFontPointSizeFact;
}

Fact* AppSettings::virtualJoystick(void)
{
    if (!_virtualJoystickFact) {
        _virtualJoystickFact = _createSettingsFact(virtualJoystickName);
    }

    return _virtualJoystickFact;
}

253 254 255 256 257 258 259 260 261
Fact* AppSettings::gstDebug(void)
{
    if (!_gstDebugFact) {
        _gstDebugFact = _createSettingsFact(gstDebugName);
    }

    return _gstDebugFact;
}

262 263 264 265 266 267 268 269 270 271 272 273 274
Fact* AppSettings::indoorPalette(void)
{
    if (!_indoorPaletteFact) {
        _indoorPaletteFact = _createSettingsFact(indoorPaletteName);
        connect(_indoorPaletteFact, &Fact::rawValueChanged, this, &AppSettings::_indoorPaletteChanged);
    }

    return _indoorPaletteFact;
}

void AppSettings::_indoorPaletteChanged(void)
{
    qgcApp()->_loadCurrentStyleSheet();
Don Gagne's avatar
Don Gagne committed
275
    QGCPalette::setGlobalTheme(indoorPalette()->rawValue().toBool() ? QGCPalette::Dark : QGCPalette::Light);
276
}
277 278 279 280 281 282 283 284 285 286

Fact* AppSettings::showLargeCompass(void)
{
    if (!_showLargeCompassFact) {
        _showLargeCompassFact = _createSettingsFact(showLargeCompassName);
    }

    return _showLargeCompassFact;
}

287 288 289 290 291 292 293 294 295 296 297 298 299 300 301 302 303
Fact* AppSettings::savePath(void)
{
    if (!_savePathFact) {
        _savePathFact = _createSettingsFact(savePathName);
    }

    return _savePathFact;
}

QString AppSettings::missionSavePath(void)
{
    QString path = savePath()->rawValue().toString();
    if (!path.isEmpty() && QDir(path).exists()) {
        QDir dir(path);
        return dir.filePath(missionDirectory);
    }

304
    return QString();
305 306 307 308 309 310 311 312 313 314
}

QString AppSettings::parameterSavePath(void)
{
    QString path = savePath()->rawValue().toString();
    if (!path.isEmpty() && QDir(path).exists()) {
        QDir dir(path);
        return dir.filePath(parameterDirectory);
    }

315
    return QString();
316 317 318 319 320 321 322 323 324 325
}

QString AppSettings::telemetrySavePath(void)
{
    QString path = savePath()->rawValue().toString();
    if (!path.isEmpty() && QDir(path).exists()) {
        QDir dir(path);
        return dir.filePath(telemetryDirectory);
    }

326
    return QString();
327 328
}

329 330 331 332 333 334 335 336
QString AppSettings::logSavePath(void)
{
    QString path = savePath()->rawValue().toString();
    if (!path.isEmpty() && QDir(path).exists()) {
        QDir dir(path);
        return dir.filePath(logDirectory);
    }

337
    return QString();
338 339
}

340 341 342 343 344 345 346 347
QString AppSettings::videoSavePath(void)
{
    QString path = savePath()->rawValue().toString();
    if (!path.isEmpty() && QDir(path).exists()) {
        QDir dir(path);
        return dir.filePath(videoDirectory);
    }

348 349 350 351 352 353 354 355 356 357 358 359
    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();
360 361
}

362
Fact* AppSettings::autoLoadMissions(void)
363
{
364 365
    if (!_autoLoadMissionsFact) {
        _autoLoadMissionsFact = _createSettingsFact(autoLoadMissionsName);
366 367
    }

368
    return _autoLoadMissionsFact;
369 370
}

371 372 373 374 375 376 377 378 379
Fact* AppSettings::advancedLinkSettings(void)
{
    if (!_advancedLinkSettingsFact) {
        _advancedLinkSettingsFact = _createSettingsFact(advancedLinkSettingsName);
    }

    return _advancedLinkSettingsFact;
}

380 381 382 383 384 385 386 387 388 389 390 391 392 393 394 395 396 397
Fact* AppSettings::mapboxToken(void)
{
    if (!_mapboxTokenFact) {
        _mapboxTokenFact = _createSettingsFact(mapboxTokenName);
    }

    return _mapboxTokenFact;
}

Fact* AppSettings::esriToken(void)
{
    if (!_esriTokenFact) {
        _esriTokenFact = _createSettingsFact(esriTokenName);
    }

    return _esriTokenFact;
}

398 399 400 401 402 403 404 405 406 407 408 409 410 411 412 413 414 415 416 417 418 419 420
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;
    }
}

421 422 423 424 425 426 427 428
Fact* AppSettings::defaultFirmwareType(void)
{
    if (!_defaultFirmwareTypeFact) {
        _defaultFirmwareTypeFact = _createSettingsFact(defaultFirmwareTypeName);
    }

    return _defaultFirmwareTypeFact;
}
429 430 431 432 433 434 435 436 437 438

Fact* AppSettings::followTarget(void)
{
    if (!_followTargetFact) {
        _followTargetFact = _createSettingsFact(followTargetName);
    }

    return _followTargetFact;
}