diff --git a/qgcresources.qrc b/qgcresources.qrc index 24aba6af8e02680c712ff63ca693ec4aedefa59e..cd510d2befb575f779a31964ff3b97eeae1fb8b2 100644 --- a/qgcresources.qrc +++ b/qgcresources.qrc @@ -186,6 +186,8 @@ src/FlightMap/Images/AlertAircraft.svg src/FlightMap/Images/AwarenessAircraft.svg resources/check.svg + src/AutoPilotPlugins/PX4/Images/no-logging.svg + src/AutoPilotPlugins/PX4/Images/no-logging-light.svg resources/action.svg diff --git a/src/AutoPilotPlugins/PX4/Images/no-logging-light.svg b/src/AutoPilotPlugins/PX4/Images/no-logging-light.svg new file mode 100644 index 0000000000000000000000000000000000000000..e047c28ae70098d29e479436a0f847850a0579d6 --- /dev/null +++ b/src/AutoPilotPlugins/PX4/Images/no-logging-light.svg @@ -0,0 +1,29 @@ + + + + + + + + + + diff --git a/src/AutoPilotPlugins/PX4/Images/no-logging.svg b/src/AutoPilotPlugins/PX4/Images/no-logging.svg new file mode 100644 index 0000000000000000000000000000000000000000..a4fbca666d896987d5c943702629dfa62963bc53 --- /dev/null +++ b/src/AutoPilotPlugins/PX4/Images/no-logging.svg @@ -0,0 +1,30 @@ + + + + + + + + + + diff --git a/src/AutoPilotPlugins/PX4/SafetyComponent.qml b/src/AutoPilotPlugins/PX4/SafetyComponent.qml index a654239aac47ab7d7741e652ad3c48e03fc88e20..314fd1ff3a9c4055a93e75f108974a47ad9884ba 100644 --- a/src/AutoPilotPlugins/PX4/SafetyComponent.qml +++ b/src/AutoPilotPlugins/PX4/SafetyComponent.qml @@ -43,6 +43,7 @@ SetupPage { property real _imageWidth: ScreenTools.defaultFontPixelWidth * 15 property real _imageHeight: ScreenTools.defaultFontPixelHeight * 3 + property Fact _enableLogging: controller.getParameterFact(-1, "SDLOG_MODE") property Fact _fenceAction: controller.getParameterFact(-1, "GF_ACTION") property Fact _fenceRadius: controller.getParameterFact(-1, "GF_MAX_HOR_DIST") property Fact _fenceAlt: controller.getParameterFact(-1, "GF_MAX_VER_DIST") @@ -98,7 +99,6 @@ SetupPage { } Rectangle { - id: otherLastRect x: landModeGrid.x + outerGrid.x - _margins y: landModeGrid.y + outerGrid.y - _margins width: landModeGrid.width + (_margins * 2) @@ -106,6 +106,15 @@ SetupPage { color: qgcPal.windowShade } + Rectangle { + id: otherLastRect + x: loggingGrid.x + outerGrid.x - _margins + y: loggingGrid.y + outerGrid.y - _margins + width: loggingGrid.width + (_margins * 2) + height: loggingGrid.height + (_margins * 2) + color: qgcPal.windowShade + } + Rectangle { id: lastRect x: hitlGrid.x + outerGrid.x - _margins @@ -486,6 +495,49 @@ SetupPage { } } + Item { width: 1; height: _margins; Layout.columnSpan: 3 } + + QGCLabel { + text: qsTr("Vehicle Telemetry Logging") + Layout.columnSpan: 3 + } + + Item { width: 1; height: _margins; Layout.columnSpan: 3 } + + Item { width: _margins; height: 1 } + + GridLayout { + id: loggingGrid + columns: 4 + columnSpacing: ScreenTools.defaultFontPixelWidth * 4 + Item { + Layout.fillWidth: true + } + Image { + mipmap: true + fillMode: Image.PreserveAspectFit + source: qgcPal.globalTheme === qgcPal.Light ? "/qmlimages/no-logging-light.svg" : "/qmlimages/no-logging.svg" + Layout.maximumWidth: _imageWidth + Layout.maximumHeight: _imageHeight + width: _imageWidth + height: _imageHeight + } + QGCCheckBox { + text: qsTr("Enable telemetry logging to vehicle storage") + checkedState: _enableLogging ? (_enableLogging.value >= 0 ? Qt.Checked : Qt.Unchecked) : Qt.Unchecked + Layout.minimumWidth: _editFieldWidth + Layout.alignment: Qt.AlignVCenter + onClicked: { + if(_enableLogging) { + _enableLogging.value = checked ? 0 : -1 + } + } + } + Item { + Layout.fillWidth: true + } + } + Item { width: 1; height: _margins; Layout.columnSpan: 3; visible: _hitlAvailable } QGCLabel { @@ -504,10 +556,10 @@ SetupPage { visible: _hitlAvailable Image { - mipmap: true - fillMode: Image.PreserveAspectFit - source: qgcPal.globalTheme === qgcPal.Light ? "/qmlimages/VehicleSummaryIcon.png" : "/qmlimages/VehicleSummaryIcon.png" - Layout.rowSpan: 3 + mipmap: true + fillMode: Image.PreserveAspectFit + source: qgcPal.globalTheme === qgcPal.Light ? "/qmlimages/VehicleSummaryIcon.png" : "/qmlimages/VehicleSummaryIcon.png" + Layout.rowSpan: 3 Layout.maximumWidth: _imageWidth Layout.maximumHeight: _imageHeight width: _imageWidth @@ -524,6 +576,7 @@ SetupPage { Layout.minimumWidth: _editFieldWidth } } + } } } diff --git a/src/QtLocationPlugin/QGCMapEngine.cpp b/src/QtLocationPlugin/QGCMapEngine.cpp index f39e67e237744a4d9654f85a89ed0020bd715c68..d6657feb7ccbd987498d4688be38903615d8a068 100644 --- a/src/QtLocationPlugin/QGCMapEngine.cpp +++ b/src/QtLocationPlugin/QGCMapEngine.cpp @@ -45,7 +45,7 @@ struct stQGeoTileCacheQGCMapTypes { //-- IMPORTANT // Changes here must reflect those in QGeoTiledMappingManagerEngineQGC.cpp -stQGeoTileCacheQGCMapTypes kMapTypes[] = { +static stQGeoTileCacheQGCMapTypes kMapTypes[] = { #ifndef QGC_LIMITED_MAPS {"Google Street Map", UrlFactory::GoogleMap}, {"Google Satellite Map", UrlFactory::GoogleSatellite}, @@ -69,7 +69,7 @@ stQGeoTileCacheQGCMapTypes kMapTypes[] = { #define NUM_MAPS (sizeof(kMapTypes) / sizeof(stQGeoTileCacheQGCMapTypes)) -stQGeoTileCacheQGCMapTypes kMapboxTypes[] = { +static stQGeoTileCacheQGCMapTypes kMapboxTypes[] = { {"Mapbox Street Map", UrlFactory::MapboxStreets}, {"Mapbox Satellite Map", UrlFactory::MapboxSatellite}, {"Mapbox High Contrast Map",UrlFactory::MapboxHighContrast}, @@ -88,7 +88,7 @@ stQGeoTileCacheQGCMapTypes kMapboxTypes[] = { #define NUM_MAPBOXMAPS (sizeof(kMapboxTypes) / sizeof(stQGeoTileCacheQGCMapTypes)) -stQGeoTileCacheQGCMapTypes kEsriTypes[] = { +static stQGeoTileCacheQGCMapTypes kEsriTypes[] = { {"Esri Street Map", UrlFactory::EsriWorldStreet}, {"Esri Satellite Map", UrlFactory::EsriWorldSatellite}, {"Esri Terrain Map", UrlFactory::EsriTerrain} @@ -96,7 +96,7 @@ stQGeoTileCacheQGCMapTypes kEsriTypes[] = { #define NUM_ESRIMAPS (sizeof(kEsriTypes) / sizeof(stQGeoTileCacheQGCMapTypes)) -stQGeoTileCacheQGCMapTypes kElevationTypes[] = { +static stQGeoTileCacheQGCMapTypes kElevationTypes[] = { {"Airmap Elevation Data", UrlFactory::AirmapElevation} }; @@ -107,7 +107,7 @@ static const char* kMaxMemCacheKey = "MaxMemoryCache"; //----------------------------------------------------------------------------- // Singleton -static QGCMapEngine* kMapEngine = NULL; +static QGCMapEngine* kMapEngine = nullptr; QGCMapEngine* getQGCMapEngine() { @@ -125,7 +125,7 @@ destroyMapEngine() { if(kMapEngine) { delete kMapEngine; - kMapEngine = NULL; + kMapEngine = nullptr; } } @@ -275,15 +275,19 @@ QGCMapEngine::cacheTile(UrlFactory::MapType type, int x, int y, int z, const QBy void QGCMapEngine::cacheTile(UrlFactory::MapType type, const QString& hash, const QByteArray& image, const QString& format, qulonglong set) { - QGCSaveTileTask* task = new QGCSaveTileTask(new QGCCacheTile(hash, image, format, type, set)); - _worker.enqueueTask(task); + AppSettings* appSettings = qgcApp()->toolbox()->settingsManager()->appSettings(); + //-- If we are allowed to persist data, save tile to cache + if(!appSettings->disableAllPersistence()->rawValue().toBool()) { + QGCSaveTileTask* task = new QGCSaveTileTask(new QGCCacheTile(hash, image, format, type, set)); + _worker.enqueueTask(task); + } } //----------------------------------------------------------------------------- QString QGCMapEngine::getTileHash(UrlFactory::MapType type, int x, int y, int z) { - return QString().sprintf("%04d%08d%08d%03d", (int)type, x, y, z); + return QString().sprintf("%04d%08d%08d%03d", static_cast(type), x, y, z); } //----------------------------------------------------------------------------- @@ -291,7 +295,7 @@ UrlFactory::MapType QGCMapEngine::hashToType(const QString& hash) { QString type = hash.mid(0,4); - return (UrlFactory::MapType)type.toInt(); + return static_cast(type.toInt()); } //----------------------------------------------------------------------------- @@ -321,7 +325,7 @@ QGCMapEngine::getTileCount(int zoom, double topleftLon, double topleftLat, doubl set.tileX1 = long2elevationTileX(bottomRightLon, zoom); set.tileY1 = lat2elevationTileY(topleftLat, zoom); } - set.tileCount = (quint64)((quint64)set.tileX1 - (quint64)set.tileX0 + 1) * (quint64)((quint64)set.tileY1 - (quint64)set.tileY0 + 1); + set.tileCount = (static_cast(set.tileX1) - static_cast(set.tileX0) + 1) * (static_cast(set.tileY1) - static_cast(set.tileY0) + 1); set.tileSize = UrlFactory::averageSizeForType(mapType) * set.tileCount; return set; } @@ -330,14 +334,14 @@ QGCMapEngine::getTileCount(int zoom, double topleftLon, double topleftLat, doubl int QGCMapEngine::long2tileX(double lon, int z) { - return (int)(floor((lon + 180.0) / 360.0 * pow(2.0, z))); + return static_cast(floor((lon + 180.0) / 360.0 * pow(2.0, z))); } //----------------------------------------------------------------------------- int QGCMapEngine::lat2tileY(double lat, int z) { - return (int)(floor((1.0 - log( tan(lat * M_PI/180.0) + 1.0 / cos(lat * M_PI/180.0)) / M_PI) / 2.0 * pow(2.0, z))); + return static_cast(floor((1.0 - log( tan(lat * M_PI/180.0) + 1.0 / cos(lat * M_PI/180.0)) / M_PI) / 2.0 * pow(2.0, z))); } //----------------------------------------------------------------------------- @@ -345,7 +349,7 @@ int QGCMapEngine::long2elevationTileX(double lon, int z) { Q_UNUSED(z); - return (int)(floor((lon + 180.0) / srtm1TileSize)); + return static_cast(floor((lon + 180.0) / srtm1TileSize)); } //----------------------------------------------------------------------------- @@ -353,7 +357,7 @@ int QGCMapEngine::lat2elevationTileY(double lat, int z) { Q_UNUSED(z); - return (int)(floor((lat + 90.0) / srtm1TileSize)); + return static_cast(floor((lat + 90.0) / srtm1TileSize)); } //----------------------------------------------------------------------------- @@ -458,13 +462,13 @@ QGCMapEngine::bigSizeToString(quint64 size) if(size < 1024) return kLocale.toString(size); else if(size < 1024 * 1024) - return kLocale.toString((double)size / 1024.0, 'f', 1) + "kB"; + return kLocale.toString(static_cast(size) / 1024.0, 'f', 1) + "kB"; else if(size < 1024 * 1024 * 1024) - return kLocale.toString((double)size / (1024.0 * 1024.0), 'f', 1) + "MB"; + return kLocale.toString(static_cast(size) / (1024.0 * 1024.0), 'f', 1) + "MB"; else if(size < 1024.0 * 1024.0 * 1024.0 * 1024.0) - return kLocale.toString((double)size / (1024.0 * 1024.0 * 1024.0), 'f', 1) + "GB"; + return kLocale.toString(static_cast(size) / (1024.0 * 1024.0 * 1024.0), 'f', 1) + "GB"; else - return kLocale.toString((double)size / (1024.0 * 1024.0 * 1024.0 * 1024), 'f', 1) + "TB"; + return kLocale.toString(static_cast(size) / (1024.0 * 1024.0 * 1024.0 * 1024), 'f', 1) + "TB"; } //----------------------------------------------------------------------------- @@ -479,7 +483,7 @@ void QGCMapEngine::_updateTotals(quint32 totaltiles, quint64 totalsize, quint32 defaulttiles, quint64 defaultsize) { emit updateTotals(totaltiles, totalsize, defaulttiles, defaultsize); - quint64 maxSize = (quint64)getMaxDiskCache() * 1024L * 1024L; + quint64 maxSize = static_cast(getMaxDiskCache()) * 1024L * 1024L; if(!_prunning && defaultsize > maxSize) { //-- Prune Disk Cache _prunning = true; diff --git a/src/QtLocationPlugin/QGCTileCacheWorker.cpp b/src/QtLocationPlugin/QGCTileCacheWorker.cpp index 0fdf19f956a566c539a74484bc2b1fec02293020..3df209644ea846a7b3a9d5fd765c7a7b2409a0a9 100644 --- a/src/QtLocationPlugin/QGCTileCacheWorker.cpp +++ b/src/QtLocationPlugin/QGCTileCacheWorker.cpp @@ -29,9 +29,9 @@ #include "time.h" -const char* kDefaultSet = "Default Tile Set"; -const QString kSession = QStringLiteral("QGeoTileWorkerSession"); -const QString kExportSession = QStringLiteral("QGeoTileExportSession"); +static const char* kDefaultSet = "Default Tile Set"; +static const QString kSession = QStringLiteral("QGeoTileWorkerSession"); +static const QString kExportSession = QStringLiteral("QGeoTileExportSession"); QGC_LOGGING_CATEGORY(QGCTileCacheLog, "QGCTileCacheLog") @@ -42,7 +42,7 @@ QGC_LOGGING_CATEGORY(QGCTileCacheLog, "QGCTileCacheLog") //----------------------------------------------------------------------------- QGCCacheWorker::QGCCacheWorker() - : _db(NULL) + : _db(nullptr) , _valid(false) , _failed(false) , _defaultSet(UINT64_MAX) @@ -54,13 +54,11 @@ QGCCacheWorker::QGCCacheWorker() , _updateTimeout(SHORT_TIMEOUT) , _hostLookupID(0) { - } //----------------------------------------------------------------------------- QGCCacheWorker::~QGCCacheWorker() { - } //----------------------------------------------------------------------------- @@ -173,13 +171,13 @@ QGCCacheWorker::run() } task->deleteLater(); //-- Check for update timeout - size_t count = _taskQueue.count(); + size_t count = static_cast(_taskQueue.count()); if(count > 100) { _updateTimeout = LONG_TIMEOUT; } else if(count < 25) { _updateTimeout = SHORT_TIMEOUT; } - if(!count || (time(0) - _lastUpdate > _updateTimeout)) { + if(!count || (time(nullptr) - _lastUpdate > _updateTimeout)) { if(_valid) { _updateTotals(); } @@ -187,7 +185,7 @@ QGCCacheWorker::run() } else { //-- Wait a bit before shutting things down _waitmutex.lock(); - int timeout = 5000; + unsigned long timeout = 5000; _waitc.wait(&_waitmutex, timeout); _waitmutex.unlock(); _mutex.lock(); @@ -201,7 +199,7 @@ QGCCacheWorker::run() } if(_db) { delete _db; - _db = NULL; + _db = nullptr; QSqlDatabase::removeDatabase(kSession); } } @@ -284,7 +282,7 @@ QGCCacheWorker::_getTile(QGCMapTask* mtask) if(query.next()) { QByteArray ar = query.value(0).toByteArray(); QString format = query.value(1).toString(); - UrlFactory::MapType type = (UrlFactory::MapType)query.value(2).toInt(); + UrlFactory::MapType type = static_cast(query.value(2).toInt()); qCDebug(QGCTileCacheLog) << "_getTile() (Found in DB) HASH:" << task->hash(); QGCCacheTile* tile = new QGCCacheTile(task->hash(), ar, format, type); task->setTileFetched(tile); @@ -320,7 +318,7 @@ QGCCacheWorker::_getTileSets(QGCMapTask* mtask) set->setBottomRightLon(query.value("bottomRightLon").toDouble()); set->setMinZoom(query.value("minZoom").toInt()); set->setMaxZoom(query.value("maxZoom").toInt()); - set->setType((UrlFactory::MapType)query.value("type").toInt()); + set->setType(static_cast(query.value("type").toInt())); set->setTotalTileCount(query.value("numTiles").toUInt()); set->setDefaultSet(query.value("defaultSet").toInt() != 0); set->setCreationDate(QDateTime::fromTime_t(query.value("date").toUInt())); @@ -413,7 +411,7 @@ QGCCacheWorker::_updateTotals() } } emit updateTotals(_totalCount, _totalSize, _defaultCount, _defaultSize); - _lastUpdate = time(0); + _lastUpdate = time(nullptr); } //----------------------------------------------------------------------------- @@ -526,14 +524,14 @@ QGCCacheWorker::_getTileDownloadList(QGCMapTask* mtask) while(query.next()) { QGCTile* tile = new QGCTile; tile->setHash(query.value("hash").toString()); - tile->setType((UrlFactory::MapType)query.value("type").toInt()); + tile->setType(static_cast(query.value("type").toInt())); tile->setX(query.value("x").toInt()); tile->setY(query.value("y").toInt()); tile->setZ(query.value("z").toInt()); tiles.append(tile); } for(int i = 0; i < tiles.size(); i++) { - s = QString("UPDATE TilesDownload SET state = %1 WHERE setID = %2 and hash = \"%3\"").arg((int)QGCTile::StateDownloading).arg(task->setID()).arg(tiles[i]->hash()); + s = QString("UPDATE TilesDownload SET state = %1 WHERE setID = %2 and hash = \"%3\"").arg(static_cast(QGCTile::StateDownloading)).arg(task->setID()).arg(tiles[i]->hash()); if(!query.exec(s)) { qWarning() << "Map Cache SQL error (set TilesDownload state):" << query.lastError().text(); } @@ -556,9 +554,9 @@ QGCCacheWorker::_updateTileDownloadState(QGCMapTask* mtask) s = QString("DELETE FROM TilesDownload WHERE setID = %1 AND hash = \"%2\"").arg(task->setID()).arg(task->hash()); } else { if(task->hash() == "*") { - s = QString("UPDATE TilesDownload SET state = %1 WHERE setID = %2").arg((int)task->state()).arg(task->setID()); + s = QString("UPDATE TilesDownload SET state = %1 WHERE setID = %2").arg(static_cast(task->state())).arg(task->setID()); } else { - s = QString("UPDATE TilesDownload SET state = %1 WHERE setID = %2 AND hash = \"%3\"").arg((int)task->state()).arg(task->setID()).arg(task->hash()); + s = QString("UPDATE TilesDownload SET state = %1 WHERE setID = %2 AND hash = \"%3\"").arg(static_cast(task->state())).arg(task->setID()).arg(task->hash()); } } if(!query.exec(s)) { diff --git a/src/QtLocationPlugin/QGeoMapReplyQGC.cpp b/src/QtLocationPlugin/QGeoMapReplyQGC.cpp index 31d9b14761217e25c16bdbb649da866dd4f086c6..c32c03f41851338da2c4242e8dfaa24a0c12911a 100644 --- a/src/QtLocationPlugin/QGeoMapReplyQGC.cpp +++ b/src/QtLocationPlugin/QGeoMapReplyQGC.cpp @@ -58,7 +58,7 @@ int QGeoTiledMapReplyQGC::_requestCount = 0; //----------------------------------------------------------------------------- QGeoTiledMapReplyQGC::QGeoTiledMapReplyQGC(QNetworkAccessManager *networkManager, const QNetworkRequest &request, const QGeoTileSpec &spec, QObject *parent) : QGeoTiledMapReply(spec, parent) - , _reply(NULL) + , _reply(nullptr) , _request(request) , _networkManager(networkManager) { @@ -73,7 +73,7 @@ QGeoTiledMapReplyQGC::QGeoTiledMapReplyQGC(QNetworkAccessManager *networkManager setFinished(true); setCached(false); } else { - QGCFetchTileTask* task = getQGCMapEngine()->createFetchTileTask((UrlFactory::MapType)spec.mapId(), spec.x(), spec.y(), spec.zoom()); + QGCFetchTileTask* task = getQGCMapEngine()->createFetchTileTask(static_cast(spec.mapId()), spec.x(), spec.y(), spec.zoom()); connect(task, &QGCFetchTileTask::tileFetched, this, &QGeoTiledMapReplyQGC::cacheReply); connect(task, &QGCMapTask::error, this, &QGeoTiledMapReplyQGC::cacheError); getQGCMapEngine()->addTask(task); @@ -93,7 +93,7 @@ QGeoTiledMapReplyQGC::_clearReply() _timer.stop(); if (_reply) { _reply->deleteLater(); - _reply = 0; + _reply = nullptr; _requestCount--; } } @@ -122,9 +122,9 @@ QGeoTiledMapReplyQGC::networkReplyFinished() return; } QByteArray a = _reply->readAll(); - QString format = getQGCMapEngine()->urlFactory()->getImageFormat((UrlFactory::MapType)tileSpec().mapId(), a); + QString format = getQGCMapEngine()->urlFactory()->getImageFormat(static_cast(tileSpec().mapId()), a); //-- Test for a specialized, elevation data (not map tile) - if ((UrlFactory::MapType)tileSpec().mapId() == UrlFactory::MapType::AirmapElevation) { + if (static_cast(tileSpec().mapId()) == UrlFactory::MapType::AirmapElevation) { a = TerrainTile::serialize(a); //-- Cache it if valid if(!a.isEmpty()) { @@ -136,7 +136,7 @@ QGeoTiledMapReplyQGC::networkReplyFinished() setMapImageData(a); if(!format.isEmpty()) { setMapImageFormat(format); - getQGCMapEngine()->cacheTile((UrlFactory::MapType)tileSpec().mapId(), tileSpec().x(), tileSpec().y(), tileSpec().zoom(), a, format); + getQGCMapEngine()->cacheTile(static_cast(tileSpec().mapId()), tileSpec().x(), tileSpec().y(), tileSpec().zoom(), a, format); } setFinished(true); } @@ -152,7 +152,7 @@ QGeoTiledMapReplyQGC::networkReplyError(QNetworkReply::NetworkError error) return; } //-- Test for a specialized, elevation data (not map tile) - if ((UrlFactory::MapType)tileSpec().mapId() == UrlFactory::MapType::AirmapElevation) { + if (static_cast(tileSpec().mapId()) == UrlFactory::MapType::AirmapElevation) { emit terrainDone(QByteArray(), error); } else { //-- Regular map tile @@ -170,7 +170,7 @@ void QGeoTiledMapReplyQGC::cacheError(QGCMapTask::TaskType type, QString /*errorString*/) { if(!getQGCMapEngine()->isInternetActive()) { - if ((UrlFactory::MapType)tileSpec().mapId() == UrlFactory::MapType::AirmapElevation) { + if (static_cast(tileSpec().mapId()) == UrlFactory::MapType::AirmapElevation) { emit terrainDone(QByteArray(), QNetworkReply::NetworkSessionFailedError); } else { setError(QGeoTiledMapReply::CommunicationError, "Network not available"); @@ -188,8 +188,8 @@ QGeoTiledMapReplyQGC::cacheError(QGCMapTask::TaskType type, QString /*errorStrin _networkManager->setProxy(tProxy); #endif _reply = _networkManager->get(_request); - _reply->setParent(0); - connect(_reply, &QNetworkReply::finished, this, &QGeoTiledMapReplyQGC::networkReplyFinished); + _reply->setParent(nullptr); + connect(_reply, &QNetworkReply::finished, this, &QGeoTiledMapReplyQGC::networkReplyFinished); connect(_reply, SIGNAL(error(QNetworkReply::NetworkError)), this, SLOT(networkReplyError(QNetworkReply::NetworkError))); #if !defined(__mobile__) _networkManager->setProxy(proxy); @@ -207,7 +207,7 @@ void QGeoTiledMapReplyQGC::cacheReply(QGCCacheTile* tile) { //-- Test for a specialized, elevation data (not map tile) - if ((UrlFactory::MapType)tileSpec().mapId() == UrlFactory::MapType::AirmapElevation) { + if (static_cast(tileSpec().mapId()) == UrlFactory::MapType::AirmapElevation) { emit terrainDone(tile->img(), QNetworkReply::NoError); } else { //-- Regular map tile diff --git a/src/QtLocationPlugin/QMLControl/QGCMapEngineManager.cc b/src/QtLocationPlugin/QMLControl/QGCMapEngineManager.cc index ca342a9d5517a0f23c36dc9d23cce6cbf43f6352..a46d63e1443e341d514a160972205512a52468ba 100644 --- a/src/QtLocationPlugin/QMLControl/QGCMapEngineManager.cc +++ b/src/QtLocationPlugin/QMLControl/QGCMapEngineManager.cc @@ -152,7 +152,7 @@ QGCMapEngineManager::startDownload(const QString& name, const QString& mapType) set->setMinZoom(_minZoom); set->setMaxZoom(_maxZoom); set->setTotalTileSize(_imageSet.tileSize); - set->setTotalTileCount(_imageSet.tileCount); + set->setTotalTileCount(static_cast(_imageSet.tileCount)); set->setType(QGCMapEngine::getTypeFromName(mapType)); QGCCreateTileSetTask* task = new QGCCreateTileSetTask(set); //-- Create Tile Set (it will also create a list of tiles to download) @@ -172,7 +172,7 @@ QGCMapEngineManager::startDownload(const QString& name, const QString& mapType) set->setMinZoom(1); set->setMaxZoom(1); set->setTotalTileSize(_elevationSet.tileSize); - set->setTotalTileCount(_elevationSet.tileCount); + set->setTotalTileCount(static_cast(_elevationSet.tileCount)); set->setType(QGCMapEngine::getTypeFromName("Airmap Elevation Data")); QGCCreateTileSetTask* task = new QGCCreateTileSetTask(set); //-- Create Tile Set (it will also create a list of tiles to download) @@ -305,7 +305,7 @@ void QGCMapEngineManager::_tileSetDeleted(quint64 setID) { //-- Tile Set successfully deleted - QGCCachedTileSet* setToDelete = NULL; + QGCCachedTileSet* setToDelete = nullptr; int i = 0; for(i = 0; i < _tileSets.count(); i++ ) { QGCCachedTileSet* set = qobject_cast(_tileSets.get(i)); @@ -436,7 +436,7 @@ QGCMapEngineManager::importSets(QString path) { dir = QDir(QDir::homePath()).filePath(QString("export_%1.db").arg(QDateTime::currentDateTime().toTime_t())); #else dir = QGCQFileDialog::getOpenFileName( - NULL, + nullptr, "Import Tile Set", QDir::homePath(), "Tile Sets (*.qgctiledb)"); @@ -547,8 +547,8 @@ QGCMapEngineManager::_updateDiskFreeSpace() QString path = getQGCMapEngine()->getCachePath(); if(!path.isEmpty()) { QStorageInfo info(path); - quint32 total = (quint32)(info.bytesTotal() / 1024); - quint32 free = (quint32)(info.bytesFree() / 1024); + quint32 total = static_cast(info.bytesTotal() / 1024); + quint32 free = static_cast(info.bytesFree() / 1024); qCDebug(QGCMapEngineManagerLog) << info.rootPath() << "has" << free << "Mbytes available."; if(_freeDiskSpace != free) { _freeDiskSpace = free; diff --git a/src/Settings/App.SettingsGroup.json b/src/Settings/App.SettingsGroup.json index 79c82b2b201a0ffc2f5d54c65f60d68c24146ac0..4e423823f3730bb15fdc8b95f573889b3469f1cb 100644 --- a/src/Settings/App.SettingsGroup.json +++ b/src/Settings/App.SettingsGroup.json @@ -235,5 +235,12 @@ "enumStrings": "System,English,български (Bulgarian),Deutsche (German),Français (French),Italiano (Italian),한국어 (Korean),Pусский (Russian),Türk (Turkish),中文 (Chinese)", "enumValues": "0,1,2,3,4,5,6,7,8,9", "defaultValue": 0 +}, +{ + "name": "disableAllPersistence", + "shortDescription": "Disable all data persistence", + "longDescription": "If this option is set, nothing will be saved to disk.", + "type": "bool", + "defaultValue": false } ] diff --git a/src/Settings/AppSettings.cc b/src/Settings/AppSettings.cc index 2e9962dce8529798e88e35678c938832f1a56013..3d7ec1c582a43f7e40512842b55c7adbc7752df0 100644 --- a/src/Settings/AppSettings.cc +++ b/src/Settings/AppSettings.cc @@ -10,6 +10,7 @@ #include "AppSettings.h" #include "QGCPalette.h" #include "QGCApplication.h" +#include "ParameterManager.h" #include #include @@ -61,7 +62,7 @@ DECLARE_SETTINGGROUP(App, "") connect(savePathFact, &Fact::rawValueChanged, this, &AppSettings::_checkSavePathDirectories); _checkSavePathDirectories(); - //-- Same for language + //-- Keep track of language changes SettingsFact* languageFact = qobject_cast(language()); connect(languageFact, &Fact::rawValueChanged, this, &AppSettings::_languageChanged); } @@ -93,6 +94,7 @@ DECLARE_SETTINGSFACT(AppSettings, enableTaisync) DECLARE_SETTINGSFACT(AppSettings, enableTaisyncVideo) DECLARE_SETTINGSFACT(AppSettings, enableMicrohard) DECLARE_SETTINGSFACT(AppSettings, language) +DECLARE_SETTINGSFACT(AppSettings, disableAllPersistence) DECLARE_SETTINGSFACT_NO_FUNC(AppSettings, indoorPalette) { diff --git a/src/Settings/AppSettings.h b/src/Settings/AppSettings.h index 920ac30e3cfbd0190a1fdbe9ce6192d374fe6471..17cb0ecfd7aa483135a9e3db40348f8d3e99dafa 100644 --- a/src/Settings/AppSettings.h +++ b/src/Settings/AppSettings.h @@ -48,6 +48,7 @@ public: DEFINE_SETTINGFACT(enableTaisyncVideo) DEFINE_SETTINGFACT(enableMicrohard) DEFINE_SETTINGFACT(language) + DEFINE_SETTINGFACT(disableAllPersistence) // Although this is a global setting it only affects ArduPilot vehicle since PX4 automatically starts the stream from the vehicle side DEFINE_SETTINGFACT(apmStartMavlinkStreams) diff --git a/src/Vehicle/MAVLinkLogManager.cc b/src/Vehicle/MAVLinkLogManager.cc index eca0bc3b3135fd765543eda0fb6b35ad2efc0fc4..04c0b71b3369a0b32652455797b4774970801a76 100644 --- a/src/Vehicle/MAVLinkLogManager.cc +++ b/src/Vehicle/MAVLinkLogManager.cc @@ -113,13 +113,13 @@ MAVLinkLogFiles::setUploaded(bool uploaded) //----------------------------------------------------------------------------- //----------------------------------------------------------------------------- MAVLinkLogProcessor::MAVLinkLogProcessor() - : _fd(NULL) + : _fd(nullptr) , _written(0) , _sequence(-1) , _numDrops(0) , _gotHeader(false) , _error(false) - , _record(NULL) + , _record(nullptr) { } @@ -135,7 +135,7 @@ MAVLinkLogProcessor::close() { if(_fd) { fclose(_fd); - _fd = NULL; + _fd = nullptr; } } @@ -143,7 +143,7 @@ MAVLinkLogProcessor::close() bool MAVLinkLogProcessor::valid() { - return (_fd != NULL) && (_record != NULL); + return (_fd != nullptr) && (_record != nullptr); } //----------------------------------------------------------------------------- @@ -300,12 +300,12 @@ MAVLinkLogManager::MAVLinkLogManager(QGCApplication* app, QGCToolbox* toolbox) : QGCTool(app, toolbox) , _enableAutoUpload(true) , _enableAutoStart(false) - , _nam(NULL) - , _currentLogfile(NULL) - , _vehicle(NULL) + , _nam(nullptr) + , _currentLogfile(nullptr) + , _vehicle(nullptr) , _logRunning(false) , _loggingDisabled(false) - , _logProcessor(NULL) + , _logProcessor(nullptr) , _deleteAfterUpload(false) , _windSpeed(-1) , _publicLog(false) @@ -487,7 +487,7 @@ MAVLinkLogManager::setPublicLog(bool pub) bool MAVLinkLogManager::uploading() { - return _currentLogfile != NULL; + return _currentLogfile != nullptr; } //----------------------------------------------------------------------------- @@ -515,7 +515,7 @@ MAVLinkLogManager::uploadLog() qWarning() << "Internal error"; } } - _currentLogfile = NULL; + _currentLogfile = nullptr; emit uploadingChanged(); } @@ -614,11 +614,15 @@ MAVLinkLogManager::cancelUpload() void MAVLinkLogManager::startLogging() { - if(_vehicle && _vehicle->px4Firmware() && !_logginDenied) { - if(_createNewLog()) { - _vehicle->startMavlinkLog(); - _logRunning = true; - emit logRunningChanged(); + //-- If we are allowed to persist data + AppSettings* appSettings = qgcApp()->toolbox()->settingsManager()->appSettings(); + if(!appSettings->disableAllPersistence()->rawValue().toBool()) { + if(_vehicle && _vehicle->px4Firmware() && !_logginDenied) { + if(_createNewLog()) { + _vehicle->startMavlinkLog(); + _logRunning = true; + emit logRunningChanged(); + } } } } @@ -644,7 +648,7 @@ MAVLinkLogManager::stopLogging() } } delete _logProcessor; - _logProcessor = NULL; + _logProcessor = nullptr; _logRunning = false; emit logRunningChanged(); } @@ -790,7 +794,7 @@ MAVLinkLogManager::_uploadFinished() if(_deleteAfterUpload) { if(_currentLogfile) { _deleteLog(_currentLogfile); - _currentLogfile = NULL; + _currentLogfile = nullptr; } } else { if(_currentLogfile) { @@ -818,7 +822,7 @@ void MAVLinkLogManager::_uploadProgress(qint64 bytesSent, qint64 bytesTotal) { if(bytesTotal) { - qreal progress = (qreal)bytesSent / (qreal)bytesTotal; + qreal progress = static_cast(bytesSent) / static_cast(bytesTotal); if(_currentLogfile) { _currentLogfile->setProgress(progress); } @@ -834,13 +838,14 @@ MAVLinkLogManager::_activeVehicleChanged(Vehicle* vehicle) // connects/disconnects. In reality, if QGC is connected to multiple vehicles, // this is called each time the user switches from one vehicle to another. So // far, I'm working on the assumption that multiple vehicles is a rare exception. - // For now, we only handle one log download at a time. + // For now, we only handle one log download at a time. The proper way is to have + // each vehicle with their own instance of this "log manager". // Disconnect the previous one (if any) if(_vehicle && _vehicle->px4Firmware()) { disconnect(_vehicle, &Vehicle::armedChanged, this, &MAVLinkLogManager::_armedChanged); disconnect(_vehicle, &Vehicle::mavlinkLogData, this, &MAVLinkLogManager::_mavlinkLogData); disconnect(_vehicle, &Vehicle::mavCommandResult, this, &MAVLinkLogManager::_mavCommandResult); - _vehicle = NULL; + _vehicle = nullptr; //-- Stop logging (if that's the case) stopLogging(); emit canStartLogChanged(); @@ -865,7 +870,7 @@ MAVLinkLogManager::_mavlinkLogData(Vehicle* /*vehicle*/, uint8_t /*target_system if(!_logProcessor->processStreamData(sequence, first_message, data)) { qCWarning(MAVLinkLogManagerLog) << "Error writing MAVLink log file:" << _logProcessor->fileName(); delete _logProcessor; - _logProcessor = NULL; + _logProcessor = nullptr; _logRunning = false; _vehicle->stopMavlinkLog(); emit logRunningChanged(); @@ -914,7 +919,7 @@ MAVLinkLogManager::_discardLog() _deleteLog(_logProcessor->record()); } delete _logProcessor; - _logProcessor = NULL; + _logProcessor = nullptr; } _logRunning = false; emit logRunningChanged(); @@ -926,18 +931,18 @@ MAVLinkLogManager::_createNewLog() { if(_logProcessor) { delete _logProcessor; - _logProcessor = NULL; + _logProcessor = nullptr; } _logProcessor = new MAVLinkLogProcessor; - if(_logProcessor->create(this, _logPath, _vehicle->id())) { + if(_logProcessor->create(this, _logPath, static_cast(_vehicle->id()))) { _insertNewLog(_logProcessor->record()); emit logFilesChanged(); } else { qCWarning(MAVLinkLogManagerLog) << "Could not create MAVLink log file:" << _logProcessor->fileName(); delete _logProcessor; - _logProcessor = NULL; + _logProcessor = nullptr; } - return _logProcessor != NULL; + return _logProcessor != nullptr; } //----------------------------------------------------------------------------- diff --git a/src/Vehicle/Vehicle.h b/src/Vehicle/Vehicle.h index 530a4ed13ae9e1aae3959bdedf9967070bc271ba..c3706980dc5e946176b8991e29f30813b7aa48d0 100644 --- a/src/Vehicle/Vehicle.h +++ b/src/Vehicle/Vehicle.h @@ -912,10 +912,10 @@ public: QString brandImageIndoor () const; QString brandImageOutdoor () const; QStringList unhealthySensors () const; - int sensorsPresentBits () const { return _onboardControlSensorsPresent; } - int sensorsEnabledBits () const { return _onboardControlSensorsEnabled; } - int sensorsHealthBits () const { return _onboardControlSensorsHealth; } - int sensorsUnhealthyBits () const { return _onboardControlSensorsUnhealthy; } + int sensorsPresentBits () const { return static_cast(_onboardControlSensorsPresent); } + int sensorsEnabledBits () const { return static_cast(_onboardControlSensorsEnabled); } + int sensorsHealthBits () const { return static_cast(_onboardControlSensorsHealth); } + int sensorsUnhealthyBits () const { return static_cast(_onboardControlSensorsUnhealthy); } QString missionFlightMode () const; QString pauseFlightMode () const; QString rtlFlightMode () const; diff --git a/src/comm/MAVLinkProtocol.cc b/src/comm/MAVLinkProtocol.cc index 8c6de29ca2640619825726bbd48af818c14da718..2d4e08da1c2c571eb1cab8b1c39d956cf19781c9 100644 --- a/src/comm/MAVLinkProtocol.cc +++ b/src/comm/MAVLinkProtocol.cc @@ -404,9 +404,13 @@ void MAVLinkProtocol::_startLogging(void) if (qgcApp()->runningUnitTests()) { return; } + AppSettings* appSettings = _app->toolbox()->settingsManager()->appSettings(); + if(appSettings->disableAllPersistence()->rawValue().toBool()) { + return; + } #ifdef __mobile__ //-- Mobile build don't write to /tmp unless told to do so - if (!_app->toolbox()->settingsManager()->appSettings()->telemetrySave()->rawValue().toBool()) { + if (!appSettings->telemetrySave()->rawValue().toBool()) { return; } #endif @@ -435,7 +439,8 @@ void MAVLinkProtocol::_stopLogging(void) if (_tempLogFile.isOpen()) { if (_closeLogFile()) { if ((_vehicleWasArmed || _app->toolbox()->settingsManager()->appSettings()->telemetrySaveNotArmed()->rawValue().toBool()) && - _app->toolbox()->settingsManager()->appSettings()->telemetrySave()->rawValue().toBool()) { + _app->toolbox()->settingsManager()->appSettings()->telemetrySave()->rawValue().toBool() && + !_app->toolbox()->settingsManager()->appSettings()->disableAllPersistence()->rawValue().toBool()) { emit saveTelemetryLog(_tempLogFile.fileName()); } else { QFile::remove(_tempLogFile.fileName()); diff --git a/src/ui/preferences/GeneralSettings.qml b/src/ui/preferences/GeneralSettings.qml index 721aabbee4533fe3ce513e8bda1c42f07720483a..ad4a90a634bdc032e48388e8a625883b0a98bfc3 100644 --- a/src/ui/preferences/GeneralSettings.qml +++ b/src/ui/preferences/GeneralSettings.qml @@ -262,22 +262,6 @@ QGCView { property Fact _audioMuted: QGroundControl.settingsManager.appSettings.audioMuted } - FactCheckBox { - id: promptSaveLog - text: qsTr("Save telemetry log after each flight") - fact: _telemetrySave - visible: _telemetrySave.visible - property Fact _telemetrySave: QGroundControl.settingsManager.appSettings.telemetrySave - } - - FactCheckBox { - text: qsTr("Save telemetry log even if vehicle was not armed") - fact: _telemetrySaveNotArmed - visible: _telemetrySaveNotArmed.visible - enabled: promptSaveLog.checked - property Fact _telemetrySaveNotArmed: QGroundControl.settingsManager.appSettings.telemetrySaveNotArmed - } - FactCheckBox { text: qsTr("AutoLoad Missions") fact: _autoLoad @@ -370,7 +354,72 @@ QGCView { } Item { width: 1; height: _margins } + QGCLabel { + id: loggingSectionLabel + text: qsTr("Data Persistence") + } + Rectangle { + Layout.preferredHeight: dataPersistCol.height + (_margins * 2) + Layout.preferredWidth: dataPersistCol.width + (_margins * 2) + color: qgcPal.windowShade + Layout.fillWidth: true + ColumnLayout { + id: dataPersistCol + anchors.margins: _margins + anchors.top: parent.top + anchors.horizontalCenter: parent.horizontalCenter + spacing: _margins * 1.5 + FactCheckBox { + id: disableDataPersistence + text: qsTr("Disable all data persistence") + fact: _disableDataPersistence + visible: _disableDataPersistence.visible + property Fact _disableDataPersistence: QGroundControl.settingsManager.appSettings.disableAllPersistence + } + QGCLabel { + text: qsTr("When Data Persistence is disabled, all telemetry logging and map tile caching is disabled and not written to disk.") + wrapMode: Text.WordWrap + font.pointSize: ScreenTools.smallFontPointSize + Layout.maximumWidth: logIfNotArmed.visible ? logIfNotArmed.width : disableDataPersistence.width * 1.5 + } + } + } + + Item { width: 1; height: _margins } + QGCLabel { + text: qsTr("Telemetry Logs from Vehicle") + } + Rectangle { + Layout.preferredHeight: loggingCol.height + (_margins * 2) + Layout.preferredWidth: loggingCol.width + (_margins * 2) + color: qgcPal.windowShade + Layout.fillWidth: true + ColumnLayout { + id: loggingCol + anchors.margins: _margins + anchors.top: parent.top + anchors.horizontalCenter: parent.horizontalCenter + spacing: _margins + FactCheckBox { + id: promptSaveLog + text: qsTr("Save log after each flight") + fact: _telemetrySave + visible: _telemetrySave.visible + enabled: !disableDataPersistence.checked + property Fact _telemetrySave: QGroundControl.settingsManager.appSettings.telemetrySave + } + FactCheckBox { + id: logIfNotArmed + text: qsTr("Save logs even if vehicle was not armed") + fact: _telemetrySaveNotArmed + visible: _telemetrySaveNotArmed.visible + enabled: promptSaveLog.checked && !disableDataPersistence.checked + property Fact _telemetrySaveNotArmed: QGroundControl.settingsManager.appSettings.telemetrySaveNotArmed + } + } + } + Item { width: 1; height: _margins } QGCLabel { id: flyViewSectionLabel text: qsTr("Fly View") diff --git a/src/ui/preferences/MavlinkSettings.qml b/src/ui/preferences/MavlinkSettings.qml index 2db2cc1d958272481712c9e77bb06b7396424a59..e0757696dcf7a2d39f17aceb850925558cbf6acb 100644 --- a/src/ui/preferences/MavlinkSettings.qml +++ b/src/ui/preferences/MavlinkSettings.qml @@ -33,8 +33,10 @@ Rectangle { property real _columnSpacing: ScreenTools.defaultFontPixelHeight * 0.25 property bool _uploadedSelected: false property var _activeVehicle: QGroundControl.multiVehicleManager.activeVehicle - property var _showMavlinkLog: QGroundControl.corePlugin.options.showMavlinkLogOptions + property bool _showMavlinkLog: QGroundControl.corePlugin.options.showMavlinkLogOptions property bool _showAPMStreamRates: QGroundControl.apmFirmwareSupported && QGroundControl.settingsManager.apmMavlinkStreamRateSettings.visible + property Fact _disableDataPersistenceFact: QGroundControl.settingsManager.appSettings.disableAllPersistence + property bool _disableDataPersistence: _disableDataPersistenceFact ? _disableDataPersistenceFact.rawValue : false QGCPalette { id: qgcPal } @@ -196,49 +198,49 @@ Rectangle { QGCLabel { text: qsTr("Raw Sensors") } FactComboBox { - fact: QGroundControl.settingsManager.apmMavlinkStreamRateSettings.streamRateRawSensors + fact: QGroundControl.settingsManager.apmMavlinkStreamRateSettings ? QGroundControl.settingsManager.apmMavlinkStreamRateSettings.streamRateRawSensors : null indexModel: false Layout.preferredWidth: _valueWidth } QGCLabel { text: qsTr("Extended Status") } FactComboBox { - fact: QGroundControl.settingsManager.apmMavlinkStreamRateSettings.streamRateExtendedStatus + fact: QGroundControl.settingsManager.apmMavlinkStreamRateSettings ? QGroundControl.settingsManager.apmMavlinkStreamRateSettings.streamRateExtendedStatus : null indexModel: false Layout.preferredWidth: _valueWidth } QGCLabel { text: qsTr("RC Channel") } FactComboBox { - fact: QGroundControl.settingsManager.apmMavlinkStreamRateSettings.streamRateRCChannels + fact: QGroundControl.settingsManager.apmMavlinkStreamRateSettings ? QGroundControl.settingsManager.apmMavlinkStreamRateSettings.streamRateRCChannels : null indexModel: false Layout.preferredWidth: _valueWidth } QGCLabel { text: qsTr("Position") } FactComboBox { - fact: QGroundControl.settingsManager.apmMavlinkStreamRateSettings.streamRatePosition + fact: QGroundControl.settingsManager.apmMavlinkStreamRateSettings ? QGroundControl.settingsManager.apmMavlinkStreamRateSettings.streamRatePosition : null indexModel: false Layout.preferredWidth: _valueWidth } QGCLabel { text: qsTr("Extra 1") } FactComboBox { - fact: QGroundControl.settingsManager.apmMavlinkStreamRateSettings.streamRateExtra1 + fact: QGroundControl.settingsManager.apmMavlinkStreamRateSettings ? QGroundControl.settingsManager.apmMavlinkStreamRateSettings.streamRateExtra1 : null indexModel: false Layout.preferredWidth: _valueWidth } QGCLabel { text: qsTr("Extra 2") } FactComboBox { - fact: QGroundControl.settingsManager.apmMavlinkStreamRateSettings.streamRateExtra2 + fact: QGroundControl.settingsManager.apmMavlinkStreamRateSettings ? QGroundControl.settingsManager.apmMavlinkStreamRateSettings.streamRateExtra2 : null indexModel: false Layout.preferredWidth: _valueWidth } QGCLabel { text: qsTr("Extra 3") } FactComboBox { - fact: QGroundControl.settingsManager.apmMavlinkStreamRateSettings.streamRateExtra3 + fact: QGroundControl.settingsManager.apmMavlinkStreamRateSettings ? QGroundControl.settingsManager.apmMavlinkStreamRateSettings.streamRateExtra3 : null indexModel: false Layout.preferredWidth: _valueWidth } @@ -370,14 +372,14 @@ Rectangle { QGCButton { text: qsTr("Start Logging") width: (_valueWidth * 0.5) - (ScreenTools.defaultFontPixelWidth * 0.5) - enabled: !QGroundControl.mavlinkLogManager.logRunning && QGroundControl.mavlinkLogManager.canStartLog + enabled: !QGroundControl.mavlinkLogManager.logRunning && QGroundControl.mavlinkLogManager.canStartLog && !_disableDataPersistence onClicked: QGroundControl.mavlinkLogManager.startLogging() anchors.verticalCenter: parent.verticalCenter } QGCButton { text: qsTr("Stop Logging") width: (_valueWidth * 0.5) - (ScreenTools.defaultFontPixelWidth * 0.5) - enabled: QGroundControl.mavlinkLogManager.logRunning + enabled: QGroundControl.mavlinkLogManager.logRunning && !_disableDataPersistence onClicked: QGroundControl.mavlinkLogManager.stopLogging() anchors.verticalCenter: parent.verticalCenter } @@ -387,6 +389,7 @@ Rectangle { QGCCheckBox { text: qsTr("Enable automatic logging") checked: QGroundControl.mavlinkLogManager.enableAutoStart + enabled: !_disableDataPersistence onClicked: { QGroundControl.mavlinkLogManager.enableAutoStart = checked } @@ -428,9 +431,10 @@ Rectangle { text: qsTr("Email address for Log Upload:") } QGCTextField { - id: emailField - text: QGroundControl.mavlinkLogManager.emailAddress - width: _valueWidth + id: emailField + text: QGroundControl.mavlinkLogManager.emailAddress + width: _valueWidth + enabled: !_disableDataPersistence inputMethodHints: Qt.ImhNoAutoUppercase | Qt.ImhEmailCharactersOnly anchors.verticalCenter: parent.verticalCenter onEditingFinished: { @@ -448,9 +452,10 @@ Rectangle { text: qsTr("Default Description:") } QGCTextField { - id: descField - text: QGroundControl.mavlinkLogManager.description - width: _valueWidth + id: descField + text: QGroundControl.mavlinkLogManager.description + width: _valueWidth + enabled: !_disableDataPersistence anchors.verticalCenter: parent.verticalCenter onEditingFinished: { saveItems(); @@ -467,9 +472,10 @@ Rectangle { text: qsTr("Default Upload URL") } QGCTextField { - id: urlField - text: QGroundControl.mavlinkLogManager.uploadURL - width: _valueWidth + id: urlField + text: QGroundControl.mavlinkLogManager.uploadURL + width: _valueWidth + enabled: !_disableDataPersistence inputMethodHints: Qt.ImhNoAutoUppercase | Qt.ImhUrlCharactersOnly anchors.verticalCenter: parent.verticalCenter onEditingFinished: { @@ -487,9 +493,10 @@ Rectangle { text: qsTr("Video URL:") } QGCTextField { - id: videoUrlField - text: QGroundControl.mavlinkLogManager.videoURL - width: _valueWidth + id: videoUrlField + text: QGroundControl.mavlinkLogManager.videoURL + width: _valueWidth + enabled: !_disableDataPersistence inputMethodHints: Qt.ImhNoAutoUppercase | Qt.ImhUrlCharactersOnly anchors.verticalCenter: parent.verticalCenter } @@ -504,8 +511,9 @@ Rectangle { text: qsTr("Wind Speed:") } QGCComboBox { - id: windCombo - width: _valueWidth + id: windCombo + width: _valueWidth + enabled: !_disableDataPersistence model: ListModel { id: windItems ListElement { text: "Please Select"; value: -1 } @@ -540,8 +548,9 @@ Rectangle { text: qsTr("Flight Rating:") } QGCComboBox { - id: ratingCombo - width: _valueWidth + id: ratingCombo + width: _valueWidth + enabled: !_disableDataPersistence model: ListModel { id: ratingItems ListElement { text: "Please Select"; value: "notset"} @@ -582,6 +591,7 @@ Rectangle { frameVisible: false font.pointSize: ScreenTools.defaultFontPointSize text: QGroundControl.mavlinkLogManager.feedback + enabled: !_disableDataPersistence style: TextAreaStyle { textColor: qgcPal.windowShade backgroundColor: qgcPal.text @@ -593,6 +603,7 @@ Rectangle { QGCCheckBox { text: qsTr("Make this log publicly available") checked: QGroundControl.mavlinkLogManager.publicLog + enabled: !_disableDataPersistence onClicked: { QGroundControl.mavlinkLogManager.publicLog = checked } @@ -603,6 +614,7 @@ Rectangle { id: autoUploadCheck text: qsTr("Enable automatic log uploads") checked: QGroundControl.mavlinkLogManager.enableAutoUpload + enabled: !_disableDataPersistence onClicked: { saveItems(); if(checked && QGroundControl.mavlinkLogManager.emailAddress === "") @@ -614,7 +626,7 @@ Rectangle { QGCCheckBox { text: qsTr("Delete log file after uploading") checked: QGroundControl.mavlinkLogManager.deleteAfterUpload - enabled: autoUploadCheck.checked + enabled: autoUploadCheck.checked && !_disableDataPersistence onClicked: { QGroundControl.mavlinkLogManager.deleteAfterUpload = checked }