From 14f18101343a8c9733e1d4b0cfc53737f427018e Mon Sep 17 00:00:00 2001 From: leonardosimovic Date: Wed, 26 Jul 2023 09:54:10 +0200 Subject: [PATCH 1/3] perf(MapEngine): avoid some unnecessary string copies --- src/QtLocationPlugin/QGCMapEngine.cpp | 12 ++++++------ src/QtLocationPlugin/QGCMapEngine.h | 16 ++++++++-------- src/QtLocationPlugin/QGCMapEngineData.h | 2 +- src/QtLocationPlugin/QGCMapUrlEngine.cpp | 19 ++++++++++++------- src/QtLocationPlugin/QGCMapUrlEngine.h | 14 +++++++------- src/QtLocationPlugin/QGCTileCacheWorker.cpp | 6 +++--- 6 files changed, 37 insertions(+), 32 deletions(-) diff --git a/src/QtLocationPlugin/QGCMapEngine.cpp b/src/QtLocationPlugin/QGCMapEngine.cpp index 15774db3683..6f29fc64571 100644 --- a/src/QtLocationPlugin/QGCMapEngine.cpp +++ b/src/QtLocationPlugin/QGCMapEngine.cpp @@ -200,7 +200,7 @@ QGCMapEngine::addTask(QGCMapTask* task) //----------------------------------------------------------------------------- void -QGCMapEngine::cacheTile(QString type, int x, int y, int z, const QByteArray& image, const QString &format, qulonglong set) +QGCMapEngine::cacheTile(const QString& type, int x, int y, int z, const QByteArray& image, const QString &format, qulonglong set) { QString hash = getTileHash(type, x, y, z); cacheTile(type, hash, image, format, set); @@ -208,7 +208,7 @@ QGCMapEngine::cacheTile(QString type, int x, int y, int z, const QByteArray& ima //----------------------------------------------------------------------------- void -QGCMapEngine::cacheTile(QString type, const QString& hash, const QByteArray& image, const QString& format, qulonglong set) +QGCMapEngine::cacheTile(const QString& type, const QString& hash, const QByteArray& image, const QString& format, qulonglong set) { AppSettings* appSettings = qgcApp()->toolbox()->settingsManager()->appSettings(); //-- If we are allowed to persist data, save tile to cache @@ -220,7 +220,7 @@ QGCMapEngine::cacheTile(QString type, const QString& hash, const QByteArray& ima //----------------------------------------------------------------------------- QString -QGCMapEngine::getTileHash(QString type, int x, int y, int z) +QGCMapEngine::getTileHash(const QString& type, int x, int y, int z) { return QString::asprintf("%010d%08d%08d%03d", getQGCMapEngine()->urlFactory()->getIdFromType(type), x, y, z); } @@ -235,7 +235,7 @@ QGCMapEngine::hashToType(const QString& hash) //----------------------------------------------------------------------------- QGCFetchTileTask* -QGCMapEngine::createFetchTileTask(QString type, int x, int y, int z) +QGCMapEngine::createFetchTileTask(const QString& type, int x, int y, int z) { QString hash = getTileHash(type, x, y, z); QGCFetchTileTask* task = new QGCFetchTileTask(hash); @@ -244,7 +244,7 @@ QGCMapEngine::createFetchTileTask(QString type, int x, int y, int z) //----------------------------------------------------------------------------- QGCTileSet -QGCMapEngine::getTileCount(int zoom, double topleftLon, double topleftLat, double bottomRightLon, double bottomRightLat, QString mapType) +QGCMapEngine::getTileCount(int zoom, double topleftLon, double topleftLat, double bottomRightLon, double bottomRightLat, const QString& mapType) { if(zoom < 1) zoom = 1; if(zoom > MAX_MAP_ZOOM) zoom = MAX_MAP_ZOOM; @@ -368,7 +368,7 @@ QGCMapEngine::_pruned() //----------------------------------------------------------------------------- int -QGCMapEngine::concurrentDownloads(QString type) +QGCMapEngine::concurrentDownloads(const QString& type) { Q_UNUSED(type); // TODO : We may want different values depending on diff --git a/src/QtLocationPlugin/QGCMapEngine.h b/src/QtLocationPlugin/QGCMapEngine.h index 4f4668d64c4..5f8bce7f2c1 100644 --- a/src/QtLocationPlugin/QGCMapEngine.h +++ b/src/QtLocationPlugin/QGCMapEngine.h @@ -36,13 +36,13 @@ class QGCMapEngine : public QObject void init (); void addTask (QGCMapTask *task); - void cacheTile (QString type, int x, int y, int z, const QByteArray& image, const QString& format, qulonglong set = UINT64_MAX); - void cacheTile (QString type, const QString& hash, const QByteArray& image, const QString& format, qulonglong set = UINT64_MAX); - QGCFetchTileTask* createFetchTileTask (QString type, int x, int y, int z); + void cacheTile (const QString& type, int x, int y, int z, const QByteArray& image, const QString& format, qulonglong set = UINT64_MAX); + void cacheTile (const QString& type, const QString& hash, const QByteArray& image, const QString& format, qulonglong set = UINT64_MAX); + QGCFetchTileTask* createFetchTileTask (const QString& type, int x, int y, int z); QStringList getMapNameList (); const QString userAgent () { return _userAgent; } void setUserAgent (const QString& ua) { _userAgent = ua; } - QString hashToType (const QString& hash); + QString hashToType (const QString& hash); quint32 getMaxDiskCache (); void setMaxDiskCache (quint32 size); quint32 getMaxMemCache (); @@ -56,13 +56,13 @@ class QGCMapEngine : public QObject UrlFactory* urlFactory () { return _urlFactory; } //-- Tile Math - static QGCTileSet getTileCount (int zoom, double topleftLon, double topleftLat, double bottomRightLon, double bottomRightLat, QString mapType); - static QString getTileHash (QString type, int x, int y, int z); - static QString getTypeFromName (const QString &name); + static QGCTileSet getTileCount (int zoom, double topleftLon, double topleftLat, double bottomRightLon, double bottomRightLat, const QString& mapType); + static QString getTileHash (const QString& type, int x, int y, int z); + static QString getTypeFromName (const QString& name); static QString bigSizeToString (quint64 size); static QString storageFreeSizeToString(quint64 size_MB); static QString numberToString (quint64 number); - static int concurrentDownloads (QString type); + static int concurrentDownloads (const QString& type); private slots: void _updateTotals (quint32 totaltiles, quint64 totalsize, quint32 defaulttiles, quint64 defaultsize); diff --git a/src/QtLocationPlugin/QGCMapEngineData.h b/src/QtLocationPlugin/QGCMapEngineData.h index 64cdbc14468..14fe489e3cb 100644 --- a/src/QtLocationPlugin/QGCMapEngineData.h +++ b/src/QtLocationPlugin/QGCMapEngineData.h @@ -76,7 +76,7 @@ class QGCCacheTile : public QObject { Q_OBJECT public: - QGCCacheTile (const QString hash, const QByteArray img, const QString format, QString type, qulonglong set = UINT64_MAX) + QGCCacheTile (const QString& hash, const QByteArray& img, const QString& format, const QString& type, qulonglong set = UINT64_MAX) : _set(set) , _hash(hash) , _img(img) diff --git a/src/QtLocationPlugin/QGCMapUrlEngine.cpp b/src/QtLocationPlugin/QGCMapUrlEngine.cpp index 24edbda93fc..3e076255f20 100644 --- a/src/QtLocationPlugin/QGCMapUrlEngine.cpp +++ b/src/QtLocationPlugin/QGCMapUrlEngine.cpp @@ -106,7 +106,7 @@ QString UrlFactory::getImageFormat(int id, const QByteArray& image) { } //----------------------------------------------------------------------------- -QString UrlFactory::getImageFormat(QString type, const QByteArray& image) { +QString UrlFactory::getImageFormat(const QString& type, const QByteArray& image) { if (_providersTable.find(type) != _providersTable.end()) { return _providersTable[type]->getImageFormat(image); } else { @@ -127,7 +127,7 @@ QNetworkRequest UrlFactory::getTileURL(int id, int x, int y, int zoom, } //----------------------------------------------------------------------------- -QNetworkRequest UrlFactory::getTileURL(QString type, int x, int y, int zoom, +QNetworkRequest UrlFactory::getTileURL(const QString& type, int x, int y, int zoom, QNetworkAccessManager* networkManager) { if (_providersTable.find(type) != _providersTable.end()) { return _providersTable[type]->getTileURL(x, y, zoom, networkManager); @@ -137,7 +137,7 @@ QNetworkRequest UrlFactory::getTileURL(QString type, int x, int y, int zoom, } //----------------------------------------------------------------------------- -quint32 UrlFactory::averageSizeForType(QString type) { +quint32 UrlFactory::averageSizeForType(const QString& type) { if (_providersTable.find(type) != _providersTable.end()) { return _providersTable[type]->getAverageSize(); } @@ -177,21 +177,26 @@ MapProvider* UrlFactory::getMapProviderFromId(int id) return nullptr; } +//----------------------------------------------------------------------------- // Todo : qHash produce a uint bigger than max(int) // There is still a low probability for this to // generate similar hash for different types -int UrlFactory::getIdFromType(QString type) { return (int)(qHash(type)>>1); } +int +UrlFactory::getIdFromType(const QString& type) +{ + return (int)(qHash(type)>>1); +} //----------------------------------------------------------------------------- int -UrlFactory::long2tileX(QString mapType, double lon, int z) +UrlFactory::long2tileX(const QString& mapType, double lon, int z) { return _providersTable[mapType]->long2tileX(lon, z); } //----------------------------------------------------------------------------- int -UrlFactory::lat2tileY(QString mapType, double lat, int z) +UrlFactory::lat2tileY(const QString& mapType, double lat, int z) { return _providersTable[mapType]->lat2tileY(lat, z); } @@ -199,7 +204,7 @@ UrlFactory::lat2tileY(QString mapType, double lat, int z) //----------------------------------------------------------------------------- QGCTileSet -UrlFactory::getTileCount(int zoom, double topleftLon, double topleftLat, double bottomRightLon, double bottomRightLat, QString mapType) +UrlFactory::getTileCount(int zoom, double topleftLon, double topleftLat, double bottomRightLon, double bottomRightLat, const QString& mapType) { return _providersTable[mapType]->getTileCount(zoom, topleftLon, topleftLat, bottomRightLon, bottomRightLat); } diff --git a/src/QtLocationPlugin/QGCMapUrlEngine.h b/src/QtLocationPlugin/QGCMapUrlEngine.h index 898cf474704..6179fd4fa0d 100644 --- a/src/QtLocationPlugin/QGCMapUrlEngine.h +++ b/src/QtLocationPlugin/QGCMapUrlEngine.h @@ -33,26 +33,26 @@ class UrlFactory : public QObject { UrlFactory (); ~UrlFactory (); - QNetworkRequest getTileURL (QString type, int x, int y, int zoom, QNetworkAccessManager* networkManager); + QNetworkRequest getTileURL (const QString& type, int x, int y, int zoom, QNetworkAccessManager* networkManager); QNetworkRequest getTileURL (int id, int x, int y, int zoom, QNetworkAccessManager* networkManager); - QString getImageFormat (QString type, const QByteArray& image); + QString getImageFormat (const QString& type, const QByteArray& image); QString getImageFormat (int id , const QByteArray& image); - quint32 averageSizeForType (QString type); + quint32 averageSizeForType (const QString& type); - int long2tileX(QString mapType, double lon, int z); - int lat2tileY(QString mapType, double lat, int z); + int long2tileX(const QString& mapType, double lon, int z); + int lat2tileY(const QString& mapType, double lat, int z); QHash getProviderTable(){return _providersTable;} - int getIdFromType(QString type); + int getIdFromType(const QString& type); QString getTypeFromId(int id); MapProvider* getMapProviderFromId(int id); QGCTileSet getTileCount(int zoom, double topleftLon, double topleftLat, double bottomRightLon, double bottomRightLat, - QString mapType); + const QString& mapType); bool isElevation(int mapId); diff --git a/src/QtLocationPlugin/QGCTileCacheWorker.cpp b/src/QtLocationPlugin/QGCTileCacheWorker.cpp index 1540bc8fc7f..f8f918876d8 100644 --- a/src/QtLocationPlugin/QGCTileCacheWorker.cpp +++ b/src/QtLocationPlugin/QGCTileCacheWorker.cpp @@ -329,11 +329,11 @@ QGCCacheWorker::_getTile(QGCMapTask* mtask) QString s = QString("SELECT tile, format, type FROM Tiles WHERE hash = \"%1\"").arg(task->hash()); if(query.exec(s)) { if(query.next()) { - QByteArray ar = query.value(0).toByteArray(); - QString format = query.value(1).toString(); + const QByteArray& arrray = query.value(0).toByteArray(); + const QString& format = query.value(1).toString(); QString type = getQGCMapEngine()->urlFactory()->getTypeFromId(query.value(2).toInt()); qCDebug(QGCTileCacheLog) << "_getTile() (Found in DB) HASH:" << task->hash(); - QGCCacheTile* tile = new QGCCacheTile(task->hash(), ar, format, type); + QGCCacheTile* tile = new QGCCacheTile(task->hash(), arrray, format, type); task->setTileFetched(tile); found = true; } From ab9913c3cec380c88f1945fbecc0fa9e9579c946 Mon Sep 17 00:00:00 2001 From: leonardosimovic Date: Thu, 20 Jul 2023 15:39:01 +0200 Subject: [PATCH 2/3] feat: replace airmap terrain with copernicus --- src/QmlControls/QGroundControlQmlGlobal.h | 6 + src/QtLocationPlugin/ElevationMapProvider.cpp | 20 +- src/QtLocationPlugin/ElevationMapProvider.h | 5 +- src/QtLocationPlugin/QGCMapTileSet.cpp | 2 +- src/QtLocationPlugin/QGCMapUrlEngine.cpp | 4 +- src/QtLocationPlugin/QGCMapUrlEngine.h | 1 + .../QMLControl/OfflineMap.qml | 2 +- .../QMLControl/QGCMapEngineManager.cc | 10 +- src/Terrain/TerrainQuery.cc | 24 +- src/TerrainTile.cc | 252 ++++++++---------- src/TerrainTile.h | 27 +- 11 files changed, 171 insertions(+), 182 deletions(-) diff --git a/src/QmlControls/QGroundControlQmlGlobal.h b/src/QmlControls/QGroundControlQmlGlobal.h index f613e3b5f8b..ff17e4452d0 100644 --- a/src/QmlControls/QGroundControlQmlGlobal.h +++ b/src/QmlControls/QGroundControlQmlGlobal.h @@ -106,6 +106,10 @@ class QGroundControlQmlGlobal : public QGCTool Q_PROPERTY(bool hasMAVLinkInspector READ hasMAVLinkInspector CONSTANT) + //------------------------------------------------------------------------- + // Elevation Provider + Q_PROPERTY(QString elevationProviderName READ elevationProviderName CONSTANT) + #if defined(QGC_ENABLE_PAIRING) Q_PROPERTY(PairingManager* pairingManager READ pairingManager CONSTANT) #endif @@ -203,6 +207,8 @@ class QGroundControlQmlGlobal : public QGCTool bool hasMAVLinkInspector () { return true; } #endif + QString elevationProviderName () { return UrlFactory::kCopernicusElevationProviderKey; } + bool singleFirmwareSupport (); bool singleVehicleSupport (); bool px4ProFirmwareSupported (); diff --git a/src/QtLocationPlugin/ElevationMapProvider.cpp b/src/QtLocationPlugin/ElevationMapProvider.cpp index c362464b503..851f162eca6 100644 --- a/src/QtLocationPlugin/ElevationMapProvider.cpp +++ b/src/QtLocationPlugin/ElevationMapProvider.cpp @@ -6,32 +6,40 @@ #include "QGCMapEngine.h" #include "TerrainTile.h" +/* +License for the COPERNICUS dataset hosted on https://terrain-ce.suite.auterion.com/: + +© DLR e.V. 2010-2014 and © Airbus Defence and Space GmbH 2014-2018 provided under COPERNICUS +by the European Union and ESA; all rights reserved. + +*/ + ElevationProvider::ElevationProvider(const QString& imageFormat, quint32 averageSize, QGeoMapType::MapStyle mapType, QObject* parent) - : MapProvider(QStringLiteral("https://api.airmap.com/"), imageFormat, averageSize, mapType, parent) {} + : MapProvider(QStringLiteral("https://terrain-ce.suite.auterion.com/"), imageFormat, averageSize, mapType, parent) {} //----------------------------------------------------------------------------- -int AirmapElevationProvider::long2tileX(const double lon, const int z) const { +int CopernicusElevationProvider::long2tileX(const double lon, const int z) const { Q_UNUSED(z) return static_cast(floor((lon + 180.0) / TerrainTile::tileSizeDegrees)); } //----------------------------------------------------------------------------- -int AirmapElevationProvider::lat2tileY(const double lat, const int z) const { +int CopernicusElevationProvider::lat2tileY(const double lat, const int z) const { Q_UNUSED(z) return static_cast(floor((lat + 90.0) / TerrainTile::tileSizeDegrees)); } -QString AirmapElevationProvider::_getURL(const int x, const int y, const int zoom, QNetworkAccessManager* networkManager) { +QString CopernicusElevationProvider::_getURL(const int x, const int y, const int zoom, QNetworkAccessManager* networkManager) { Q_UNUSED(networkManager) Q_UNUSED(zoom) - return QString("https://api.airmap.com/elevation/v1/ele/carpet?points=%1,%2,%3,%4") + return QString("https://terrain-ce.suite.auterion.com/api/v1/carpet?points=%1,%2,%3,%4") .arg(static_cast(y) * TerrainTile::tileSizeDegrees - 90.0) .arg(static_cast(x) * TerrainTile::tileSizeDegrees - 180.0) .arg(static_cast(y + 1) * TerrainTile::tileSizeDegrees - 90.0) .arg(static_cast(x + 1) * TerrainTile::tileSizeDegrees - 180.0); } -QGCTileSet AirmapElevationProvider::getTileCount(const int zoom, const double topleftLon, +QGCTileSet CopernicusElevationProvider::getTileCount(const int zoom, const double topleftLon, const double topleftLat, const double bottomRightLon, const double bottomRightLat) const { QGCTileSet set; diff --git a/src/QtLocationPlugin/ElevationMapProvider.h b/src/QtLocationPlugin/ElevationMapProvider.h index ce2cbea7345..842056918ac 100644 --- a/src/QtLocationPlugin/ElevationMapProvider.h +++ b/src/QtLocationPlugin/ElevationMapProvider.h @@ -24,10 +24,10 @@ class ElevationProvider : public MapProvider { // ----------------------------------------------------------- // Airmap Elevation -class AirmapElevationProvider : public ElevationProvider { +class CopernicusElevationProvider : public ElevationProvider { Q_OBJECT public: - AirmapElevationProvider(QObject* parent = nullptr) + CopernicusElevationProvider(QObject* parent = nullptr) : ElevationProvider(QStringLiteral("bin"), AVERAGE_AIRMAP_ELEV_SIZE, QGeoMapType::StreetMap, parent) {} @@ -42,4 +42,3 @@ class AirmapElevationProvider : public ElevationProvider { protected: QString _getURL(const int x, const int y, const int zoom, QNetworkAccessManager* networkManager) override; }; - diff --git a/src/QtLocationPlugin/QGCMapTileSet.cpp b/src/QtLocationPlugin/QGCMapTileSet.cpp index e8ad05d1afb..0e18f537466 100644 --- a/src/QtLocationPlugin/QGCMapTileSet.cpp +++ b/src/QtLocationPlugin/QGCMapTileSet.cpp @@ -287,7 +287,7 @@ QGCCachedTileSet::_networkReplyFinished() qCDebug(QGCCachedTileSetLog) << "Tile fetched" << hash; QByteArray image = reply->readAll(); QString type = getQGCMapEngine()->hashToType(hash); - if (type == "Airmap Elevation" ) { + if (type == UrlFactory::kCopernicusElevationProviderKey) { image = TerrainTile::serializeFromAirMapJson(image); } QString format = getQGCMapEngine()->urlFactory()->getImageFormat(type, image); diff --git a/src/QtLocationPlugin/QGCMapUrlEngine.cpp b/src/QtLocationPlugin/QGCMapUrlEngine.cpp index 3e076255f20..4ee56bdf87a 100644 --- a/src/QtLocationPlugin/QGCMapUrlEngine.cpp +++ b/src/QtLocationPlugin/QGCMapUrlEngine.cpp @@ -32,6 +32,8 @@ QGC_LOGGING_CATEGORY(QGCMapUrlEngineLog, "QGCMapUrlEngineLog") #include #include +const char* UrlFactory::kCopernicusElevationProviderKey = "Copernicus Elevation"; + //----------------------------------------------------------------------------- UrlFactory::UrlFactory() : _timeout(5 * 1000) { @@ -75,7 +77,7 @@ UrlFactory::UrlFactory() : _timeout(5 * 1000) { _providersTable["VWorld Street Map"] = new VWorldStreetMapProvider(this); _providersTable["VWorld Satellite Map"] = new VWorldSatMapProvider(this); - _providersTable["Airmap Elevation"] = new AirmapElevationProvider(this); + _providersTable[kCopernicusElevationProviderKey] = new CopernicusElevationProvider(this); _providersTable["Japan-GSI Contour"] = new JapanStdMapProvider(this); _providersTable["Japan-GSI Seamless"] = new JapanSeamlessMapProvider(this); diff --git a/src/QtLocationPlugin/QGCMapUrlEngine.h b/src/QtLocationPlugin/QGCMapUrlEngine.h index 6179fd4fa0d..b43301b0dc4 100644 --- a/src/QtLocationPlugin/QGCMapUrlEngine.h +++ b/src/QtLocationPlugin/QGCMapUrlEngine.h @@ -29,6 +29,7 @@ class UrlFactory : public QObject { Q_OBJECT public: + static const char* kCopernicusElevationProviderKey; UrlFactory (); ~UrlFactory (); diff --git a/src/QtLocationPlugin/QMLControl/OfflineMap.qml b/src/QtLocationPlugin/QMLControl/OfflineMap.qml index b6a3d83ac32..5db10d441d9 100644 --- a/src/QtLocationPlugin/QMLControl/OfflineMap.qml +++ b/src/QtLocationPlugin/QMLControl/OfflineMap.qml @@ -522,7 +522,7 @@ Item { Row { spacing: ScreenTools.defaultFontPixelWidth anchors.horizontalCenter: parent.horizontalCenter - visible: !_defaultSet && mapType !== "Airmap Elevation" + visible: !_defaultSet && mapType !== QGroundControl.elevationProviderName QGCLabel { text: qsTr("Zoom Levels:"); width: infoView._labelWidth; } QGCLabel { text: offlineMapView._currentSelection ? (offlineMapView._currentSelection.minZoom + " - " + offlineMapView._currentSelection.maxZoom) : ""; horizontalAlignment: Text.AlignRight; width: infoView._valueWidth; } } diff --git a/src/QtLocationPlugin/QMLControl/QGCMapEngineManager.cc b/src/QtLocationPlugin/QMLControl/QGCMapEngineManager.cc index d1ed4d5eb58..ec4fe2dae67 100644 --- a/src/QtLocationPlugin/QMLControl/QGCMapEngineManager.cc +++ b/src/QtLocationPlugin/QMLControl/QGCMapEngineManager.cc @@ -28,6 +28,8 @@ QGC_LOGGING_CATEGORY(QGCMapEngineManagerLog, "QGCMapEngineManagerLog") static const char* kQmlOfflineMapKeyName = "QGCOfflineMap"; +static const auto kElevationMapType = UrlFactory::kCopernicusElevationProviderKey; + //----------------------------------------------------------------------------- QGCMapEngineManager::QGCMapEngineManager(QGCApplication* app, QGCToolbox* toolbox) : QGCTool(app, toolbox) @@ -84,7 +86,7 @@ QGCMapEngineManager::updateForCurrentView(double lon0, double lat0, double lon1, _imageSet += set; } if (_fetchElevation) { - QGCTileSet set = QGCMapEngine::getTileCount(1, lon0, lat0, lon1, lat1, "Airmap Elevation"); + QGCTileSet set = QGCMapEngine::getTileCount(1, lon0, lat0, lon1, lat1, kElevationMapType); _elevationSet += set; } @@ -159,9 +161,9 @@ QGCMapEngineManager::startDownload(const QString& name, const QString& mapType) } else { qWarning() << "QGCMapEngineManager::startDownload() No Tiles to save"; } - if (mapType != "Airmap Elevation" && _fetchElevation) { + if (mapType != kElevationMapType && _fetchElevation) { QGCCachedTileSet* set = new QGCCachedTileSet(name + " Elevation"); - set->setMapTypeStr("Airmap Elevation"); + set->setMapTypeStr(kElevationMapType); set->setTopleftLat(_topleftLat); set->setTopleftLon(_topleftLon); set->setBottomRightLat(_bottomRightLat); @@ -170,7 +172,7 @@ QGCMapEngineManager::startDownload(const QString& name, const QString& mapType) set->setMaxZoom(1); set->setTotalTileSize(_elevationSet.tileSize); set->setTotalTileCount(static_cast(_elevationSet.tileCount)); - set->setType("Airmap Elevation"); + set->setType(kElevationMapType); QGCCreateTileSetTask* task = new QGCCreateTileSetTask(set); //-- Create Tile Set (it will also create a list of tiles to download) connect(task, &QGCCreateTileSetTask::tileSetSaved, this, &QGCMapEngineManager::_tileSetSaved); diff --git a/src/Terrain/TerrainQuery.cc b/src/Terrain/TerrainQuery.cc index 8e32d005fd6..42edfb6a432 100644 --- a/src/Terrain/TerrainQuery.cc +++ b/src/Terrain/TerrainQuery.cc @@ -32,6 +32,8 @@ QGC_LOGGING_CATEGORY(TerrainQueryVerboseLog, "TerrainQueryVerboseLog") Q_GLOBAL_STATIC(TerrainAtCoordinateBatchManager, _TerrainAtCoordinateBatchManager) Q_GLOBAL_STATIC(TerrainTileManager, _terrainTileManager) +static const auto kMapType = UrlFactory::kCopernicusElevationProviderKey; + TerrainAirMapQuery::TerrainAirMapQuery(QObject* parent) : TerrainQueryInterface(parent) { @@ -442,13 +444,17 @@ bool TerrainTileManager::getAltitudesForCoordinates(const QList& altitudes.push_back(elevation); } else { if (_state != State::Downloading) { - QNetworkRequest request = getQGCMapEngine()->urlFactory()->getTileURL("Airmap Elevation", getQGCMapEngine()->urlFactory()->long2tileX("Airmap Elevation",coordinate.longitude(), 1), getQGCMapEngine()->urlFactory()->lat2tileY("Airmap Elevation", coordinate.latitude(), 1), 1, &_networkManager); + QNetworkRequest request = getQGCMapEngine()->urlFactory()->getTileURL( + kMapType, getQGCMapEngine()->urlFactory()->long2tileX(kMapType, coordinate.longitude(), 1), + getQGCMapEngine()->urlFactory()->lat2tileY(kMapType, coordinate.latitude(), 1), + 1, + &_networkManager); qCDebug(TerrainQueryLog) << "TerrainTileManager::getAltitudesForCoordinates query from database" << request.url(); QGeoTileSpec spec; - spec.setX(getQGCMapEngine()->urlFactory()->long2tileX("Airmap Elevation", coordinate.longitude(), 1)); - spec.setY(getQGCMapEngine()->urlFactory()->lat2tileY("Airmap Elevation", coordinate.latitude(), 1)); + spec.setX(getQGCMapEngine()->urlFactory()->long2tileX(kMapType, coordinate.longitude(), 1)); + spec.setY(getQGCMapEngine()->urlFactory()->lat2tileY(kMapType, coordinate.latitude(), 1)); spec.setZoom(1); - spec.setMapId(getQGCMapEngine()->urlFactory()->getIdFromType("Airmap Elevation")); + spec.setMapId(getQGCMapEngine()->urlFactory()->getIdFromType(kMapType)); QGeoTiledMapReplyQGC* reply = new QGeoTiledMapReplyQGC(&_networkManager, request, spec); connect(reply, &QGeoTiledMapReplyQGC::terrainDone, this, &TerrainTileManager::_terrainDone); _state = State::Downloading; @@ -465,7 +471,7 @@ bool TerrainTileManager::getAltitudesForCoordinates(const QList& void TerrainTileManager::_tileFailed(void) { - QList noAltitudes; + QList noAltitudes; for (const QueuedRequestInfo_t& requestInfo: _requestQueue) { if (requestInfo.queryMode == QueryMode::QueryModeCoordinates) { @@ -489,7 +495,7 @@ void TerrainTileManager::_terrainDone(QByteArray responseBytes, QNetworkReply::N // remove from download queue QGeoTileSpec spec = reply->tileSpec(); - QString hash = QGCMapEngine::getTileHash("Airmap Elevation", spec.x(), spec.y(), spec.zoom()); + QString hash = QGCMapEngine::getTileHash(kMapType, spec.x(), spec.y(), spec.zoom()); // handle potential errors if (error != QNetworkReply::NoError) { @@ -556,9 +562,9 @@ void TerrainTileManager::_terrainDone(QByteArray responseBytes, QNetworkReply::N QString TerrainTileManager::_getTileHash(const QGeoCoordinate& coordinate) { QString ret = QGCMapEngine::getTileHash( - "Airmap Elevation", - getQGCMapEngine()->urlFactory()->long2tileX("Airmap Elevation", coordinate.longitude(), 1), - getQGCMapEngine()->urlFactory()->lat2tileY("Airmap Elevation", coordinate.latitude(), 1), + kMapType, + getQGCMapEngine()->urlFactory()->long2tileX(kMapType, coordinate.longitude(), 1), + getQGCMapEngine()->urlFactory()->lat2tileY(kMapType, coordinate.latitude(), 1), 1); qCDebug(TerrainQueryVerboseLog) << "Computing unique tile hash for " << coordinate << ret; diff --git a/src/TerrainTile.cc b/src/TerrainTile.cc index 654847fc58b..c651f2b1374 100644 --- a/src/TerrainTile.cc +++ b/src/TerrainTile.cc @@ -31,140 +31,120 @@ const char* TerrainTile::_jsonMinElevationKey = "min"; const char* TerrainTile::_jsonAvgElevationKey = "avg"; const char* TerrainTile::_jsonCarpetKey = "carpet"; -TerrainTile::TerrainTile() - : _minElevation(-1.0) - , _maxElevation(-1.0) - , _avgElevation(-1.0) - , _data(nullptr) - , _gridSizeLat(-1) - , _gridSizeLon(-1) - , _isValid(false) +TerrainTile::TerrainTile(const QByteArray& byteArray) { + // Copy tile info + _tileInfo = *reinterpret_cast(byteArray.constData()); -} - -TerrainTile::~TerrainTile() -{ - if (_data) { - for (int i = 0; i < _gridSizeLat; i++) { - delete[] _data[i]; - } - delete[] _data; - _data = nullptr; + // Check feasibility + if ((_tileInfo.neLon - _tileInfo.swLon) < 0.0 || (_tileInfo.neLat - _tileInfo.swLat) < 0.0) { + qCWarning(TerrainTileLog) << this << "Tile extent is infeasible"; + _isValid = false; + return; } -} -TerrainTile::TerrainTile(QByteArray byteArray) - : _minElevation(-1.0) - , _maxElevation(-1.0) - , _avgElevation(-1.0) - , _data(nullptr) - , _gridSizeLat(-1) - , _gridSizeLon(-1) - , _isValid(false) -{ + _cellSizeLat = (_tileInfo.neLat - _tileInfo.swLat) / _tileInfo.gridSizeLat; + _cellSizeLon = (_tileInfo.neLon - _tileInfo.swLon) / _tileInfo.gridSizeLon; + + qCDebug(TerrainTileLog) << this << "TileInfo: south west: " << _tileInfo.swLat << _tileInfo.swLon; + qCDebug(TerrainTileLog) << this << "TileInfo: north east: " << _tileInfo.neLat << _tileInfo.neLon; + qCDebug(TerrainTileLog) << this << "TileInfo: dimensions: " << _tileInfo.gridSizeLat << "by" << _tileInfo.gridSizeLat; + qCDebug(TerrainTileLog) << this << "TileInfo: min, max, avg: " << _tileInfo.minElevation << _tileInfo.maxElevation << _tileInfo.avgElevation; + qCDebug(TerrainTileLog) << this << "TileInfo: cell size: " << _cellSizeLat << _cellSizeLon; + int cTileHeaderBytes = static_cast(sizeof(TileInfo_t)); int cTileBytesAvailable = byteArray.size(); if (cTileBytesAvailable < cTileHeaderBytes) { - qWarning() << "Terrain tile binary data too small for TileInfo_s header"; + qCWarning(TerrainTileLog) << "Terrain tile binary data too small for TileInfo_s header"; return; } - const TileInfo_t* tileInfo = reinterpret_cast(byteArray.constData()); - _southWest.setLatitude(tileInfo->swLat); - _southWest.setLongitude(tileInfo->swLon); - _northEast.setLatitude(tileInfo->neLat); - _northEast.setLongitude(tileInfo->neLon); - _minElevation = tileInfo->minElevation; - _maxElevation = tileInfo->maxElevation; - _avgElevation = tileInfo->avgElevation; - _gridSizeLat = tileInfo->gridSizeLat; - _gridSizeLon = tileInfo->gridSizeLon; - - qCDebug(TerrainTileLog) << "Loading terrain tile: " << _southWest << " - " << _northEast; - qCDebug(TerrainTileLog) << "min:max:avg:sizeLat:sizeLon" << _minElevation << _maxElevation << _avgElevation << _gridSizeLat << _gridSizeLon; - - int cTileDataBytes = static_cast(sizeof(int16_t)) * _gridSizeLat * _gridSizeLon; + int cTileDataBytes = static_cast(sizeof(int16_t)) * _tileInfo.gridSizeLat * _tileInfo.gridSizeLon; if (cTileBytesAvailable < cTileHeaderBytes + cTileDataBytes) { - qWarning() << "Terrain tile binary data too small for tile data"; + qCWarning(TerrainTileLog) << "Terrain tile binary data too small for tile data"; return; } - _data = new int16_t*[_gridSizeLat]; - for (int k = 0; k < _gridSizeLat; k++) { - _data[k] = new int16_t[_gridSizeLon]; + _data = new int16_t*[_tileInfo.gridSizeLat]; + for (int k = 0; k < _tileInfo.gridSizeLat; k++) { + _data[k] = new int16_t[_tileInfo.gridSizeLon]; } int valueIndex = 0; const int16_t* pTileData = reinterpret_cast(&reinterpret_cast(byteArray.constData())[cTileHeaderBytes]); - for (int i = 0; i < _gridSizeLat; i++) { - for (int j = 0; j < _gridSizeLon; j++) { + for (int i = 0; i < _tileInfo.gridSizeLat; i++) { + for (int j = 0; j < _tileInfo.gridSizeLon; j++) { _data[i][j] = pTileData[valueIndex++]; } } _isValid = true; +} - return; +TerrainTile::~TerrainTile() +{ + if (!_data) { + return; + } + + for (unsigned i = 0; i < static_cast(_tileInfo.gridSizeLat); i++) { + delete[] _data[i]; + } + + delete[] _data; } double TerrainTile::elevation(const QGeoCoordinate& coordinate) const { - if (_isValid && _southWest.isValid() && _northEast.isValid()) { - qCDebug(TerrainTileLog) << "elevation: " << coordinate << " , in sw " << _southWest << " , ne " << _northEast; - - // The lat/lon values in _northEast and _southWest coordinates can have rounding errors such that the coordinate - // request may be slightly outside the tile box specified by these values. So we clamp the incoming values to the - // edges of the tile if needed. - - double clampedLon = qMax(coordinate.longitude(), _southWest.longitude()); - double clampedLat = qMax(coordinate.latitude(), _southWest.latitude()); - - // Calc the index of the southernmost and westernmost index data value - int lonIndex = qFloor((clampedLon - _southWest.longitude()) / tileValueSpacingDegrees); - int latIndex = qFloor((clampedLat - _southWest.latitude()) / tileValueSpacingDegrees); - - // Calc how far along in between the known values the requested lat/lon is fractionally - double lonIndexLongitude = _southWest.longitude() + (static_cast(lonIndex) * tileValueSpacingDegrees); - double lonFraction = (clampedLon - lonIndexLongitude) / tileValueSpacingDegrees; - double latIndexLatitude = _southWest.latitude() + (static_cast(latIndex) * tileValueSpacingDegrees); - double latFraction = (clampedLat - latIndexLatitude) / tileValueSpacingDegrees; - - // Calc the elevation as the average across the four known points - double known00 = _data[latIndex][lonIndex]; - double known01 = _data[latIndex][lonIndex+1]; - double known10 = _data[latIndex+1][lonIndex]; - double known11 = _data[latIndex+1][lonIndex+1]; - double lonValue1 = known00 + ((known01 - known00) * lonFraction); - double lonValue2 = known10 + ((known11 - known10) * lonFraction); - double latValue = lonValue1 + ((lonValue2 - lonValue1) * latFraction); - - return latValue; - } else { - qCWarning(TerrainTileLog) << "elevation: Internal error - invalid tile"; + if (!_isValid || !_data) { + qCWarning(TerrainTileLog) << this << "Request for elevation, but tile is invalid."; return qQNaN(); } -} -QGeoCoordinate TerrainTile::centerCoordinate(void) const -{ - return _southWest.atDistanceAndAzimuth(_southWest.distanceTo(_northEast) / 2.0, _southWest.azimuthTo(_northEast)); + const double latDeltaSw = coordinate.latitude() - _tileInfo.swLat; + const double lonDeltaSw = coordinate.longitude() - _tileInfo.swLon; + + const int16_t latIndex = qFloor(latDeltaSw / _cellSizeLat); + const int16_t lonIndex = qFloor(lonDeltaSw / _cellSizeLon); + + const bool latIndexInvalid = latIndex < 0 || latIndex > (_tileInfo.gridSizeLat - 1); + const bool lonIndexInvalid = lonIndex < 0 || lonIndex > (_tileInfo.gridSizeLon - 1); + + if (latIndexInvalid || lonIndexInvalid) { + qCWarning(TerrainTileLog) << this << "Internal error: coordinate" << coordinate << "outside tile bounds"; + return qQNaN(); + } + + const auto elevation = _data[latIndex][lonIndex]; + + // Print warning if elevation is outside min/max of tile meta data + if (elevation < _tileInfo.minElevation) { + qCWarning(TerrainTileLog) << this << "Warning: elevation read is below min elevation in tile:" << elevation << "<" << _tileInfo.minElevation; + } + else if (elevation > _tileInfo.maxElevation) { + qCWarning(TerrainTileLog) << this << "Warning: elevation read is above max elevation in tile:" << elevation << ">" << _tileInfo.maxElevation; + } + +#ifdef QT_DEBUG + qCDebug(TerrainTileLog) << this << "latIndex, lonIndex:" << latIndex << lonIndex << "elevation:" << elevation; +#endif + + return static_cast(elevation); } -QByteArray TerrainTile::serializeFromAirMapJson(QByteArray input) +QByteArray TerrainTile::serializeFromAirMapJson(const QByteArray& input) { QJsonParseError parseError; QJsonDocument document = QJsonDocument::fromJson(input, &parseError); if (parseError.error != QJsonParseError::NoError) { - QByteArray emptyArray; - return emptyArray; + qCWarning(TerrainTileLog) << "TerrainTile::serializeFromAirMapJson: Terrain tile json doc parse error" << parseError.errorString(); + return QByteArray(); } if (!document.isObject()) { - qCDebug(TerrainTileLog) << "Terrain tile json doc is no object"; - QByteArray emptyArray; - return emptyArray; + qCWarning(TerrainTileLog) << "TerrainTile::serializeFromAirMapJson: Terrain tile json doc is no object"; + return QByteArray(); } QJsonObject rootObject = document.object(); @@ -174,15 +154,13 @@ QByteArray TerrainTile::serializeFromAirMapJson(QByteArray input) { _jsonDataKey, QJsonValue::Object, true }, }; if (!JsonHelper::validateKeys(rootObject, rootVersionKeyInfoList, errorString)) { - qCDebug(TerrainTileLog) << "Error in reading json: " << errorString; - QByteArray emptyArray; - return emptyArray; + qCWarning(TerrainTileLog) << "TerrainTile::serializeFromAirMapJson: Error in reading json: " << errorString; + return QByteArray(); } if (rootObject[_jsonStatusKey].toString() != "success") { - qCDebug(TerrainTileLog) << "Invalid terrain tile."; - QByteArray emptyArray; - return emptyArray; + qCWarning(TerrainTileLog) << "TerrainTile::serializeFromAirMapJson: Invalid terrain tile."; + return QByteArray(); } const QJsonObject& dataObject = rootObject[_jsonDataKey].toObject(); QList dataVersionKeyInfoList = { @@ -191,9 +169,8 @@ QByteArray TerrainTile::serializeFromAirMapJson(QByteArray input) { _jsonCarpetKey, QJsonValue::Array, true }, }; if (!JsonHelper::validateKeys(dataObject, dataVersionKeyInfoList, errorString)) { - qCDebug(TerrainTileLog) << "Error in reading json: " << errorString; - QByteArray emptyArray; - return emptyArray; + qCWarning(TerrainTileLog) << "TerrainTile::serializeFromAirMapJson: Error in reading json: " << errorString; + return QByteArray(); } // Bounds @@ -203,18 +180,24 @@ QByteArray TerrainTile::serializeFromAirMapJson(QByteArray input) { _jsonNorthEastKey, QJsonValue::Array, true }, }; if (!JsonHelper::validateKeys(boundsObject, boundsVersionKeyInfoList, errorString)) { - qCDebug(TerrainTileLog) << "Error in reading json: " << errorString; - QByteArray emptyArray; - return emptyArray; + qCWarning(TerrainTileLog) << "TerrainTile::serializeFromAirMapJson: Error in reading json: " << errorString; + return QByteArray(); } const QJsonArray& swArray = boundsObject[_jsonSouthWestKey].toArray(); const QJsonArray& neArray = boundsObject[_jsonNorthEastKey].toArray(); if (swArray.count() < 2 || neArray.count() < 2 ) { - qCDebug(TerrainTileLog) << "Incomplete bounding location"; - QByteArray emptyArray; - return emptyArray; + qCWarning(TerrainTileLog) << "TerrainTile::serializeFromAirMapJson: Incomplete bounding location"; + return QByteArray(); } + const double swLat = swArray[0].toDouble(); + const double swLon = swArray[1].toDouble(); + const double neLat = neArray[0].toDouble(); + const double neLon = neArray[1].toDouble(); + + qCDebug(TerrainTileLog) << "Serialize: swArray: south west: " << (40.42 - swLat) << (-3.23 - swLon); + qCDebug(TerrainTileLog) << "Serialize: neArray: north east: " << neLat << neLon; + // Stats const QJsonObject& statsObject = dataObject[_jsonStatsKey].toObject(); QList statsVersionKeyInfoList = { @@ -223,18 +206,14 @@ QByteArray TerrainTile::serializeFromAirMapJson(QByteArray input) { _jsonAvgElevationKey, QJsonValue::Double, true }, }; if (!JsonHelper::validateKeys(statsObject, statsVersionKeyInfoList, errorString)) { - qCDebug(TerrainTileLog) << "Error in reading json: " << errorString; - QByteArray emptyArray; - return emptyArray; + qCWarning(TerrainTileLog) << "TerrainTile::serializeFromAirMapJson: Error in reading json: " << errorString; + return QByteArray(); } - // Carpet const QJsonArray& carpetArray = dataObject[_jsonCarpetKey].toArray(); - int gridSizeLat = carpetArray.count(); - int gridSizeLon = carpetArray[0].toArray().count(); - - TileInfo_t tileInfo; + // Tile meta data + TerrainTile::TileInfo_t tileInfo; tileInfo.swLat = swArray[0].toDouble(); tileInfo.swLon = swArray[1].toDouble(); tileInfo.neLat = neArray[0].toDouble(); @@ -242,41 +221,34 @@ QByteArray TerrainTile::serializeFromAirMapJson(QByteArray input) tileInfo.minElevation = static_cast(statsObject[_jsonMinElevationKey].toInt()); tileInfo.maxElevation = static_cast(statsObject[_jsonMaxElevationKey].toInt()); tileInfo.avgElevation = statsObject[_jsonAvgElevationKey].toDouble(); - tileInfo.gridSizeLat = static_cast(gridSizeLat); - tileInfo.gridSizeLon = static_cast(gridSizeLon); - - // We require 1-arc second value spacing - double neCornerLatExpected = tileInfo.swLat + ((tileInfo.gridSizeLat - 1) * tileValueSpacingDegrees); - double neCornerLonExpected = tileInfo.swLon + ((tileInfo.gridSizeLon - 1) * tileValueSpacingDegrees); - if (!QGC::fuzzyCompare(tileInfo.neLat, neCornerLatExpected) || !QGC::fuzzyCompare(tileInfo.neLon, neCornerLonExpected)) { - qCWarning(TerrainTileLog) << QStringLiteral("serialize: Internal error - distance between values incorrect neExpected(%1, %2) neActual(%3, %4) sw(%5, %6) gridSize(%7, %8)") - .arg(neCornerLatExpected).arg(neCornerLonExpected).arg(tileInfo.neLat).arg(tileInfo.neLon).arg(tileInfo.swLat).arg(tileInfo.swLon).arg(tileInfo.gridSizeLat).arg(tileInfo.gridSizeLon); - QByteArray emptyArray; - return emptyArray; - } + tileInfo.gridSizeLat = static_cast(carpetArray.count()); + tileInfo.gridSizeLon = static_cast(carpetArray[0].toArray().count()); - int cTileHeaderBytes = static_cast(sizeof(TileInfo_t)); - int cTileDataBytes = static_cast(sizeof(int16_t)) * gridSizeLat * gridSizeLon; + qCDebug(TerrainTileLog) << "Serialize: TileInfo: south west: " << tileInfo.swLat << tileInfo.swLon; + qCDebug(TerrainTileLog) << "Serialize: TileInfo: north east: " << tileInfo.neLat << tileInfo.neLon; + + const auto cTileNumHeaderBytes = static_cast(sizeof(TileInfo_t)); + const auto cTileNumDataBytes = static_cast(sizeof(int16_t)) * tileInfo.gridSizeLat * tileInfo.gridSizeLon; - QByteArray byteArray(cTileHeaderBytes + cTileDataBytes, 0); + QByteArray res; + res.resize(cTileNumHeaderBytes + cTileNumDataBytes); - TileInfo_t* pTileInfo = reinterpret_cast(byteArray.data()); - int16_t* pTileData = reinterpret_cast(&reinterpret_cast(byteArray.data())[cTileHeaderBytes]); + TileInfo_t* pTileInfo = reinterpret_cast(res.data()); + int16_t* pTileData = reinterpret_cast(&reinterpret_cast(res.data())[cTileNumHeaderBytes]); *pTileInfo = tileInfo; int valueIndex = 0; - for (int i = 0; i < gridSizeLat; i++) { + for (unsigned i = 0; i < static_cast(tileInfo.gridSizeLat); i++) { const QJsonArray& row = carpetArray[i].toArray(); - if (row.count() < gridSizeLon) { - qCDebug(TerrainTileLog) << "Expected row array of " << gridSizeLon << ", instead got " << row.count(); - QByteArray emptyArray; - return emptyArray; + if (row.count() < tileInfo.gridSizeLon) { + qCDebug(TerrainTileLog) << "Expected row array of " << tileInfo.gridSizeLon << ", instead got " << row.count(); + return QByteArray(); } - for (int j = 0; j < gridSizeLon; j++) { + for (unsigned j = 0; j < static_cast(tileInfo.gridSizeLon); j++) { pTileData[valueIndex++] = static_cast(row[j].toDouble()); } } - return byteArray; + return res; } diff --git a/src/TerrainTile.h b/src/TerrainTile.h index bd1417df621..01345939089 100644 --- a/src/TerrainTile.h +++ b/src/TerrainTile.h @@ -16,7 +16,7 @@ Q_DECLARE_LOGGING_CATEGORY(TerrainTileLog) class TerrainTile { public: - TerrainTile(); + TerrainTile() = default; ~TerrainTile(); /** @@ -24,7 +24,7 @@ class TerrainTile * * @param document */ - TerrainTile(QByteArray byteArray); + TerrainTile(const QByteArray& byteArray); /** * Check whether valid data is loaded @@ -46,30 +46,29 @@ class TerrainTile * * @return minimum elevation */ - double minElevation(void) const { return _minElevation; } + double minElevation(void) const { return _isValid ? static_cast(_tileInfo.minElevation) : qQNaN(); } /** * Accessor for the maximum elevation of the tile * * @return maximum elevation */ - double maxElevation(void) const { return _maxElevation; } + double maxElevation(void) const { return _isValid ? static_cast(_tileInfo.maxElevation) : qQNaN(); } /** * Accessor for the average elevation of the tile * * @return average elevation */ - double avgElevation(void) const { return _avgElevation; } + double avgElevation(void) const { return _isValid ? _tileInfo.avgElevation : qQNaN(); } /** * Accessor for the center coordinate * * @return center coordinate */ - QGeoCoordinate centerCoordinate(void) const; - static QByteArray serializeFromAirMapJson(QByteArray input); + static QByteArray serializeFromAirMapJson(const QByteArray& input); static constexpr double tileSizeDegrees = 0.01; ///< Each terrain tile represents a square area .01 degrees in lat/lon static constexpr double tileValueSpacingDegrees = 1.0 / 3600; ///< 1 Arc-Second spacing of elevation values @@ -77,7 +76,7 @@ class TerrainTile private: typedef struct { - double swLat,swLon, neLat, neLon; + double swLat, swLon, neLat, neLon; int16_t minElevation; int16_t maxElevation; double avgElevation; @@ -85,16 +84,10 @@ class TerrainTile int16_t gridSizeLon; } TileInfo_t; - QGeoCoordinate _southWest; /// South west corner of the tile - QGeoCoordinate _northEast; /// North east corner of the tile - - int16_t _minElevation; /// Minimum elevation in tile - int16_t _maxElevation; /// Maximum elevation in tile - double _avgElevation; /// Average elevation of the tile - + TileInfo_t _tileInfo; int16_t** _data; /// 2D elevation data array - int16_t _gridSizeLat; /// data grid size in latitude direction - int16_t _gridSizeLon; /// data grid size in longitude direction + double _cellSizeLat; /// data grid size in latitude direction + double _cellSizeLon; /// data grid size in longitude direction bool _isValid; /// data loaded is valid // Json keys From 534e33fa750bd5480e2bcf2b5518d73b7f7b4fa4 Mon Sep 17 00:00:00 2001 From: leonardosimovic Date: Wed, 26 Jul 2023 09:48:50 +0200 Subject: [PATCH 3/3] feat: give credit to elevation provider --- src/PlanView/PlanView.qml | 13 +++++++++++++ src/PlanView/TerrainStatus.qml | 1 - src/QmlControls/QGroundControlQmlGlobal.h | 3 +++ src/QtLocationPlugin/QGCMapUrlEngine.cpp | 9 +++++---- src/QtLocationPlugin/QGCMapUrlEngine.h | 1 + 5 files changed, 22 insertions(+), 5 deletions(-) diff --git a/src/PlanView/PlanView.qml b/src/PlanView/PlanView.qml index a96928cb675..98ad6ff497a 100644 --- a/src/PlanView/PlanView.qml +++ b/src/PlanView/PlanView.qml @@ -730,6 +730,19 @@ Item { } } + QGCLabel { + // Elevation provider notice on top of terrain plot + readonly property string _licenseString: QGroundControl.elevationProviderNotice + + id: licenseLabel + visible: terrainStatus.visible && _licenseString !== "" + anchors.bottom: terrainStatus.top + anchors.horizontalCenter: terrainStatus.horizontalCenter + anchors.bottomMargin: ScreenTools.defaultFontPixelWidth * 0.5 + font.pointSize: ScreenTools.smallFontPointSize + text: qsTr("Powered by %1").arg(_licenseString) + } + TerrainStatus { id: terrainStatus anchors.margins: _toolsMargin diff --git a/src/PlanView/TerrainStatus.qml b/src/PlanView/TerrainStatus.qml index 51f11099816..fe3418de085 100644 --- a/src/PlanView/TerrainStatus.qml +++ b/src/PlanView/TerrainStatus.qml @@ -50,7 +50,6 @@ Rectangle { QGCFlickable { id: terrainProfileFlickable - //anchors.margins: _margins anchors.top: parent.top anchors.bottom: parent.bottom anchors.leftMargin: titleLabel.contentHeight diff --git a/src/QmlControls/QGroundControlQmlGlobal.h b/src/QmlControls/QGroundControlQmlGlobal.h index ff17e4452d0..1a54275ad93 100644 --- a/src/QmlControls/QGroundControlQmlGlobal.h +++ b/src/QmlControls/QGroundControlQmlGlobal.h @@ -109,6 +109,8 @@ class QGroundControlQmlGlobal : public QGCTool //------------------------------------------------------------------------- // Elevation Provider Q_PROPERTY(QString elevationProviderName READ elevationProviderName CONSTANT) + Q_PROPERTY(QString elevationProviderNotice READ elevationProviderNotice CONSTANT) + #if defined(QGC_ENABLE_PAIRING) Q_PROPERTY(PairingManager* pairingManager READ pairingManager CONSTANT) @@ -208,6 +210,7 @@ class QGroundControlQmlGlobal : public QGCTool #endif QString elevationProviderName () { return UrlFactory::kCopernicusElevationProviderKey; } + QString elevationProviderNotice () { return UrlFactory::kCopernicusElevationProviderNotice; } bool singleFirmwareSupport (); bool singleVehicleSupport (); diff --git a/src/QtLocationPlugin/QGCMapUrlEngine.cpp b/src/QtLocationPlugin/QGCMapUrlEngine.cpp index 4ee56bdf87a..7f4cbfd02b5 100644 --- a/src/QtLocationPlugin/QGCMapUrlEngine.cpp +++ b/src/QtLocationPlugin/QGCMapUrlEngine.cpp @@ -33,6 +33,7 @@ QGC_LOGGING_CATEGORY(QGCMapUrlEngineLog, "QGCMapUrlEngineLog") #include const char* UrlFactory::kCopernicusElevationProviderKey = "Copernicus Elevation"; +const char* UrlFactory::kCopernicusElevationProviderNotice = "© Airbus Defence and Space GmbH"; //----------------------------------------------------------------------------- UrlFactory::UrlFactory() : _timeout(5 * 1000) { @@ -73,7 +74,7 @@ UrlFactory::UrlFactory() : _timeout(5 * 1000) { //_providersTable["MapQuest Map"] = new MapQuestMapMapProvider(this); //_providersTable["MapQuest Sat"] = new MapQuestSatMapProvider(this); - + _providersTable["VWorld Street Map"] = new VWorldStreetMapProvider(this); _providersTable["VWorld Satellite Map"] = new VWorldSatMapProvider(this); @@ -84,9 +85,9 @@ UrlFactory::UrlFactory() : _timeout(5 * 1000) { _providersTable["Japan-GSI Anaglyph"] = new JapanAnaglyphMapProvider(this); _providersTable["Japan-GSI Slope"] = new JapanSlopeMapProvider(this); _providersTable["Japan-GSI Relief"] = new JapanReliefMapProvider(this); - + _providersTable["LINZ Basemap"] = new LINZBasemapMapProvider(this); - + _providersTable["CustomURL Custom"] = new CustomURLMapProvider(this); } @@ -142,7 +143,7 @@ QNetworkRequest UrlFactory::getTileURL(const QString& type, int x, int y, int zo quint32 UrlFactory::averageSizeForType(const QString& type) { if (_providersTable.find(type) != _providersTable.end()) { return _providersTable[type]->getAverageSize(); - } + } qCDebug(QGCMapUrlEngineLog) << "UrlFactory::averageSizeForType " << type << " Not registered"; diff --git a/src/QtLocationPlugin/QGCMapUrlEngine.h b/src/QtLocationPlugin/QGCMapUrlEngine.h index b43301b0dc4..8d3535c84ac 100644 --- a/src/QtLocationPlugin/QGCMapUrlEngine.h +++ b/src/QtLocationPlugin/QGCMapUrlEngine.h @@ -30,6 +30,7 @@ class UrlFactory : public QObject { Q_OBJECT public: static const char* kCopernicusElevationProviderKey; + static const char* kCopernicusElevationProviderNotice; UrlFactory (); ~UrlFactory ();