Browse Source

Remove dependency to UrlFactory::MapType

QGC4.4
Pierre TILAK 6 years ago
parent
commit
1f6c8d1a8a
  1. 4
      src/QtLocationPlugin/GoogleMapProvider.cpp
  2. 1
      src/QtLocationPlugin/GoogleMapProvider.h
  3. 2
      src/QtLocationPlugin/MapProvider.h
  4. 264
      src/QtLocationPlugin/QGCMapEngine.cpp
  5. 16
      src/QtLocationPlugin/QGCMapEngine.h
  6. 14
      src/QtLocationPlugin/QGCMapEngineData.h
  7. 6
      src/QtLocationPlugin/QGCMapTileSet.cpp
  8. 6
      src/QtLocationPlugin/QGCMapTileSet.h
  9. 52
      src/QtLocationPlugin/QGCMapUrlEngine.cpp
  10. 120
      src/QtLocationPlugin/QGCMapUrlEngine.h
  11. 10
      src/QtLocationPlugin/QGCTileCacheWorker.cpp
  12. 20
      src/QtLocationPlugin/QGeoMapReplyQGC.cpp
  13. 2
      src/QtLocationPlugin/QGeoTileFetcherQGC.cpp
  14. 6
      src/QtLocationPlugin/QGeoTiledMappingManagerEngineQGC.cpp
  15. 12
      src/QtLocationPlugin/QMLControl/QGCMapEngineManager.cc
  16. 8
      src/Terrain/TerrainQuery.cc
  17. 54
      src/Terrain/patch

4
src/QtLocationPlugin/GoogleMapProvider.cpp

