From eff0450ff0d020027ba8a9f87590e374a98ad46e Mon Sep 17 00:00:00 2001 From: Holden Date: Tue, 20 Aug 2024 20:41:42 -0400 Subject: [PATCH] QtLocationPlugin: Add Elevation Provider Selection --- src/QmlControls/QGroundControlQmlGlobal.cc | 7 ++- src/QmlControls/QGroundControlQmlGlobal.h | 4 +- src/QtLocationPlugin/ElevationMapProvider.cpp | 56 +++++++++++++++++++ src/QtLocationPlugin/ElevationMapProvider.h | 32 ++++++++++- src/QtLocationPlugin/QGCCachedTileSet.cpp | 1 - src/QtLocationPlugin/QGCMapUrlEngine.cpp | 13 +++++ src/QtLocationPlugin/QGCMapUrlEngine.h | 1 + .../QMLControl/QGCMapEngineManager.cc | 26 ++++++--- .../QMLControl/QGCMapEngineManager.h | 28 ++++++---- src/Settings/FlightMap.SettingsGroup.json | 6 ++ src/Settings/FlightMapSettings.cc | 1 + src/Settings/FlightMapSettings.h | 2 +- src/Terrain/CMakeLists.txt | 1 + src/Terrain/TerrainQuery.cc | 9 +-- src/Terrain/TerrainQuery.h | 7 ++- src/Terrain/TerrainQueryAirMap.cc | 14 +++-- src/Terrain/TerrainQueryAirMap.h | 36 ++---------- src/Terrain/TerrainQueryInterface.h | 35 ++++++++++++ src/Terrain/TerrainTileManager.cc | 32 ++++------- src/Terrain/TerrainTileManager.h | 1 - test/Terrain/TerrainQueryTest.cc | 2 +- test/Terrain/TerrainQueryTest.h | 2 +- 22 files changed, 221 insertions(+), 95 deletions(-) create mode 100644 src/Terrain/TerrainQueryInterface.h diff --git a/src/QmlControls/QGroundControlQmlGlobal.cc b/src/QmlControls/QGroundControlQmlGlobal.cc index e5f175775f3..727989cb66c 100644 --- a/src/QmlControls/QGroundControlQmlGlobal.cc +++ b/src/QmlControls/QGroundControlQmlGlobal.cc @@ -11,9 +11,10 @@ #include "QGCApplication.h" #include "LinkManager.h" #include "MAVLinkProtocol.h" -#include "ElevationMapProvider.h" #include "FirmwarePluginManager.h" #include "AppSettings.h" +#include "FlightMapSettings.h" +#include "SettingsManager.h" #include "PositionManager.h" #include "QGCMapEngineManager.h" #ifndef NO_SERIAL_LINK @@ -334,12 +335,12 @@ int QGroundControlQmlGlobal::mavlinkSystemID() QString QGroundControlQmlGlobal::elevationProviderName() { - return CopernicusElevationProvider::kProviderKey; + return _settingsManager->flightMapSettings()->elevationMapProvider()->rawValue().toString(); } QString QGroundControlQmlGlobal::elevationProviderNotice() { - return CopernicusElevationProvider::kProviderNotice; + return _settingsManager->flightMapSettings()->elevationMapProvider()->rawValue().toString(); } QString QGroundControlQmlGlobal::parameterFileExtension() const diff --git a/src/QmlControls/QGroundControlQmlGlobal.h b/src/QmlControls/QGroundControlQmlGlobal.h index daa5d934f77..c5b32f9fb1e 100644 --- a/src/QmlControls/QGroundControlQmlGlobal.h +++ b/src/QmlControls/QGroundControlQmlGlobal.h @@ -218,8 +218,8 @@ class QGroundControlQmlGlobal : public QGCTool bool hasMAVLinkInspector () { return true; } #endif - static QString elevationProviderName (); - static QString elevationProviderNotice (); + QString elevationProviderName (); + QString elevationProviderNotice (); bool singleFirmwareSupport (); bool singleVehicleSupport (); diff --git a/src/QtLocationPlugin/ElevationMapProvider.cpp b/src/QtLocationPlugin/ElevationMapProvider.cpp index c86f6a1d31e..3631062a8b2 100644 --- a/src/QtLocationPlugin/ElevationMapProvider.cpp +++ b/src/QtLocationPlugin/ElevationMapProvider.cpp @@ -61,3 +61,59 @@ QByteArray CopernicusElevationProvider::serialize(const QByteArray &image) const { return TerrainTile::serializeFromAirMapJson(image); } + +/*===========================================================================*/ + +int ArduPilotTerrainElevationProvider::long2tileX(double lon, int z) const +{ + Q_UNUSED(z) + return static_cast(floor((lon + 180.0))); +} + +int ArduPilotTerrainElevationProvider::lat2tileY(double lat, int z) const +{ + Q_UNUSED(z) + return static_cast(floor((lat + 90.0))); +} + +QString ArduPilotTerrainElevationProvider::_getURL(int x, int y, int zoom) const +{ + Q_UNUSED(zoom) + + // For saving them internally we do 0-360 and 0-180 to avoid signs. Need to redo that to obtain proper format for call + int xForUrl = x - 180; + int yForUrl = y - 90; + + const QString formattedStringYLat = (yForUrl > 0) ? QStringLiteral("N%1").arg(QString::number(yForUrl).rightJustified(2, '0')) : + QStringLiteral("S%1").arg(QString::number(-yForUrl).rightJustified(2, '0')); + + const QString formattedStringXLong = (xForUrl > 0) ? QStringLiteral("E%1").arg(QString::number(xForUrl).rightJustified(3, '0')) : + QStringLiteral("W%1").arg(QString::number(-xForUrl).rightJustified(3, '0')); + + return _mapUrl.arg(formattedStringYLat, formattedStringXLong); +} + +QGCTileSet ArduPilotTerrainElevationProvider::getTileCount(int zoom, double topleftLon, + double topleftLat, double bottomRightLon, + double bottomRightLat) const +{ + QGCTileSet set; + set.tileX0 = long2tileX(topleftLon, zoom); + set.tileY0 = lat2tileY(bottomRightLat, zoom); + set.tileX1 = long2tileX(bottomRightLon, zoom); + set.tileY1 = lat2tileY(topleftLat, zoom); + + set.tileCount = (static_cast(set.tileX1) - + static_cast(set.tileX0) + 1) * + (static_cast(set.tileY1) - + static_cast(set.tileY0) + 1); + + set.tileSize = getAverageSize() * set.tileCount; + + return set; +} + +QByteArray ArduPilotTerrainElevationProvider::serialize(const QByteArray &image) const +{ + return TerrainTile::serializeFromAirMapJson(image); +} diff --git a/src/QtLocationPlugin/ElevationMapProvider.h b/src/QtLocationPlugin/ElevationMapProvider.h index eae1a39918d..b5cbe33e46e 100644 --- a/src/QtLocationPlugin/ElevationMapProvider.h +++ b/src/QtLocationPlugin/ElevationMapProvider.h @@ -2,7 +2,8 @@ #include "MapProvider.h" -static constexpr const quint32 AVERAGE_COPERNICUS_ELEV_SIZE = 2786; +static constexpr quint32 AVERAGE_COPERNICUS_ELEV_SIZE = 2786; +static constexpr quint32 AVERAGE_ARDUPILOT_ELEV_SIZE = 100000; class ElevationProvider : public MapProvider { @@ -49,3 +50,32 @@ class CopernicusElevationProvider : public ElevationProvider const QString _mapUrl = QStringLiteral("https://terrain-ce.suite.auterion.com/api/v1/carpet?points=%1,%2,%3,%4"); }; + +class ArduPilotTerrainElevationProvider : public ElevationProvider +{ +public: + ArduPilotTerrainElevationProvider() + : ElevationProvider( + QStringLiteral("ArduPilot Terrain Elevation"), + QStringLiteral("https://terrain.ardupilot.org/SRTM1/"), + QStringLiteral("hgt"), + AVERAGE_ARDUPILOT_ELEV_SIZE, + QGeoMapType::StreetMap) {} + + int long2tileX(double lon, int z) const final; + int lat2tileY(double lat, int z) const final; + + QGCTileSet getTileCount(int zoom, double topleftLon, + double topleftLat, double bottomRightLon, + double bottomRightLat) const final; + + QByteArray serialize(const QByteArray &image) const final; + + static constexpr const char *kProviderKey = "ArduPilot Terrain Elevation"; + static constexpr const char *kProviderNotice = "© ArduPilot.org"; + +private: + QString _getURL(int x, int y, int zoom) const final; + + const QString _mapUrl = QStringLiteral("https://terrain.ardupilot.org/SRTM1/%1%2.hgt.zip"); +}; diff --git a/src/QtLocationPlugin/QGCCachedTileSet.cpp b/src/QtLocationPlugin/QGCCachedTileSet.cpp index 0bbd7ae8555..0421cbef8d5 100644 --- a/src/QtLocationPlugin/QGCCachedTileSet.cpp +++ b/src/QtLocationPlugin/QGCCachedTileSet.cpp @@ -28,7 +28,6 @@ #include #include #include -#include #include diff --git a/src/QtLocationPlugin/QGCMapUrlEngine.cpp b/src/QtLocationPlugin/QGCMapUrlEngine.cpp index d2620113864..a4092d997c3 100644 --- a/src/QtLocationPlugin/QGCMapUrlEngine.cpp +++ b/src/QtLocationPlugin/QGCMapUrlEngine.cpp @@ -63,6 +63,7 @@ const QList UrlFactory::_providers = { std::make_shared(), std::make_shared(), + std::make_shared(), std::make_shared(), std::make_shared(), @@ -229,6 +230,18 @@ int UrlFactory::getQtMapIdFromProviderType(QStringView type) return -1; } +QStringList UrlFactory::getElevationProviderTypes() +{ + QStringList types; + for (const SharedMapProvider &provider : _providers) { + if (provider->isElevationProvider()) { + (void) types.append(provider->getMapName()); + } + } + + return types; +} + QStringList UrlFactory::getProviderTypes() { QStringList types; diff --git a/src/QtLocationPlugin/QGCMapUrlEngine.h b/src/QtLocationPlugin/QGCMapUrlEngine.h index 63161b413d4..d0713f3b165 100644 --- a/src/QtLocationPlugin/QGCMapUrlEngine.h +++ b/src/QtLocationPlugin/QGCMapUrlEngine.h @@ -45,6 +45,7 @@ class UrlFactory QStringView mapType); static const QList>& getProviders() { return _providers; } + static QStringList getElevationProviderTypes(); static QStringList getProviderTypes(); static int getQtMapIdFromProviderType(QStringView type); static QString getProviderTypeFromQtMapId(int qtMapId); diff --git a/src/QtLocationPlugin/QMLControl/QGCMapEngineManager.cc b/src/QtLocationPlugin/QMLControl/QGCMapEngineManager.cc index d49e0a46a14..f3398732173 100644 --- a/src/QtLocationPlugin/QMLControl/QGCMapEngineManager.cc +++ b/src/QtLocationPlugin/QMLControl/QGCMapEngineManager.cc @@ -18,6 +18,8 @@ #include "ElevationMapProvider.h" #include "QmlObjectListModel.h" #include "QGCApplication.h" +#include "QGCToolbox.h" +#include "SettingsManager.h" #include "QGCLoggingCategory.h" #include @@ -28,9 +30,6 @@ QGC_LOGGING_CATEGORY(QGCMapEngineManagerLog, "qgc.qtlocation.qmlcontrol.qgcmapenginemanagerlog") -static const QString kQmlOfflineMapKeyName = QStringLiteral("QGCOfflineMap"); -static const QString kElevationMapType = QString(CopernicusElevationProvider::kProviderKey); // TODO: Variable Elevation Provider Type - Q_APPLICATION_STATIC(QGCMapEngineManager, _mapEngineManager); QGCMapEngineManager *QGCMapEngineManager::instance() @@ -76,7 +75,8 @@ void QGCMapEngineManager::updateForCurrentView(double lon0, double lat0, double } if (_fetchElevation) { - const QGCTileSet set = UrlFactory::getTileCount(1, lon0, lat0, lon1, lat1, kElevationMapType); + const QString elevationProviderName = qgcApp()->toolbox()->settingsManager()->flightMapSettings()->elevationMapProvider()->rawValue().toString(); + const QGCTileSet set = UrlFactory::getTileCount(1, lon0, lat0, lon1, lat1, elevationProviderName); _elevationSet += set; } @@ -143,9 +143,11 @@ void QGCMapEngineManager::startDownload(const QString &name, const QString &mapT qCWarning(QGCMapEngineManagerLog) << Q_FUNC_INFO << "No Tiles to save"; } - if ((mapType != kElevationMapType) && _fetchElevation) { + const int mapid = UrlFactory::getQtMapIdFromProviderType(mapType); + if (_fetchElevation && !UrlFactory::isElevation(mapid)) { QGCCachedTileSet* const set = new QGCCachedTileSet(name + QStringLiteral(" Elevation")); - set->setMapTypeStr(kElevationMapType); + const QString elevationProviderName = qgcApp()->toolbox()->settingsManager()->flightMapSettings()->elevationMapProvider()->rawValue().toString(); + set->setMapTypeStr(elevationProviderName); set->setTopleftLat(_topleftLat); set->setTopleftLon(_topleftLon); set->setBottomRightLat(_bottomRightLat); @@ -154,7 +156,7 @@ void QGCMapEngineManager::startDownload(const QString &name, const QString &mapT set->setMaxZoom(1); set->setTotalTileSize(_elevationSet.tileSize); set->setTotalTileCount(static_cast(_elevationSet.tileCount)); - set->setType(kElevationMapType); + set->setType(elevationProviderName); QGCCreateTileSetTask* const task = new QGCCreateTileSetTask(set); (void) connect(task, &QGCCreateTileSetTask::tileSetSaved, this, &QGCMapEngineManager::_tileSetSaved); @@ -458,7 +460,10 @@ QStringList QGCMapEngineManager::mapList() QStringList QGCMapEngineManager::mapProviderList() { QStringList mapStringList = mapList(); - (void) mapStringList.removeAll(CopernicusElevationProvider::kProviderKey); + const QStringList elevationStringList = elevationProviderList(); + for (const QString &elevationProviderName : elevationStringList) { + (void) mapStringList.removeAll(elevationProviderName); + } static const QRegularExpression providerType = QRegularExpression(QStringLiteral("^([^\\ ]*) (.*)$")); (void) mapStringList.replaceInStrings(providerType,"\\1"); @@ -466,3 +471,8 @@ QStringList QGCMapEngineManager::mapProviderList() return mapStringList; } + +QStringList QGCMapEngineManager::elevationProviderList() +{ + return UrlFactory::getElevationProviderTypes(); +} diff --git a/src/QtLocationPlugin/QMLControl/QGCMapEngineManager.h b/src/QtLocationPlugin/QMLControl/QGCMapEngineManager.h index b7c930620a7..9583ddfad3f 100644 --- a/src/QtLocationPlugin/QMLControl/QGCMapEngineManager.h +++ b/src/QtLocationPlugin/QMLControl/QGCMapEngineManager.h @@ -32,17 +32,18 @@ class QGCMapEngineManager : public QObject Q_MOC_INCLUDE("QmlObjectListModel.h") Q_MOC_INCLUDE("QGCCachedTileSet.h") - Q_PROPERTY(bool fetchElevation MEMBER _fetchElevation NOTIFY fetchElevationChanged) - Q_PROPERTY(bool importReplace MEMBER _importReplace NOTIFY importReplaceChanged) - Q_PROPERTY(ImportAction importAction READ importAction WRITE setImportAction NOTIFY importActionChanged) - Q_PROPERTY(int actionProgress READ actionProgress NOTIFY actionProgressChanged) - Q_PROPERTY(int selectedCount READ selectedCount NOTIFY selectedCountChanged) - Q_PROPERTY(QmlObjectListModel *tileSets READ tileSets NOTIFY tileSetsChanged) - Q_PROPERTY(QString errorMessage READ errorMessage NOTIFY errorMessageChanged) - Q_PROPERTY(QString tileCountStr READ tileCountStr NOTIFY tileCountChanged) - Q_PROPERTY(QString tileSizeStr READ tileSizeStr NOTIFY tileSizeChanged) - Q_PROPERTY(QStringList mapList READ mapList CONSTANT) - Q_PROPERTY(QStringList mapProviderList READ mapProviderList CONSTANT) + Q_PROPERTY(bool fetchElevation MEMBER _fetchElevation NOTIFY fetchElevationChanged) + Q_PROPERTY(bool importReplace MEMBER _importReplace NOTIFY importReplaceChanged) + Q_PROPERTY(ImportAction importAction READ importAction WRITE setImportAction NOTIFY importActionChanged) + Q_PROPERTY(int actionProgress READ actionProgress NOTIFY actionProgressChanged) + Q_PROPERTY(int selectedCount READ selectedCount NOTIFY selectedCountChanged) + Q_PROPERTY(QmlObjectListModel *tileSets READ tileSets NOTIFY tileSetsChanged) + Q_PROPERTY(QString errorMessage READ errorMessage NOTIFY errorMessageChanged) + Q_PROPERTY(QString tileCountStr READ tileCountStr NOTIFY tileCountChanged) + Q_PROPERTY(QString tileSizeStr READ tileSizeStr NOTIFY tileSizeChanged) + Q_PROPERTY(QStringList mapList READ mapList CONSTANT) + Q_PROPERTY(QStringList mapProviderList READ mapProviderList CONSTANT) + Q_PROPERTY(QStringList elevationProviderList READ elevationProviderList CONSTANT) Q_PROPERTY(quint32 diskSpace READ diskSpace) Q_PROPERTY(quint32 freeDiskSpace READ freeDiskSpace NOTIFY freeDiskSpaceChanged) Q_PROPERTY(quint64 tileCount READ tileCount NOTIFY tileCountChanged) @@ -97,6 +98,7 @@ class QGCMapEngineManager : public QObject static QStringList mapList(); static QStringList mapProviderList(); + static QStringList elevationProviderList(); signals: void actionProgressChanged(); @@ -123,7 +125,7 @@ private slots: void _updateTotals(quint32 totaltiles, quint64 totalsize, quint32 defaulttiles, quint64 defaultsize); private: - void _updateDiskFreeSpace(); + void _updateDiskFreeSpace(); QmlObjectListModel *_tileSets = nullptr; QGCTileSet _imageSet; @@ -142,4 +144,6 @@ private slots: QString _errorMessage; bool _fetchElevation = true; bool _importReplace = false; + + static constexpr const char *kQmlOfflineMapKeyName = "QGCOfflineMap"; }; diff --git a/src/Settings/FlightMap.SettingsGroup.json b/src/Settings/FlightMap.SettingsGroup.json index 1c0746207aa..5686a02aa6c 100644 --- a/src/Settings/FlightMap.SettingsGroup.json +++ b/src/Settings/FlightMap.SettingsGroup.json @@ -14,6 +14,12 @@ "shortDesc": "Currently selected map type for flight maps", "type": "string", "default": "Hybrid" +}, +{ + "name": "elevationMapProvider", + "shortDesc": "Currently selected elevation map provider", + "type": "string", + "default": "Copernicus Elevation" } ] } diff --git a/src/Settings/FlightMapSettings.cc b/src/Settings/FlightMapSettings.cc index 902392cbfe2..2e361b19c06 100644 --- a/src/Settings/FlightMapSettings.cc +++ b/src/Settings/FlightMapSettings.cc @@ -18,3 +18,4 @@ DECLARE_SETTINGGROUP(FlightMap, "FlightMap") DECLARE_SETTINGSFACT(FlightMapSettings, mapProvider) DECLARE_SETTINGSFACT(FlightMapSettings, mapType) +DECLARE_SETTINGSFACT(FlightMapSettings, elevationMapProvider) diff --git a/src/Settings/FlightMapSettings.h b/src/Settings/FlightMapSettings.h index 6627b3fe2d7..fb9ef5298e1 100644 --- a/src/Settings/FlightMapSettings.h +++ b/src/Settings/FlightMapSettings.h @@ -22,5 +22,5 @@ class FlightMapSettings : public SettingsGroup DEFINE_SETTING_NAME_GROUP() DEFINE_SETTINGFACT(mapProvider) DEFINE_SETTINGFACT(mapType) - + DEFINE_SETTINGFACT(elevationMapProvider) }; diff --git a/src/Terrain/CMakeLists.txt b/src/Terrain/CMakeLists.txt index 6c2ff7502c7..81c8ed9ab03 100644 --- a/src/Terrain/CMakeLists.txt +++ b/src/Terrain/CMakeLists.txt @@ -5,6 +5,7 @@ qt_add_library(Terrain STATIC TerrainQuery.h TerrainQueryAirMap.cc TerrainQueryAirMap.h + TerrainQueryInterface.h TerrainTile.cc TerrainTile.h TerrainTileManager.cc diff --git a/src/Terrain/TerrainQuery.cc b/src/Terrain/TerrainQuery.cc index daa642ecc30..84293b34db3 100644 --- a/src/Terrain/TerrainQuery.cc +++ b/src/Terrain/TerrainQuery.cc @@ -9,6 +9,7 @@ #include "TerrainQuery.h" #include "TerrainTileManager.h" +#include "TerrainQueryAirMap.h" #include "QGCLoggingCategory.h" #include @@ -23,7 +24,7 @@ TerrainAtCoordinateBatchManager::TerrainAtCoordinateBatchManager(void) _batchTimer.setSingleShot(true); _batchTimer.setInterval(_batchTimeout); connect(&_batchTimer, &QTimer::timeout, this, &TerrainAtCoordinateBatchManager::_sendNextBatch); - connect(&_terrainQuery, &TerrainQueryInterface::coordinateHeightsReceived, this, &TerrainAtCoordinateBatchManager::_coordinateHeights); + connect(_terrainQuery, &TerrainQueryInterface::coordinateHeightsReceived, this, &TerrainAtCoordinateBatchManager::_coordinateHeights); } void TerrainAtCoordinateBatchManager::addQuery(TerrainAtCoordinateQuery* terrainAtCoordinateQuery, const QList& coordinates) @@ -71,7 +72,7 @@ void TerrainAtCoordinateBatchManager::_sendNextBatch(void) qCDebug(TerrainQueryLog) << "TerrainAtCoordinateBatchManager::_sendNextBatch requesting next batch _state:_requestQueue.count:_sentRequests.count" << _stateToString(_state) << _requestQueue.count() << _sentRequests.count(); _state = State::Downloading; - _terrainQuery.requestCoordinateHeights(coords); + _terrainQuery->requestCoordinateHeights(coords); } void TerrainAtCoordinateBatchManager::_batchFailed(void) @@ -184,12 +185,12 @@ TerrainPathQuery::TerrainPathQuery(bool autoDelete) : _autoDelete (autoDelete) { qRegisterMetaType(); - connect(&_terrainQuery, &TerrainQueryInterface::pathHeightsReceived, this, &TerrainPathQuery::_pathHeights); + connect(_terrainQuery, &TerrainQueryInterface::pathHeightsReceived, this, &TerrainPathQuery::_pathHeights); } void TerrainPathQuery::requestData(const QGeoCoordinate& fromCoord, const QGeoCoordinate& toCoord) { - _terrainQuery.requestPathHeights(fromCoord, toCoord); + _terrainQuery->requestPathHeights(fromCoord, toCoord); } void TerrainPathQuery::_pathHeights(bool success, double distanceBetween, double finalDistanceBetween, const QList& heights) diff --git a/src/Terrain/TerrainQuery.h b/src/Terrain/TerrainQuery.h index 0a716b43020..3c0875df6e2 100644 --- a/src/Terrain/TerrainQuery.h +++ b/src/Terrain/TerrainQuery.h @@ -12,9 +12,10 @@ #include #include #include +#include #include -#include "TerrainQueryAirMap.h" +class TerrainQueryInterface; Q_DECLARE_LOGGING_CATEGORY(TerrainQueryLog) Q_DECLARE_LOGGING_CATEGORY(TerrainQueryVerboseLog) @@ -84,7 +85,7 @@ private slots: private: bool _autoDelete; - TerrainOfflineAirMapQuery _terrainQuery; + TerrainQueryInterface *_terrainQuery = nullptr; }; Q_DECLARE_METATYPE(TerrainPathQuery::PathHeightInfo_t) @@ -158,5 +159,5 @@ private slots: State _state = State::Idle; const int _batchTimeout = 500; QTimer _batchTimer; - TerrainOfflineAirMapQuery _terrainQuery; + TerrainQueryInterface *_terrainQuery = nullptr; }; diff --git a/src/Terrain/TerrainQueryAirMap.cc b/src/Terrain/TerrainQueryAirMap.cc index f267a11a83d..d9f9995cf04 100644 --- a/src/Terrain/TerrainQueryAirMap.cc +++ b/src/Terrain/TerrainQueryAirMap.cc @@ -14,6 +14,7 @@ #include #include +#include #include #include #include @@ -28,7 +29,14 @@ QGC_LOGGING_CATEGORY(TerrainQueryAirMapVerboseLog, "qgc.terrain.terrainqueryairm TerrainAirMapQuery::TerrainAirMapQuery(QObject* parent) : TerrainQueryInterface(parent) + , _networkManager(new QNetworkAccessManager(parent)) { +#ifndef __mobile__ + QNetworkProxy proxy = _networkManager->proxy(); + proxy.setType(QNetworkProxy::DefaultProxy); + _networkManager->setProxy(proxy); +#endif + qCDebug(TerrainQueryAirMapVerboseLog) << "supportsSsl" << QSslSocket::supportsSsl() << "sslLibraryBuildVersionString" << QSslSocket::sslLibraryBuildVersionString(); } @@ -92,11 +100,7 @@ void TerrainAirMapQuery::_sendQuery(const QString& path, const QUrlQuery& urlQue sslConf.setPeerVerifyMode(QSslSocket::VerifyNone); request.setSslConfiguration(sslConf); - QNetworkProxy tProxy; - tProxy.setType(QNetworkProxy::DefaultProxy); - _networkManager.setProxy(tProxy); - - QNetworkReply* networkReply = _networkManager.get(request); + QNetworkReply* networkReply = _networkManager->get(request); if (!networkReply) { qCWarning(TerrainQueryAirMapLog) << "QNetworkManager::Get did not return QNetworkReply"; _requestFailed(); diff --git a/src/Terrain/TerrainQueryAirMap.h b/src/Terrain/TerrainQueryAirMap.h index 0be525d77e1..2229fed5650 100644 --- a/src/Terrain/TerrainQueryAirMap.h +++ b/src/Terrain/TerrainQueryAirMap.h @@ -10,44 +10,16 @@ #pragma once #include -#include #include #include +#include "TerrainQueryInterface.h" + Q_DECLARE_LOGGING_CATEGORY(TerrainQueryAirMapLog) Q_DECLARE_LOGGING_CATEGORY(TerrainQueryAirMapVerboseLog) class QGeoCoordinate; - -/// Base class for offline/online terrain queries -class TerrainQueryInterface : public QObject -{ - Q_OBJECT - -public: - TerrainQueryInterface(QObject* parent) : QObject(parent) { } - - /// Request terrain heights for specified coodinates. - /// Signals: coordinateHeights when data is available - virtual void requestCoordinateHeights(const QList& coordinates) = 0; - - /// Requests terrain heights along the path specified by the two coordinates. - /// Signals: pathHeights - /// @param coordinates to query - virtual void requestPathHeights(const QGeoCoordinate& fromCoord, const QGeoCoordinate& toCoord) = 0; - - /// Request terrain heights for the rectangular area specified. - /// Signals: carpetHeights when data is available - /// @param swCoord South-West bound of rectangular area to query - /// @param neCoord North-East bound of rectangular area to query - /// @param statsOnly true: Return only stats, no carpet data - virtual void requestCarpetHeights(const QGeoCoordinate& swCoord, const QGeoCoordinate& neCoord, bool statsOnly) = 0; - -signals: - void coordinateHeightsReceived(bool success, QList heights); - void pathHeightsReceived(bool success, double distanceBetween, double finalDistanceBetween, const QList& heights); - void carpetHeightsReceived(bool success, double minHeight, double maxHeight, const QList>& carpet); -}; +class QNetworkAccessManager; /// AirMap online implementation of terrain queries class TerrainAirMapQuery : public TerrainQueryInterface { @@ -79,7 +51,7 @@ private slots: QueryModeCarpet }; - QNetworkAccessManager _networkManager; + QNetworkAccessManager *_networkManager = nullptr; QueryMode _queryMode; bool _carpetStatsOnly; }; diff --git a/src/Terrain/TerrainQueryInterface.h b/src/Terrain/TerrainQueryInterface.h new file mode 100644 index 00000000000..deda1993d41 --- /dev/null +++ b/src/Terrain/TerrainQueryInterface.h @@ -0,0 +1,35 @@ +#pragma once + +#include + +class QGeoCoordinate; + +/// Base class for offline/online terrain queries +class TerrainQueryInterface : public QObject +{ + Q_OBJECT + +public: + TerrainQueryInterface(QObject* parent) : QObject(parent) { } + + /// Request terrain heights for specified coodinates. + /// Signals: coordinateHeights when data is available + virtual void requestCoordinateHeights(const QList& coordinates) = 0; + + /// Requests terrain heights along the path specified by the two coordinates. + /// Signals: pathHeights + /// @param coordinates to query + virtual void requestPathHeights(const QGeoCoordinate& fromCoord, const QGeoCoordinate& toCoord) = 0; + + /// Request terrain heights for the rectangular area specified. + /// Signals: carpetHeights when data is available + /// @param swCoord South-West bound of rectangular area to query + /// @param neCoord North-East bound of rectangular area to query + /// @param statsOnly true: Return only stats, no carpet data + virtual void requestCarpetHeights(const QGeoCoordinate& swCoord, const QGeoCoordinate& neCoord, bool statsOnly) = 0; + +signals: + void coordinateHeightsReceived(bool success, QList heights); + void pathHeightsReceived(bool success, double distanceBetween, double finalDistanceBetween, const QList& heights); + void carpetHeightsReceived(bool success, double minHeight, double maxHeight, const QList>& carpet); +}; diff --git a/src/Terrain/TerrainTileManager.cc b/src/Terrain/TerrainTileManager.cc index 4eb1e8c4a61..098953aa28b 100644 --- a/src/Terrain/TerrainTileManager.cc +++ b/src/Terrain/TerrainTileManager.cc @@ -14,6 +14,9 @@ #include #include #include +#include "QGCApplication.h" +#include "QGCToolbox.h" +#include "SettingsManager.h" #include #include @@ -23,8 +26,6 @@ QGC_LOGGING_CATEGORY(TerrainTileManagerLog, "qgc.terrain.terraintilemanager") -static const QString kMapType = CopernicusElevationProvider::kProviderKey; - Q_GLOBAL_STATIC(TerrainTileManager, s_terrainTileManager) TerrainTileManager* TerrainTileManager::instance(void) @@ -142,8 +143,15 @@ bool TerrainTileManager::getAltitudesForCoordinates(const QList& { error = false; + const QString elevationProviderName = qgcApp()->toolbox()->settingsManager()->flightMapSettings()->elevationMapProvider()->rawValue().toString(); + const SharedMapProvider provider = UrlFactory::getMapProviderFromProviderType(elevationProviderName); for (const QGeoCoordinate& coordinate: coordinates) { - QString tileHash = _getTileHash(coordinate); + const QString tileHash = UrlFactory::getTileHash( + provider->getMapName(), + provider->long2tileX(coordinate.longitude(), 1), + provider->lat2tileY(coordinate.latitude(), 1), + 1 + ); qCDebug(TerrainTileManagerLog) << "TerrainTileManager::getAltitudesForCoordinates hash:coordinate" << tileHash << coordinate; _tilesMutex.lock(); @@ -158,7 +166,6 @@ bool TerrainTileManager::getAltitudesForCoordinates(const QList& altitudes.push_back(elevation); } else { if (_state != State::Downloading) { - const SharedMapProvider provider = UrlFactory::getMapProviderFromProviderType(kMapType); QGeoTileSpec spec; spec.setX(provider->long2tileX(coordinate.longitude(), 1)); spec.setY(provider->lat2tileY(coordinate.latitude(), 1)); @@ -207,7 +214,7 @@ void TerrainTileManager::_terrainDone() // remove from download queue const QByteArray responseBytes = reply->mapImageData(); const QGeoTileSpec spec = reply->tileSpec(); - const QString hash = UrlFactory::getTileHash(kMapType, spec.x(), spec.y(), spec.zoom()); + const QString hash = UrlFactory::getTileHash(UrlFactory::getProviderTypeFromQtMapId(spec.mapId()), spec.x(), spec.y(), spec.zoom()); // handle potential errors if (reply->error() != QGeoTiledMapReplyQGC::NoError) { @@ -267,18 +274,3 @@ void TerrainTileManager::_terrainDone() } } } - -QString TerrainTileManager::_getTileHash(const QGeoCoordinate &coordinate) -{ - const SharedMapProvider provider = UrlFactory::getMapProviderFromProviderType(kMapType); - - const QString result = UrlFactory::getTileHash( - provider->getMapName(), - provider->long2tileX(coordinate.longitude(), 1), - provider->lat2tileY(coordinate.latitude(), 1), - 1 - ); - - qCDebug(TerrainQueryVerboseLog) << "Computing unique tile hash for" << coordinate << result; - return result; -} diff --git a/src/Terrain/TerrainTileManager.h b/src/Terrain/TerrainTileManager.h index 8ef9dcab7d4..c86d074f188 100644 --- a/src/Terrain/TerrainTileManager.h +++ b/src/Terrain/TerrainTileManager.h @@ -61,7 +61,6 @@ private slots: } QueuedRequestInfo_t; void _tileFailed (void); - QString _getTileHash (const QGeoCoordinate& coordinate); QList _requestQueue; State _state = State::Idle; diff --git a/test/Terrain/TerrainQueryTest.cc b/test/Terrain/TerrainQueryTest.cc index ae9a97a185f..192c12acc64 100644 --- a/test/Terrain/TerrainQueryTest.cc +++ b/test/Terrain/TerrainQueryTest.cc @@ -65,7 +65,7 @@ void UnitTestTerrainQuery::requestCarpetHeights(const QGeoCoordinate& swCoord, c QList> carpet; if (swCoord.longitude() > neCoord.longitude() || swCoord.latitude() > neCoord.latitude()) { - qCWarning(TerrainQueryLog) << "UnitTestTerrainQuery::requestCarpetHeights: Internal Error - bad carpet coords"; + // qCWarning(TerrainQueryLog) << "UnitTestTerrainQuery::requestCarpetHeights: Internal Error - bad carpet coords"; emit qobject_cast(parent())->carpetHeightsReceived(false, qQNaN(), qQNaN(), carpet); return; } diff --git a/test/Terrain/TerrainQueryTest.h b/test/Terrain/TerrainQueryTest.h index 3af59606316..206c0d790a6 100644 --- a/test/Terrain/TerrainQueryTest.h +++ b/test/Terrain/TerrainQueryTest.h @@ -13,7 +13,7 @@ #include #include -#include +#include /// @brief Provides unit test terrain query responses. /// @details It provides preset, emulated, 1 arc-second (SRTM1) resolution regions that are either