Unverified Commit 2f5324fd authored by Gus Grubba's avatar Gus Grubba Committed by GitHub

Merge pull request #7341 from mavlink/disableLogging

Disable Logging
parents 9e381539 109931a4
......@@ -186,6 +186,8 @@
<file alias="AlertAircraft.svg">src/FlightMap/Images/AlertAircraft.svg</file>
<file alias="AwarenessAircraft.svg">src/FlightMap/Images/AwarenessAircraft.svg</file>
<file alias="check.svg">resources/check.svg</file>
<file alias="no-logging.svg">src/AutoPilotPlugins/PX4/Images/no-logging.svg</file>
<file alias="no-logging-light.svg">src/AutoPilotPlugins/PX4/Images/no-logging-light.svg</file>
</qresource>
<qresource prefix="/res">
<file alias="action.svg">resources/action.svg</file>
......
<?xml version="1.0" encoding="utf-8"?>
<!-- Generator: Adobe Illustrator 23.0.3, SVG Export Plug-In . SVG Version: 6.00 Build 0) -->
<svg version="1.1" id="Layer_1" xmlns="http://www.w3.org/2000/svg" xmlns:xlink="http://www.w3.org/1999/xlink" x="0px" y="0px"
viewBox="0 0 72 72" style="enable-background:new 0 0 72 72;" xml:space="preserve">
<style type="text/css">
.st0{fill:none;stroke:#A10000;stroke-width:4;stroke-linecap:round;stroke-miterlimit:10;}
.st1{fill:none;stroke:#A10000;stroke-width:4;stroke-miterlimit:10;}
</style>
<path d="M18.089,56.362c-2.034,0-3.689-1.655-3.689-3.689V19.327c0-2.034,1.655-3.689,3.689-3.689l27.492,0
c2.034,0,3.689,1.655,3.689,3.689v0.459l-2.68,0v-0.459c0-0.557-0.453-1.009-1.009-1.009H18.089c-0.557,0-1.009,0.453-1.009,1.009
v33.346c0,0.557,0.453,1.009,1.009,1.009H45.58c0.556,0,1.009-0.453,1.009-1.009v-0.459h0.001v-7.247h2.68v7.706
c0,2.034-1.655,3.689-3.689,3.689H18.089z M37.842,49.247c-0.268,0-0.527-0.079-0.748-0.229c-0.445-0.3-0.667-0.835-0.567-1.363
l1.23-6.429c0.01-0.053,0.028-0.097,0.044-0.13c0.029-0.107,0.068-0.219,0.138-0.332l10.74-16.986c0.006-0.01,0.012-0.02,0.019-0.03
c0.002-0.003,0.012-0.02,0.012-0.02l1.579-2.28c0.139-0.19,0.9-1.136,2.271-1.136c0.468,0,0.942,0.115,1.408,0.341
c1.349,0.656,2.557,1.573,2.69,1.676c0.112,0.087,0.205,0.185,0.28,0.293c0.121,0.172,1.179,1.75,0.345,3.121
c-0.345,0.566-1.289,1.952-1.574,2.368L44.392,45.148c-0.064,0.096-0.14,0.153-0.181,0.184l-0.003,0.002
c-0.003,0.003-0.006,0.007-0.009,0.011c-0.037,0.046-0.099,0.124-0.199,0.188l-5.434,3.501
C38.348,49.173,38.098,49.247,37.842,49.247z M39.746,45.083l1.124-0.724L40,43.754L39.746,45.083z M42.919,42.52l9.642-14.516
l-2.357-1.63L40.89,41.107L42.919,42.52z M54.051,25.778c0.397-0.588,0.682-1.02,0.854-1.29c-0.018-0.051-0.044-0.115-0.077-0.181
c-0.442-0.319-1.225-0.852-2.032-1.244c-0.063-0.03-0.122-0.045-0.18-0.045c-0.089,0-0.161,0.036-0.199,0.059l-0.736,1.063
L54.051,25.778z M19.812,43.954c-0.739,0-1.34-0.601-1.34-1.34c0-0.739,0.601-1.34,1.34-1.34h9.492c0.739,0,1.34,0.601,1.34,1.34
c0,0.739-0.601,1.34-1.34,1.34H19.812z M19.812,35.15c-0.739,0-1.34-0.601-1.34-1.34c0-0.739,0.601-1.34,1.34-1.34l15.777,0
c0.739,0,1.34,0.601,1.34,1.34c0,0.739-0.601,1.34-1.34,1.34H19.812z M19.812,26.403c-0.739,0-1.34-0.601-1.34-1.34
c0-0.739,0.601-1.34,1.34-1.34h22.063c0.739,0,1.34,0.601,1.34,1.34c0,0.739-0.601,1.34-1.34,1.34H19.812z"/>
<g>
<line class="st0" x1="12.502" y1="59.445" x2="59.268" y2="12.554"/>
<circle class="st1" cx="36" cy="36" r="33.84"/>
</g>
</svg>
<?xml version="1.0" encoding="utf-8"?>
<!-- Generator: Adobe Illustrator 23.0.3, SVG Export Plug-In . SVG Version: 6.00 Build 0) -->
<svg version="1.1" id="Layer_1" xmlns="http://www.w3.org/2000/svg" xmlns:xlink="http://www.w3.org/1999/xlink" x="0px" y="0px"
viewBox="0 0 72 72" style="enable-background:new 0 0 72 72;" xml:space="preserve">
<style type="text/css">
.st0{fill:#FFFFFF;}
.st1{fill:none;stroke:#A10000;stroke-width:4;stroke-linecap:round;stroke-miterlimit:10;}
.st2{fill:none;stroke:#A10000;stroke-width:4;stroke-miterlimit:10;}
</style>
<path class="st0" d="M18.089,56.362c-2.034,0-3.689-1.655-3.689-3.689V19.327c0-2.034,1.655-3.689,3.689-3.689l27.492,0
c2.034,0,3.689,1.655,3.689,3.689v0.459l-2.68,0v-0.459c0-0.557-0.453-1.009-1.009-1.009H18.089c-0.557,0-1.009,0.453-1.009,1.009
v33.346c0,0.557,0.453,1.009,1.009,1.009H45.58c0.556,0,1.009-0.453,1.009-1.009v-0.459h0.001v-7.247h2.68v7.706
c0,2.034-1.655,3.689-3.689,3.689H18.089z M37.842,49.247c-0.268,0-0.527-0.079-0.748-0.229c-0.445-0.3-0.667-0.835-0.567-1.363
l1.23-6.429c0.01-0.053,0.028-0.097,0.044-0.13c0.029-0.107,0.068-0.219,0.138-0.332l10.74-16.986c0.006-0.01,0.012-0.02,0.019-0.03
c0.002-0.003,0.012-0.02,0.012-0.02l1.579-2.28c0.139-0.19,0.9-1.136,2.271-1.136c0.468,0,0.942,0.115,1.408,0.341
c1.349,0.656,2.557,1.573,2.69,1.676c0.112,0.087,0.205,0.185,0.28,0.293c0.121,0.172,1.179,1.75,0.345,3.121
c-0.345,0.566-1.289,1.952-1.574,2.368L44.392,45.148c-0.064,0.096-0.14,0.153-0.181,0.184l-0.003,0.002
c-0.003,0.003-0.006,0.007-0.009,0.011c-0.037,0.046-0.099,0.124-0.199,0.188l-5.434,3.501
C38.348,49.173,38.098,49.247,37.842,49.247z M39.746,45.083l1.124-0.724L40,43.754L39.746,45.083z M42.919,42.52l9.642-14.516
l-2.357-1.63L40.89,41.107L42.919,42.52z M54.051,25.778c0.397-0.588,0.682-1.02,0.854-1.29c-0.018-0.051-0.044-0.115-0.077-0.181
c-0.442-0.319-1.225-0.852-2.032-1.244c-0.063-0.03-0.122-0.045-0.18-0.045c-0.089,0-0.161,0.036-0.199,0.059l-0.736,1.063
L54.051,25.778z M19.812,43.954c-0.739,0-1.34-0.601-1.34-1.34c0-0.739,0.601-1.34,1.34-1.34h9.492c0.739,0,1.34,0.601,1.34,1.34
c0,0.739-0.601,1.34-1.34,1.34H19.812z M19.812,35.15c-0.739,0-1.34-0.601-1.34-1.34c0-0.739,0.601-1.34,1.34-1.34l15.777,0
c0.739,0,1.34,0.601,1.34,1.34c0,0.739-0.601,1.34-1.34,1.34H19.812z M19.812,26.403c-0.739,0-1.34-0.601-1.34-1.34
c0-0.739,0.601-1.34,1.34-1.34h22.063c0.739,0,1.34,0.601,1.34,1.34c0,0.739-0.601,1.34-1.34,1.34H19.812z"/>
<g>
<line class="st1" x1="12.502" y1="59.445" x2="59.268" y2="12.554"/>
<circle class="st2" cx="36" cy="36" r="33.84"/>
</g>
</svg>
......@@ -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
}
}
}
}
}
......
......@@ -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<int>(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<UrlFactory::MapType>(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<quint64>(set.tileX1) - static_cast<quint64>(set.tileX0) + 1) * (static_cast<quint64>(set.tileY1) - static_cast<quint64>(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<int>(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<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)));
}
//-----------------------------------------------------------------------------
......@@ -345,7 +349,7 @@ int
QGCMapEngine::long2elevationTileX(double lon, int z)
{
Q_UNUSED(z);
return (int)(floor((lon + 180.0) / srtm1TileSize));
return static_cast<int>(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<int>(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<double>(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<double>(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<double>(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<double>(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<quint64>(getMaxDiskCache()) * 1024L * 1024L;
if(!_prunning && defaultsize > maxSize) {
//-- Prune Disk Cache
_prunning = true;
......
......@@ -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<size_t>(_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<UrlFactory::MapType>(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<UrlFactory::MapType>(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<UrlFactory::MapType>(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<int>(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<int>(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<int>(task->state())).arg(task->setID()).arg(task->hash());
}
}
if(!query.exec(s)) {
......
......@@ -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<UrlFactory::MapType>(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<UrlFactory::MapType>(tileSpec().mapId()), a);
//-- Test for a specialized, elevation data (not map tile)
if ((UrlFactory::MapType)tileSpec().mapId() == UrlFactory::MapType::AirmapElevation) {
if (static_cast<UrlFactory::MapType>(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<UrlFactory::MapType>(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<UrlFactory::MapType>(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<UrlFactory::MapType>(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<UrlFactory::MapType>(tileSpec().mapId()) == UrlFactory::MapType::AirmapElevation) {
emit terrainDone(tile->img(), QNetworkReply::NoError);
} else {
//-- Regular map tile
......
......@@ -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<quint32>(_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<quint32>(_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<QGCCachedTileSet*>(_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<quint32>(info.bytesTotal() / 1024);
quint32 free = static_cast<quint32>(info.bytesFree() / 1024);
qCDebug(QGCMapEngineManagerLog) << info.rootPath() << "has" << free << "Mbytes available.";
if(_freeDiskSpace != free) {
_freeDiskSpace = free;
......
......@@ -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
}
]
......@@ -10,6 +10,7 @@
#include "AppSettings.h"
#include "QGCPalette.h"
#include "QGCApplication.h"
#include "ParameterManager.h"
#include <QQmlEngine>
#include <QtQml>
......@@ -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<SettingsFact*>(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)
{
......
......@@ -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)
......
......@@ -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();