@ -19,10 +19,6 @@ GoogleMapProvider::GoogleMapProvider(quint32 averageSize, QGeoMapType::MapStyle @@ -19,10 +19,6 @@ GoogleMapProvider::GoogleMapProvider(quint32 averageSize, QGeoMapType::MapStyle
_secGoogleWord = "Galileo";
}
quint32 GoogleMapProvider::getAverageSize() {
return quint32(AVERAGE_GOOGLE_STREET_MAP);
}
GoogleMapProvider::~GoogleMapProvider() {
if (_googleReply)
_googleReply->deleteLater();

1
src/QtLocationPlugin/GoogleMapProvider.h

@ -17,7 +17,6 @@ class GoogleMapProvider : public MapProvider { @@ -17,7 +17,6 @@ class GoogleMapProvider : public MapProvider {
~GoogleMapProvider();
static quint32 getAverageSize();
// Google Specific private slots
private slots:
void _networkReplyError(QNetworkReply::NetworkError error);

2
src/QtLocationPlugin/MapProvider.h

@ -30,6 +30,8 @@ class MapProvider : public QObject { @@ -30,6 +30,8 @@ class MapProvider : public QObject {
QString getImageFormat(const QByteArray& image);
quint32 getAverageSize(){return _averageSize;}
QGeoMapType::MapStyle getMapStyle(){return _mapType;}
protected:

264
src/QtLocationPlugin/QGCMapEngine.cpp

@ -39,68 +39,68 @@ static QLocale kLocale; @@ -39,68 +39,68 @@ static QLocale kLocale;
struct stQGeoTileCacheQGCMapTypes {
const char* name;
UrlFactory::MapType type;
QString type;
};
//-- IMPORTANT
// Changes here must reflect those in QGeoTiledMappingManagerEngineQGC.cpp
static stQGeoTileCacheQGCMapTypes kMapTypes[] = {
#ifndef QGC_LIMITED_MAPS
{"Google Street Map", UrlFactory::GoogleMap},
{"Google Satellite Map", UrlFactory::GoogleSatellite},
{"Google Terrain Map", UrlFactory::GoogleTerrain},
#endif
{"Bing Street Map", UrlFactory::BingMap},
{"Bing Satellite Map", UrlFactory::BingSatellite},
{"Bing Hybrid Map", UrlFactory::BingHybrid},
{"Statkart Terrain Map", UrlFactory::StatkartTopo},
{"ENIRO Terrain Map", UrlFactory::EniroTopo},
{"VWorld Satellite Map", UrlFactory::VWorldSatellite},
{"VWorld Street Map", UrlFactory::VWorldStreet}
/*
{"MapQuest Street Map", UrlFactory::MapQuestMap},
{"MapQuest Satellite Map", UrlFactory::MapQuestSat}
{"Open Street Map", UrlFactory::OpenStreetMap}
*/
};
#define NUM_MAPS (sizeof(kMapTypes) / sizeof(stQGeoTileCacheQGCMapTypes))
static stQGeoTileCacheQGCMapTypes kMapboxTypes[] = {
{"Mapbox Street Map", UrlFactory::MapboxStreets},
{"Mapbox Satellite Map", UrlFactory::MapboxSatellite},
{"Mapbox High Contrast Map",UrlFactory::MapboxHighContrast},
{"Mapbox Light Map", UrlFactory::MapboxLight},
{"Mapbox Dark Map", UrlFactory::MapboxDark},
{"Mapbox Hybrid Map", UrlFactory::MapboxHybrid},
{"Mapbox Wheat Paste Map", UrlFactory::MapboxWheatPaste},
{"Mapbox Streets Basic Map",UrlFactory::MapboxStreetsBasic},
{"Mapbox Comic Map", UrlFactory::MapboxComic},
{"Mapbox Outdoors Map", UrlFactory::MapboxOutdoors},
{"Mapbox Run, Byke and Hike Map", UrlFactory::MapboxRunBikeHike},
{"Mapbox Pencil Map", UrlFactory::MapboxPencil},
{"Mapbox Pirates Map", UrlFactory::MapboxPirates},
{"Mapbox Emerald Map", UrlFactory::MapboxEmerald}
};
#define NUM_MAPBOXMAPS (sizeof(kMapboxTypes) / sizeof(stQGeoTileCacheQGCMapTypes))
static stQGeoTileCacheQGCMapTypes kEsriTypes[] = {
{"Esri Street Map", UrlFactory::EsriWorldStreet},
{"Esri Satellite Map", UrlFactory::EsriWorldSatellite},
{"Esri Terrain Map", UrlFactory::EsriTerrain}
};
#define NUM_ESRIMAPS (sizeof(kEsriTypes) / sizeof(stQGeoTileCacheQGCMapTypes))
static stQGeoTileCacheQGCMapTypes kElevationTypes[] = {
{"Airmap Elevation Data", UrlFactory::AirmapElevation}
};
#define NUM_ELEVMAPS (sizeof(kElevationTypes) / sizeof(stQGeoTileCacheQGCMapTypes))
//static stQGeoTileCacheQGCMapTypes kMapTypes[] = {
//#ifndef QGC_LIMITED_MAPS
// {"Google Street Map", UrlFactory::GoogleMap},
// {"Google Satellite Map", UrlFactory::GoogleSatellite},
// {"Google Terrain Map", UrlFactory::GoogleTerrain},
//#endif
// {"Bing Street Map", UrlFactory::BingMap},
// {"Bing Satellite Map", UrlFactory::BingSatellite},
// {"Bing Hybrid Map", UrlFactory::BingHybrid},
// {"Statkart Terrain Map", UrlFactory::StatkartTopo},
// {"ENIRO Terrain Map", UrlFactory::EniroTopo},
//
// {"VWorld Satellite Map", UrlFactory::VWorldSatellite},
// {"VWorld Street Map", UrlFactory::VWorldStreet}
//
// /*
// {"MapQuest Street Map", UrlFactory::MapQuestMap},
// {"MapQuest Satellite Map", UrlFactory::MapQuestSat}
// {"Open Street Map", UrlFactory::OpenStreetMap}
// */
//};
//#define NUM_MAPS (sizeof(kMapTypes) / sizeof(stQGeoTileCacheQGCMapTypes))
//static stQGeoTileCacheQGCMapTypes kMapboxTypes[] = {
// {"Mapbox Street Map", UrlFactory::MapboxStreets},
// {"Mapbox Satellite Map", UrlFactory::MapboxSatellite},
// {"Mapbox High Contrast Map",UrlFactory::MapboxHighContrast},
// {"Mapbox Light Map", UrlFactory::MapboxLight},
// {"Mapbox Dark Map", UrlFactory::MapboxDark},
// {"Mapbox Hybrid Map", UrlFactory::MapboxHybrid},
// {"Mapbox Wheat Paste Map", UrlFactory::MapboxWheatPaste},
// {"Mapbox Streets Basic Map",UrlFactory::MapboxStreetsBasic},
// {"Mapbox Comic Map", UrlFactory::MapboxComic},
// {"Mapbox Outdoors Map", UrlFactory::MapboxOutdoors},
// {"Mapbox Run, Byke and Hike Map", UrlFactory::MapboxRunBikeHike},
// {"Mapbox Pencil Map", UrlFactory::MapboxPencil},
// {"Mapbox Pirates Map", UrlFactory::MapboxPirates},
// {"Mapbox Emerald Map", UrlFactory::MapboxEmerald}
//};
//
//#define NUM_MAPBOXMAPS (sizeof(kMapboxTypes) / sizeof(stQGeoTileCacheQGCMapTypes))
//static stQGeoTileCacheQGCMapTypes kEsriTypes[] = {
// {"Esri Street Map", UrlFactory::EsriWorldStreet},
// {"Esri Satellite Map", UrlFactory::EsriWorldSatellite},
// {"Esri Terrain Map", UrlFactory::EsriTerrain}
//};
//
//#define NUM_ESRIMAPS (sizeof(kEsriTypes) / sizeof(stQGeoTileCacheQGCMapTypes))
//
//static stQGeoTileCacheQGCMapTypes kElevationTypes[] = {
// {"Airmap Elevation Data", UrlFactory::AirmapElevation}
//};
//
//#define NUM_ELEVMAPS (sizeof(kElevationTypes) / sizeof(stQGeoTileCacheQGCMapTypes))
static const char* kMaxDiskCacheKey = "MaxDiskCache";
static const char* kMaxMemCacheKey = "MaxMemoryCache";
@ -265,7 +265,7 @@ QGCMapEngine::addTask(QGCMapTask* task) @@ -265,7 +265,7 @@ QGCMapEngine::addTask(QGCMapTask* task)
//-----------------------------------------------------------------------------
void
QGCMapEngine::cacheTile(UrlFactory::MapType type, int x, int y, int z, const QByteArray& image, const QString &format, qulonglong set)
QGCMapEngine::cacheTile(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);
@ -273,7 +273,7 @@ QGCMapEngine::cacheTile(UrlFactory::MapType type, int x, int y, int z, const QBy @@ -273,7 +273,7 @@ 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)
QGCMapEngine::cacheTile(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
@ -285,22 +285,22 @@ QGCMapEngine::cacheTile(UrlFactory::MapType type, const QString& hash, const QBy @@ -285,22 +285,22 @@ QGCMapEngine::cacheTile(UrlFactory::MapType type, const QString& hash, const QBy
//-----------------------------------------------------------------------------
QString
QGCMapEngine::getTileHash(UrlFactory::MapType type, int x, int y, int z)
QGCMapEngine::getTileHash(QString type, int x, int y, int z)
{
return QString().sprintf("%04d%08d%08d%03d", static_cast<int>(type), x, y, z);
return QString().sprintf("%04d%08d%08d%03d", getQGCMapEngine()->urlFactory()->getIdFromType(type), x, y, z);
}
//-----------------------------------------------------------------------------
UrlFactory::MapType
QString
QGCMapEngine::hashToType(const QString& hash)
{
QString type = hash.mid(0,4);
return static_cast<UrlFactory::MapType>(type.toInt());
return static_cast<QString>(type.toInt());
}
//-----------------------------------------------------------------------------
QGCFetchTileTask*
QGCMapEngine::createFetchTileTask(UrlFactory::MapType type, int x, int y, int z)
QGCMapEngine::createFetchTileTask(QString type, int x, int y, int z)
{
QString hash = getTileHash(type, x, y, z);
QGCFetchTileTask* task = new QGCFetchTileTask(hash);
@ -309,12 +309,12 @@ QGCMapEngine::createFetchTileTask(UrlFactory::MapType type, int x, int y, int z) @@ -309,12 +309,12 @@ QGCMapEngine::createFetchTileTask(UrlFactory::MapType type, int x, int y, int z)
//-----------------------------------------------------------------------------
QGCTileSet
QGCMapEngine::getTileCount(int zoom, double topleftLon, double topleftLat, double bottomRightLon, double bottomRightLat, UrlFactory::MapType mapType)
QGCMapEngine::getTileCount(int zoom, double topleftLon, double topleftLat, double bottomRightLon, double bottomRightLat, QString mapType)
{
if(zoom < 1) zoom = 1;
if(zoom > MAX_MAP_ZOOM) zoom = MAX_MAP_ZOOM;
QGCTileSet set;
if (mapType != UrlFactory::AirmapElevation) {
if (mapType != "AirmapElevation") {
set.tileX0 = long2tileX(topleftLon, zoom);
set.tileY0 = lat2tileY(topleftLat, zoom);
set.tileX1 = long2tileX(bottomRightLon, zoom);
@ -326,7 +326,7 @@ QGCMapEngine::getTileCount(int zoom, double topleftLon, double topleftLat, doubl @@ -326,7 +326,7 @@ QGCMapEngine::getTileCount(int zoom, double topleftLon, double topleftLat, doubl
set.tileY1 = lat2elevationTileY(topleftLat, zoom);
}
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;
set.tileSize = getQGCMapEngine()->urlFactory()->averageSizeForType(mapType) * set.tileCount;
return set;
}
@ -361,48 +361,48 @@ QGCMapEngine::lat2elevationTileY(double lat, int z) @@ -361,48 +361,48 @@ QGCMapEngine::lat2elevationTileY(double lat, int z)
}
//-----------------------------------------------------------------------------
UrlFactory::MapType
QGCMapEngine::getTypeFromName(const QString& name)
{
size_t i;
for(i = 0; i < NUM_MAPS; i++) {
if(name.compare(kMapTypes[i].name, Qt::CaseInsensitive) == 0)
return kMapTypes[i].type;
}
for(i = 0; i < NUM_MAPBOXMAPS; i++) {
if(name.compare(kMapboxTypes[i].name, Qt::CaseInsensitive) == 0)
return kMapboxTypes[i].type;
}
for(i = 0; i < NUM_ESRIMAPS; i++) {
if(name.compare(kEsriTypes[i].name, Qt::CaseInsensitive) == 0)
return kEsriTypes[i].type;
}
for(i = 0; i < NUM_ELEVMAPS; i++) {
if(name.compare(kElevationTypes[i].name, Qt::CaseInsensitive) == 0)
return kElevationTypes[i].type;
}
return UrlFactory::Invalid;
}
//QString
//QGCMapEngine::getTypeFromName(const QString& name)
//{
// size_t i;
// for(i = 0; i < NUM_MAPS; i++) {
// if(name.compare(kMapTypes[i].name, Qt::CaseInsensitive) == 0)
// return kMapTypes[i].type;
// }
// for(i = 0; i < NUM_MAPBOXMAPS; i++) {
// if(name.compare(kMapboxTypes[i].name, Qt::CaseInsensitive) == 0)
// return kMapboxTypes[i].type;
// }
// for(i = 0; i < NUM_ESRIMAPS; i++) {
// if(name.compare(kEsriTypes[i].name, Qt::CaseInsensitive) == 0)
// return kEsriTypes[i].type;
// }
// for(i = 0; i < NUM_ELEVMAPS; i++) {
// if(name.compare(kElevationTypes[i].name, Qt::CaseInsensitive) == 0)
// return kElevationTypes[i].type;
// }
// return UrlFactory::Invalid;
//}
//-----------------------------------------------------------------------------
QStringList
QGCMapEngine::getMapNameList()
{
QStringList mapList;
for(size_t i = 0; i < NUM_MAPS; i++) {
mapList << kMapTypes[i].name;
}
if(!qgcApp()->toolbox()->settingsManager()->appSettings()->mapboxToken()->rawValue().toString().isEmpty()) {
for(size_t i = 0; i < NUM_MAPBOXMAPS; i++) {
mapList << kMapboxTypes[i].name;
}
}
if(!qgcApp()->toolbox()->settingsManager()->appSettings()->esriToken()->rawValue().toString().isEmpty()) {
for(size_t i = 0; i < NUM_ESRIMAPS; i++) {
mapList << kEsriTypes[i].name;
}
}
return mapList;
return QStringList(getQGCMapEngine()->urlFactory()->getProviderTable().keys());
//for(size_t i = 0; i < NUM_MAPS; i++) {
// mapList << kMapTypes[i].name;
//}
//if(!qgcApp()->toolbox()->settingsManager()->appSettings()->mapboxToken()->rawValue().toString().isEmpty()) {
// for(size_t i = 0; i < NUM_MAPBOXMAPS; i++) {
// mapList << kMapboxTypes[i].name;
// }
//}
//if(!qgcApp()->toolbox()->settingsManager()->appSettings()->esriToken()->rawValue().toString().isEmpty()) {
// for(size_t i = 0; i < NUM_ESRIMAPS; i++) {
// mapList << kEsriTypes[i].name;
// }
//}
//return mapList;
}
//-----------------------------------------------------------------------------
@ -513,34 +513,36 @@ QGCMapEngine::_pruned() @@ -513,34 +513,36 @@ QGCMapEngine::_pruned()
//-----------------------------------------------------------------------------
int
QGCMapEngine::concurrentDownloads(UrlFactory::MapType type)
{
switch(type) {
case UrlFactory::GoogleMap:
case UrlFactory::GoogleSatellite:
case UrlFactory::GoogleTerrain:
case UrlFactory::BingMap:
case UrlFactory::BingSatellite:
case UrlFactory::BingHybrid:
case UrlFactory::StatkartTopo:
case UrlFactory::EniroTopo:
case UrlFactory::EsriWorldStreet:
case UrlFactory::EsriWorldSatellite:
case UrlFactory::EsriTerrain:
case UrlFactory::AirmapElevation:
case UrlFactory::VWorldMap:
case UrlFactory::VWorldSatellite:
case UrlFactory::VWorldStreet:
QGCMapEngine::concurrentDownloads(QString type)
{
Q_UNUSED(type);
return 12;
/*
case UrlFactory::MapQuestMap:
case UrlFactory::MapQuestSat:
return 8;
*/
default:
break;
}
return 6;
//switch(type) {
//case UrlFactory::GoogleMap:
//case UrlFactory::GoogleSatellite:
//case UrlFactory::GoogleTerrain:
//case UrlFactory::BingMap:
//case UrlFactory::BingSatellite:
//case UrlFactory::BingHybrid:
//case UrlFactory::StatkartTopo:
//case UrlFactory::EniroTopo:
//case UrlFactory::EsriWorldStreet:
//case UrlFactory::EsriWorldSatellite:
//case UrlFactory::EsriTerrain:
//case UrlFactory::AirmapElevation:
//case UrlFactory::VWorldMap:
//case UrlFactory::VWorldSatellite:
//case UrlFactory::VWorldStreet:
// return 12;
///*
//case UrlFactory::MapQuestMap:
//case UrlFactory::MapQuestSat:
// return 8;
//*/
//default:
// break;
//}
//return 6;
}
//-----------------------------------------------------------------------------

16
src/QtLocationPlugin/QGCMapEngine.h

@ -71,13 +71,13 @@ public: @@ -71,13 +71,13 @@ public:
void init ();
void addTask (QGCMapTask *task);
void cacheTile (UrlFactory::MapType type, int x, int y, int z, const QByteArray& image, const QString& format, qulonglong set = UINT64_MAX);
void cacheTile (UrlFactory::MapType type, const QString& hash, const QByteArray& image, const QString& format, qulonglong set = UINT64_MAX);
QGCFetchTileTask* createFetchTileTask (UrlFactory::MapType type, int x, int y, int z);
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);
QStringList getMapNameList ();
const QString userAgent () { return _userAgent; }
void setUserAgent (const QString& ua) { _userAgent = ua; }
UrlFactory::MapType hashToType (const QString& hash);
QString hashToType (const QString& hash);
quint32 getMaxDiskCache ();
void setMaxDiskCache (quint32 size);
quint32 getMaxMemCache ();
@ -91,17 +91,17 @@ public: @@ -91,17 +91,17 @@ public:
UrlFactory* urlFactory () { return _urlFactory; }
//-- Tile Math
static QGCTileSet getTileCount (int zoom, double topleftLon, double topleftLat, double bottomRightLon, double bottomRightLat, UrlFactory::MapType mapType);
static QGCTileSet getTileCount (int zoom, double topleftLon, double topleftLat, double bottomRightLon, double bottomRightLat, QString mapType);
static int long2tileX (double lon, int z);
static int lat2tileY (double lat, int z);
static int long2elevationTileX (double lon, int z);
static int lat2elevationTileY (double lat, int z);
static QString getTileHash (UrlFactory::MapType type, int x, int y, int z);
static UrlFactory::MapType getTypeFromName (const QString &name);
static QString getTileHash (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 (UrlFactory::MapType type);
static int concurrentDownloads (QString type);
/// size of an elevation tile in degree
static const double srtm1TileSize;

14
src/QtLocationPlugin/QGCMapEngineData.h

@ -37,7 +37,7 @@ public: @@ -37,7 +37,7 @@ public:
, _y(0)
, _z(0)
, _set(UINT64_MAX)
, _type(UrlFactory::Invalid)
, _type("Invalid")
{
}
@ -53,14 +53,14 @@ public: @@ -53,14 +53,14 @@ public:
int z () const { return _z; }
qulonglong set () const { return _set; }
const QString hash () const { return _hash; }
UrlFactory::MapType type () const { return _type; }
QString type () const { return _type; }
void setX (int x) { _x = x; }
void setY (int y) { _y = y; }
void setZ (int z) { _z = z; }
void setTileSet (qulonglong set) { _set = set; }
void setHash (const QString& hash) { _hash = hash; }
void setType (UrlFactory::MapType type) { _type = type; }
void setType (QString type) { _type = type; }
private:
int _x;
@ -68,7 +68,7 @@ private: @@ -68,7 +68,7 @@ private:
int _z;
qulonglong _set;
QString _hash;
UrlFactory::MapType _type;
QString _type;
};
//-----------------------------------------------------------------------------
@ -76,7 +76,7 @@ class QGCCacheTile : public QObject @@ -76,7 +76,7 @@ class QGCCacheTile : public QObject
{
Q_OBJECT
public:
QGCCacheTile (const QString hash, const QByteArray img, const QString format, UrlFactory::MapType type, qulonglong set = UINT64_MAX)
QGCCacheTile (const QString hash, const QByteArray img, const QString format, QString type, qulonglong set = UINT64_MAX)
: _set(set)
, _hash(hash)
, _img(img)
@ -93,13 +93,13 @@ public: @@ -93,13 +93,13 @@ public:
QString hash () { return _hash; }
QByteArray img () { return _img; }
QString format () { return _format;}
UrlFactory::MapType type () { return _type; }
QString type () { return _type; }
private:
qulonglong _set;
QString _hash;
QByteArray _img;
QString _format;
UrlFactory::MapType _type;
QString _type;
};
//-----------------------------------------------------------------------------

6
src/QtLocationPlugin/QGCMapTileSet.cpp

@ -47,7 +47,7 @@ QGCCachedTileSet::QGCCachedTileSet(const QString& name) @@ -47,7 +47,7 @@ QGCCachedTileSet::QGCCachedTileSet(const QString& name)
, _deleting(false)
, _downloading(false)
, _id(0)
, _type(UrlFactory::Invalid)
, _type("Invalid")
, _networkManager(nullptr)
, _errorCount(0)
, _noMoreTiles(false)
@ -279,8 +279,8 @@ QGCCachedTileSet::_networkReplyFinished() @@ -279,8 +279,8 @@ QGCCachedTileSet::_networkReplyFinished()
}
qCDebug(QGCCachedTileSetLog) << "Tile fetched" << hash;
QByteArray image = reply->readAll();
UrlFactory::MapType type = getQGCMapEngine()->hashToType(hash);
if (type == UrlFactory::MapType::AirmapElevation) {
QString type = getQGCMapEngine()->hashToType(hash);
if (type == "AirmapElevation" ) {
image = TerrainTile::serialize(image);
}
QString format = getQGCMapEngine()->urlFactory()->getImageFormat(type, image);

6
src/QtLocationPlugin/QGCMapTileSet.h

@ -103,7 +103,7 @@ public: @@ -103,7 +103,7 @@ public:
int maxZoom () { return _maxZoom; }
QDateTime creationDate () { return _creationDate; }
quint64 id () { return _id; }
UrlFactory::MapType type () { return _type; }
QString type () { return _type; }
bool complete () { return _defaultSet || (_totalTileCount <= _savedTileCount); }
bool defaultSet () { return _defaultSet; }
quint64 setID () { return _id; }
@ -130,7 +130,7 @@ public: @@ -130,7 +130,7 @@ public:
void setMaxZoom (int zoom) { _maxZoom = zoom; }
void setCreationDate (QDateTime date) { _creationDate = date; }
void setId (quint64 id) { _id = id; }
void setType (UrlFactory::MapType type) { _type = type; }
void setType (QString type) { _type = type; }
void setDefaultSet (bool def) { _defaultSet = def; }
void setDeleting (bool del) { _deleting = del; emit deletingChanged(); }
void setDownloading (bool down) { _downloading = down; }
@ -178,7 +178,7 @@ private: @@ -178,7 +178,7 @@ private:
bool _downloading;
QDateTime _creationDate;
quint64 _id;
UrlFactory::MapType _type;
QString _type;
QNetworkAccessManager* _networkManager;
QHash<QString, QNetworkReply*> _replies;
quint32 _errorCount;

52
src/QtLocationPlugin/QGCMapUrlEngine.cpp

@ -41,7 +41,10 @@ UrlFactory::UrlFactory() @@ -41,7 +41,10 @@ UrlFactory::UrlFactory()
_providersTable["GoogleStreet"] = new GoogleStreetMapProvider(this);
_providersTable["GoogleSatellite"] = new GoogleSatelliteMapProvider(this);
#endif
_curMapProvider = _providersTable["GoogleStreet"];
}
void UrlFactory::registerProvider(QString name, MapProvider* provider){
_providersTable[name]=provider;
}
//-----------------------------------------------------------------------------
@ -49,13 +52,17 @@ UrlFactory::~UrlFactory() @@ -49,13 +52,17 @@ UrlFactory::~UrlFactory()
{
}
QString
UrlFactory::getImageFormat(int id, const QByteArray& image)
{
return _providersTable[getTypeFromId(id)]->getImageFormat(image);
}
//-----------------------------------------------------------------------------
QString
UrlFactory::getImageFormat(MapType type, const QByteArray& image)
UrlFactory::getImageFormat(QString type, const QByteArray& image)
{
Q_UNUSED(type);
return _curMapProvider->getImageFormat(image);
return _providersTable[type]->getImageFormat(image);
//QString format;
//if(image.size() > 2)
//{
@ -119,13 +126,17 @@ UrlFactory::getImageFormat(MapType type, const QByteArray& image) @@ -119,13 +126,17 @@ UrlFactory::getImageFormat(MapType type, const QByteArray& image)
//}
//return format;
}
QNetworkRequest
UrlFactory::getTileURL(int id, int x, int y, int zoom, QNetworkAccessManager* networkManager){
return _providersTable[getTypeFromId(id)]->getTileURL(x,y,zoom,networkManager);
}
//-----------------------------------------------------------------------------
QNetworkRequest
UrlFactory::getTileURL(MapType type, int x, int y, int zoom, QNetworkAccessManager* networkManager)
UrlFactory::getTileURL(QString type, int x, int y, int zoom, QNetworkAccessManager* networkManager)
{
Q_UNUSED(type);
return _curMapProvider->getTileURL(x,y,zoom,networkManager);
return _providersTable[type]->getTileURL(x,y,zoom,networkManager);
////-- Build URL
//QNetworkRequest request;
//QString url = _getURL(type, x, y, zoom, networkManager);
@ -187,7 +198,7 @@ UrlFactory::getTileURL(MapType type, int x, int y, int zoom, QNetworkAccessManag @@ -187,7 +198,7 @@ UrlFactory::getTileURL(MapType type, int x, int y, int zoom, QNetworkAccessManag
//-----------------------------------------------------------------------------
#if 0
QString
UrlFactory::_getURL(MapType type, int x, int y, int zoom, QNetworkAccessManager* networkManager)
UrlFactory::_getURL(QString type, int x, int y, int zoom, QNetworkAccessManager* networkManager)
{
switch (type) {
Q_UNUSED(networkManager);
@ -447,10 +458,9 @@ UrlFactory::_getURL(MapType type, int x, int y, int zoom, QNetworkAccessManager* @@ -447,10 +458,9 @@ UrlFactory::_getURL(MapType type, int x, int y, int zoom, QNetworkAccessManager*
//-----------------------------------------------------------------------------
quint32
UrlFactory::averageSizeForType(MapType type)
UrlFactory::averageSizeForType(QString type)
{
Q_UNUSED(type);
return GoogleMapProvider::getAverageSize();
return _providersTable[type]->getAverageSize();
// switch (type) {
// case GoogleMap:
@ -490,3 +500,23 @@ UrlFactory::averageSizeForType(MapType type) @@ -490,3 +500,23 @@ UrlFactory::averageSizeForType(MapType type)
// }
// return AVERAGE_TILE_SIZE;
}
QString UrlFactory::getTypeFromId(int id){
QHashIterator<QString, MapProvider*> i(_providersTable);
while(i.hasNext()){
i.next();
if(abs(qHash(i.key())) == id){
return i.key();
}
}
return "";
}
// Todo : qHash produce a uint bigger than max(int)
// There is still a low probability for abs to
// generate similar hash for different types
int UrlFactory::getIdFromType(QString type){
return abs(qHash(type));
}

120
src/QtLocationPlugin/QGCMapUrlEngine.h

@ -23,77 +23,83 @@ @@ -23,77 +23,83 @@
class UrlFactory : public QObject {
Q_OBJECT
public:
enum MapType
{
Invalid = -1,
GoogleMap = 1,
GoogleSatellite = 4,
GoogleLabels = 8,
GoogleTerrain = 16,
GoogleHybrid = 20,
OpenStreetMap = 32,
OpenStreetOsm = 33,
OpenStreetMapSurfer = 34,
OpenStreetMapSurferTerrain=35,
StatkartTopo = 100,
EniroTopo = 110,
BingMap = 444,
BingSatellite = 555,
BingHybrid = 666,
/*
MapQuestMap = 700,
MapQuestSat = 701,
*/
VWorldMap = 800,
VWorldSatellite = 801,
VWorldStreet = 802,
MapboxStreets = 6000,
MapboxLight = 6001,
MapboxDark = 6002,
MapboxSatellite = 6003,
MapboxHybrid = 6004,
MapboxWheatPaste = 6005,
MapboxStreetsBasic = 6006,
MapboxComic = 6007,
MapboxOutdoors = 6008,
MapboxRunBikeHike = 6009,
MapboxPencil = 6010,
MapboxPirates = 6011,
MapboxEmerald = 6012,
MapboxHighContrast = 6013,
EsriWorldStreet = 7000,
EsriWorldSatellite = 7001,
EsriTerrain = 7002,
AirmapElevation = 8001
};
//
// enum QString
// {
// Invalid = -1,
//
// GoogleMap = 1,
// GoogleSatellite = 4,
// GoogleLabels = 8,
// GoogleTerrain = 16,
// GoogleHybrid = 20,
//
// OpenStreetMap = 32,
// OpenStreetOsm = 33,
// OpenStreetMapSurfer = 34,
// OpenStreetMapSurferTerrain=35,
//
// StatkartTopo = 100,
// EniroTopo = 110,
//
// BingMap = 444,
// BingSatellite = 555,
// BingHybrid = 666,
//
// /*
// MapQuestMap = 700,
// MapQuestSat = 701,
// */
//
// VWorldMap = 800,
// VWorldSatellite = 801,
// VWorldStreet = 802,
//
// MapboxStreets = 6000,
// MapboxLight = 6001,
// MapboxDark = 6002,
// MapboxSatellite = 6003,
// MapboxHybrid = 6004,
// MapboxWheatPaste = 6005,
// MapboxStreetsBasic = 6006,
// MapboxComic = 6007,
// MapboxOutdoors = 6008,
// MapboxRunBikeHike = 6009,
// MapboxPencil = 6010,
// MapboxPirates = 6011,
// MapboxEmerald = 6012,
// MapboxHighContrast = 6013,
//
// EsriWorldStreet = 7000,
// EsriWorldSatellite = 7001,
// EsriTerrain = 7002,
//
// AirmapElevation = 8001
// };
UrlFactory ();
~UrlFactory ();
QNetworkRequest getTileURL (MapType type, int x, int y, int zoom, QNetworkAccessManager* networkManager);
QString getImageFormat (MapType type, const QByteArray& image);
QNetworkRequest getTileURL (QString type, int x, int y, int zoom, QNetworkAccessManager* networkManager);
QNetworkRequest getTileURL (int id, int x, int y, int zoom, QNetworkAccessManager* networkManager);
static quint32 averageSizeForType (MapType type);
QString getImageFormat (QString type, const QByteArray& image);
QString getImageFormat (int id , const QByteArray& image);
quint32 averageSizeForType (QString type);
QHash<QString, MapProvider*> getProviderTable(){return _providersTable;}
int getIdFromType(QString type);
QString getTypeFromId(int id);
private:
int _timeout;
QHash<QString, MapProvider*> _providersTable;
void registerProvider(QString Name, MapProvider* provider);
// BingMaps
//QString _versionBingMaps;
MapProvider* _curMapProvider;
};

10
src/QtLocationPlugin/QGCTileCacheWorker.cpp

@ -282,7 +282,7 @@ QGCCacheWorker::_getTile(QGCMapTask* mtask) @@ -282,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 = static_cast<UrlFactory::MapType>(query.value(2).toInt());
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);
task->setTileFetched(tile);
@ -318,7 +318,7 @@ QGCCacheWorker::_getTileSets(QGCMapTask* mtask) @@ -318,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(static_cast<UrlFactory::MapType>(query.value("type").toInt()));
set->setType(getQGCMapEngine()->urlFactory()->getTypeFromId(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()));
@ -353,7 +353,7 @@ QGCCacheWorker::_updateSetTotals(QGCCachedTileSet* set) @@ -353,7 +353,7 @@ QGCCacheWorker::_updateSetTotals(QGCCachedTileSet* set)
set->setSavedTileSize(subquery.value(1).toULongLong());
qCDebug(QGCTileCacheLog) << "Set" << set->id() << "Totals:" << set->savedTileCount() << " " << set->savedTileSize() << "Expected: " << set->totalTileCount() << " " << set->totalTilesSize();
//-- Update (estimated) size
quint64 avg = UrlFactory::averageSizeForType(set->type());
quint64 avg = getQGCMapEngine()->urlFactory()->averageSizeForType(set->type());
if(set->totalTileCount() <= set->savedTileCount()) {
//-- We're done so the saved size is the total size
set->setTotalTileSize(set->savedTileSize());
@ -465,7 +465,7 @@ QGCCacheWorker::_createTileSet(QGCMapTask *mtask) @@ -465,7 +465,7 @@ QGCCacheWorker::_createTileSet(QGCMapTask *mtask)
task->tileSet()->topleftLon(), task->tileSet()->topleftLat(),
task->tileSet()->bottomRightLon(), task->tileSet()->bottomRightLat(), task->tileSet()->type());
tileCount += set.tileCount;
UrlFactory::MapType type = task->tileSet()->type();
QString type = task->tileSet()->type();
for(int x = set.tileX0; x <= set.tileX1; x++) {
for(int y = set.tileY0; y <= set.tileY1; y++) {
//-- See if tile is already downloaded
@ -524,7 +524,7 @@ QGCCacheWorker::_getTileDownloadList(QGCMapTask* mtask) @@ -524,7 +524,7 @@ QGCCacheWorker::_getTileDownloadList(QGCMapTask* mtask)
while(query.next()) {
QGCTile* tile = new QGCTile;
tile->setHash(query.value("hash").toString());
tile->setType(static_cast<UrlFactory::MapType>(query.value("type").toInt()));
tile->setType(getQGCMapEngine()->urlFactory()->getTypeFromId(query.value("type").toInt()));
tile->setX(query.value("x").toInt());
tile->setY(query.value("y").toInt());
tile->setZ(query.value("z").toInt());

20
src/QtLocationPlugin/QGeoMapReplyQGC.cpp

@ -73,7 +73,7 @@ QGeoTiledMapReplyQGC::QGeoTiledMapReplyQGC(QNetworkAccessManager *networkManager @@ -73,7 +73,7 @@ QGeoTiledMapReplyQGC::QGeoTiledMapReplyQGC(QNetworkAccessManager *networkManager
setFinished(true);
setCached(false);
} else {
QGCFetchTileTask* task = getQGCMapEngine()->createFetchTileTask(static_cast<UrlFactory::MapType>(spec.mapId()), spec.x(), spec.y(), spec.zoom());
QGCFetchTileTask* task = getQGCMapEngine()->createFetchTileTask(getQGCMapEngine()->urlFactory()->getTypeFromId(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);
@ -122,13 +122,14 @@ QGeoTiledMapReplyQGC::networkReplyFinished() @@ -122,13 +122,14 @@ QGeoTiledMapReplyQGC::networkReplyFinished()
return;
}
QByteArray a = _reply->readAll();
QString format = getQGCMapEngine()->urlFactory()->getImageFormat(static_cast<UrlFactory::MapType>(tileSpec().mapId()), a);
QString format = getQGCMapEngine()->urlFactory()->getImageFormat(tileSpec().mapId(), a);
//-- Test for a specialized, elevation data (not map tile)
if (static_cast<UrlFactory::MapType>(tileSpec().mapId()) == UrlFactory::MapType::AirmapElevation) {
int AirmapElevationId = getQGCMapEngine()->urlFactory()->getIdFromType("AirmapElevation");
if (tileSpec().mapId() == AirmapElevationId) {
a = TerrainTile::serialize(a);
//-- Cache it if valid
if(!a.isEmpty()) {
getQGCMapEngine()->cacheTile(UrlFactory::MapType::AirmapElevation, tileSpec().x(), tileSpec().y(), tileSpec().zoom(), a, format);
getQGCMapEngine()->cacheTile("AirmapElevation", tileSpec().x(), tileSpec().y(), tileSpec().zoom(), a, format);
}
emit terrainDone(a, QNetworkReply::NoError);
} else {
@ -136,7 +137,7 @@ QGeoTiledMapReplyQGC::networkReplyFinished() @@ -136,7 +137,7 @@ QGeoTiledMapReplyQGC::networkReplyFinished()
setMapImageData(a);
if(!format.isEmpty()) {
setMapImageFormat(format);
getQGCMapEngine()->cacheTile(static_cast<UrlFactory::MapType>(tileSpec().mapId()), tileSpec().x(), tileSpec().y(), tileSpec().zoom(), a, format);
getQGCMapEngine()->cacheTile(getQGCMapEngine()->urlFactory()->getTypeFromId(tileSpec().mapId()), tileSpec().x(), tileSpec().y(), tileSpec().zoom(), a, format);
}
setFinished(true);
}
@ -152,7 +153,8 @@ QGeoTiledMapReplyQGC::networkReplyError(QNetworkReply::NetworkError error) @@ -152,7 +153,8 @@ QGeoTiledMapReplyQGC::networkReplyError(QNetworkReply::NetworkError error)
return;
}
//-- Test for a specialized, elevation data (not map tile)
if (static_cast<UrlFactory::MapType>(tileSpec().mapId()) == UrlFactory::MapType::AirmapElevation) {
int AirmapElevationId = getQGCMapEngine()->urlFactory()->getIdFromType("AirmapElevation");
if (tileSpec().mapId() == AirmapElevationId) {
emit terrainDone(QByteArray(), error);
} else {
//-- Regular map tile
@ -170,7 +172,8 @@ void @@ -170,7 +172,8 @@ void
QGeoTiledMapReplyQGC::cacheError(QGCMapTask::TaskType type, QString /*errorString*/)
{
if(!getQGCMapEngine()->isInternetActive()) {
if (static_cast<UrlFactory::MapType>(tileSpec().mapId()) == UrlFactory::MapType::AirmapElevation) {
int AirmapElevationId = getQGCMapEngine()->urlFactory()->getIdFromType("AirmapElevation");
if (tileSpec().mapId() == AirmapElevationId) {
emit terrainDone(QByteArray(), QNetworkReply::NetworkSessionFailedError);
} else {
setError(QGeoTiledMapReply::CommunicationError, "Network not available");
@ -207,7 +210,8 @@ void @@ -207,7 +210,8 @@ void
QGeoTiledMapReplyQGC::cacheReply(QGCCacheTile* tile)
{
//-- Test for a specialized, elevation data (not map tile)
if (static_cast<UrlFactory::MapType>(tileSpec().mapId()) == UrlFactory::MapType::AirmapElevation) {
int AirmapElevationId = getQGCMapEngine()->urlFactory()->getIdFromType("AirmapElevation");
if (tileSpec().mapId() == AirmapElevationId) {
emit terrainDone(tile->img(), QNetworkReply::NoError);
} else {
//-- Regular map tile

2
src/QtLocationPlugin/QGeoTileFetcherQGC.cpp

@ -74,7 +74,7 @@ QGeoTiledMapReply* @@ -74,7 +74,7 @@ QGeoTiledMapReply*
QGeoTileFetcherQGC::getTileImage(const QGeoTileSpec &spec)
{
//-- Build URL
QNetworkRequest request = getQGCMapEngine()->urlFactory()->getTileURL((UrlFactory::MapType)spec.mapId(), spec.x(), spec.y(), spec.zoom(), _networkManager);
QNetworkRequest request = getQGCMapEngine()->urlFactory()->getTileURL(spec.mapId(), spec.x(), spec.y(), spec.zoom(), _networkManager);
if ( ! request.url().isEmpty() ) {
return new QGeoTiledMapReplyQGC(_networkManager, request, spec);
}

6
src/QtLocationPlugin/QGeoTiledMappingManagerEngineQGC.cpp

@ -106,10 +106,12 @@ QGeoTiledMappingManagerEngineQGC::QGeoTiledMappingManagerEngineQGC(const QVarian @@ -106,10 +106,12 @@ QGeoTiledMappingManagerEngineQGC::QGeoTiledMappingManagerEngineQGC(const QVarian
while(i.hasNext()){
i.next();
id++;
mapList.append(QGCGEOMAPTYPE(i.value()->getMapStyle(), i.key(), i.key(), false, false, id));
qDebug()<< "Add MapProvider" <<i.value()->getMapStyle() << i.key()<<getQGCMapEngine()->urlFactory()->getIdFromType(i.key());
mapList.append(QGCGEOMAPTYPE(i.value()->getMapStyle(), i.key(), i.key(), false, false, getQGCMapEngine()->urlFactory()->getIdFromType(i.key()) ));
}
setSupportedMapTypes(mapList);
qDebug() << "End Adding Provider";
//-- IMPORTANT
// Changes here must reflect those in QGCMapEngine.cpp

12
src/QtLocationPlugin/QMLControl/QGCMapEngineManager.cc

@ -69,8 +69,6 @@ QGCMapEngineManager::setToolbox(QGCToolbox *toolbox) @@ -69,8 +69,6 @@ QGCMapEngineManager::setToolbox(QGCToolbox *toolbox)
void
QGCMapEngineManager::updateForCurrentView(double lon0, double lat0, double lon1, double lat1, int minZoom, int maxZoom, const QString& mapName)
{
UrlFactory::MapType mapType = QGCMapEngine::getTypeFromName(mapName);
_topleftLat = lat0;
_topleftLon = lon0;
_bottomRightLat = lat1;
@ -82,11 +80,11 @@ QGCMapEngineManager::updateForCurrentView(double lon0, double lat0, double lon1, @@ -82,11 +80,11 @@ QGCMapEngineManager::updateForCurrentView(double lon0, double lat0, double lon1,
_elevationSet.clear();
for(int z = minZoom; z <= maxZoom; z++) {
QGCTileSet set = QGCMapEngine::getTileCount(z, lon0, lat0, lon1, lat1, mapType);
QGCTileSet set = QGCMapEngine::getTileCount(z, lon0, lat0, lon1, lat1, mapName);
_imageSet += set;
}
if (_fetchElevation) {
QGCTileSet set = QGCMapEngine::getTileCount(1, lon0, lat0, lon1, lat1, UrlFactory::AirmapElevation);
QGCTileSet set = QGCMapEngine::getTileCount(1, lon0, lat0, lon1, lat1, "AirmapElevation");
_elevationSet += set;
}
@ -129,7 +127,7 @@ void @@ -129,7 +127,7 @@ void
QGCMapEngineManager::_tileSetFetched(QGCCachedTileSet* tileSet)
{
//-- A blank (default) type means it uses various types and not just one
if(tileSet->type() == UrlFactory::Invalid) {
if(tileSet->type() == "Invalid") {
tileSet->setMapTypeStr("Various");
}
_tileSets.append(tileSet);
@ -152,7 +150,7 @@ QGCMapEngineManager::startDownload(const QString& name, const QString& mapType) @@ -152,7 +150,7 @@ QGCMapEngineManager::startDownload(const QString& name, const QString& mapType)
set->setMaxZoom(_maxZoom);
set->setTotalTileSize(_imageSet.tileSize);
set->setTotalTileCount(static_cast<quint32>(_imageSet.tileCount));
set->setType(QGCMapEngine::getTypeFromName(mapType));
set->setType(mapType);
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);
@ -172,7 +170,7 @@ QGCMapEngineManager::startDownload(const QString& name, const QString& mapType) @@ -172,7 +170,7 @@ QGCMapEngineManager::startDownload(const QString& name, const QString& mapType)
set->setMaxZoom(1);
set->setTotalTileSize(_elevationSet.tileSize);
set->setTotalTileCount(static_cast<quint32>(_elevationSet.tileCount));
set->setType(QGCMapEngine::getTypeFromName("Airmap Elevation Data"));
set->setType("AirmapElevation");
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);

8
src/Terrain/TerrainQuery.cc

@ -426,13 +426,13 @@ bool TerrainTileManager::_getAltitudesForCoordinates(const QList<QGeoCoordinate> @@ -426,13 +426,13 @@ bool TerrainTileManager::_getAltitudesForCoordinates(const QList<QGeoCoordinate>
}
} else {
if (_state != State::Downloading) {
QNetworkRequest request = getQGCMapEngine()->urlFactory()->getTileURL(UrlFactory::AirmapElevation, QGCMapEngine::long2elevationTileX(coordinate.longitude(), 1), QGCMapEngine::lat2elevationTileY(coordinate.latitude(), 1), 1, &_networkManager);
QNetworkRequest request = getQGCMapEngine()->urlFactory()->getTileURL("AirmapElevation", QGCMapEngine::long2elevationTileX(coordinate.longitude(), 1), QGCMapEngine::lat2elevationTileY(coordinate.latitude(), 1), 1, &_networkManager);
qCDebug(TerrainQueryLog) << "TerrainTileManager::_getAltitudesForCoordinates query from database" << request.url();
QGeoTileSpec spec;
spec.setX(QGCMapEngine::long2elevationTileX(coordinate.longitude(), 1));
spec.setY(QGCMapEngine::lat2elevationTileY(coordinate.latitude(), 1));
spec.setZoom(1);
spec.setMapId(UrlFactory::AirmapElevation);
spec.setMapId(getQGCMapEngine()->urlFactory()->getIdFromType("AirmapElevation"));
QGeoTiledMapReplyQGC* reply = new QGeoTiledMapReplyQGC(&_networkManager, request, spec);
connect(reply, &QGeoTiledMapReplyQGC::terrainDone, this, &TerrainTileManager::_terrainDone);
_state = State::Downloading;
@ -473,7 +473,7 @@ void TerrainTileManager::_terrainDone(QByteArray responseBytes, QNetworkReply::N @@ -473,7 +473,7 @@ void TerrainTileManager::_terrainDone(QByteArray responseBytes, QNetworkReply::N
// remove from download queue
QGeoTileSpec spec = reply->tileSpec();
QString hash = QGCMapEngine::getTileHash(UrlFactory::AirmapElevation, spec.x(), spec.y(), spec.zoom());
QString hash = QGCMapEngine::getTileHash("AirmapElevation", spec.x(), spec.y(), spec.zoom());
// handle potential errors
if (error != QNetworkReply::NoError) {
@ -539,7 +539,7 @@ void TerrainTileManager::_terrainDone(QByteArray responseBytes, QNetworkReply::N @@ -539,7 +539,7 @@ void TerrainTileManager::_terrainDone(QByteArray responseBytes, QNetworkReply::N
QString TerrainTileManager::_getTileHash(const QGeoCoordinate& coordinate)
{
QString ret = QGCMapEngine::getTileHash(UrlFactory::AirmapElevation, QGCMapEngine::long2elevationTileX(coordinate.longitude(), 1), QGCMapEngine::lat2elevationTileY(coordinate.latitude(), 1), 1);
QString ret = QGCMapEngine::getTileHash("AirmapElevation", QGCMapEngine::long2elevationTileX(coordinate.longitude(), 1), QGCMapEngine::lat2elevationTileY(coordinate.latitude(), 1), 1);
qCDebug(TerrainQueryVerboseLog) << "Computing unique tile hash for " << coordinate << ret;
return ret;

54
src/Terrain/patch

@ -0,0 +1,54 @@ @@ -0,0 +1,54 @@
diff --git a/libs/mavlink/include/mavlink/v2.0 b/libs/mavlink/include/mavlink/v2.0
--- a/libs/mavlink/include/mavlink/v2.0
+++ b/libs/mavlink/include/mavlink/v2.0
@@ -1 +1 @@
-Subproject commit 68869da6575d4ca61b92e9081b7c81587f157ed6
+Subproject commit 68869da6575d4ca61b92e9081b7c81587f157ed6-dirty
diff --git a/src/Terrain/TerrainQueryManager.cc b/src/Terrain/TerrainQueryManager.cc
index 59ec2d4..c38a870 100644
--- a/src/Terrain/TerrainQueryManager.cc
+++ b/src/Terrain/TerrainQueryManager.cc
@@ -3,17 +3,20 @@
TerrainQueryManager::TerrainQueryManager(QObject* parent)
: TerrainQueryInterface(parent)
{
- _providerAirMap = new TerrainOfflineAirMapQuery(parent);
+ connect(&_providerAirMap, &TerrainQueryInterface::coordinateHeightsReceived, this, &TerrainQueryInterface::coordinateHeightsReceived);
+ connect(&_providerAirMap, &TerrainQueryInterface::pathHeightsReceived, this, &TerrainQueryInterface::pathHeightsReceived);
+ connect(&_providerAirMap, &TerrainQueryInterface::carpetHeightsReceived, this, &TerrainQueryInterface::carpetHeightsReceived);
}
void TerrainQueryManager::requestCoordinateHeights(const QList<QGeoCoordinate>& coordinates){
- _providerAirMap->requestCoordinateHeights(coordinates);
+ _providerAirMap.requestCoordinateHeights(coordinates);
}
void TerrainQueryManager::requestPathHeights(const QGeoCoordinate& fromCoord, const QGeoCoordinate& toCoord){
- _providerAirMap->requestPathHeights(fromCoord,toCoord);
+ _providerAirMap.requestPathHeights(fromCoord,toCoord);
}
void TerrainQueryManager::requestCarpetHeights(const QGeoCoordinate& swCoord, const QGeoCoordinate& neCoord, bool statsOnly){
- _providerAirMap->requestCarpetHeights(swCoord,neCoord,statsOnly);
+ _providerAirMap.requestCarpetHeights(swCoord,neCoord,statsOnly);
}
+
diff --git a/src/Terrain/TerrainQueryManager.h b/src/Terrain/TerrainQueryManager.h
index 2921679..9b4494c 100644
--- a/src/Terrain/TerrainQueryManager.h
+++ b/src/Terrain/TerrainQueryManager.h
@@ -27,12 +27,12 @@ public:
/// @param neCoord North-East bound of rectangular area to query
/// @param statsOnly true: Return only stats, no carpet data
void requestCarpetHeights(const QGeoCoordinate& swCoord, const QGeoCoordinate& neCoord, bool statsOnly);
-
+
signals:
void coordinateHeightsReceived(bool success, QList<double> heights);
void pathHeightsReceived(bool success, double latStep, double lonStep, const QList<double>& heights);
void carpetHeightsReceived(bool success, double minHeight, double maxHeight, const QList<QList<double>>& carpet);
private:
- TerrainOfflineAirMapQuery * _providerAirMap;
+ TerrainOfflineAirMapQuery _providerAirMap;
};
Loading…
Cancel
Save