Commit 83643d68 authored by Andreas Bircher's avatar Andreas Bircher

Cache offline elevation maps

parent e7932490
...@@ -91,6 +91,12 @@ stQGeoTileCacheQGCMapTypes kEsriTypes[] = { ...@@ -91,6 +91,12 @@ stQGeoTileCacheQGCMapTypes kEsriTypes[] = {
#define NUM_ESRIMAPS (sizeof(kEsriTypes) / sizeof(stQGeoTileCacheQGCMapTypes)) #define NUM_ESRIMAPS (sizeof(kEsriTypes) / sizeof(stQGeoTileCacheQGCMapTypes))
stQGeoTileCacheQGCMapTypes kElevationTypes[] = {
{"Airmap Elevation Data", UrlFactory::AirmapElevation}
};
#define NUM_ELEVMAPS (sizeof(kElevationTypes) / sizeof(stQGeoTileCacheQGCMapTypes))
static const char* kMaxDiskCacheKey = "MaxDiskCache"; static const char* kMaxDiskCacheKey = "MaxDiskCache";
static const char* kMaxMemCacheKey = "MaxMemoryCache"; static const char* kMaxMemCacheKey = "MaxMemoryCache";
...@@ -105,6 +111,9 @@ getQGCMapEngine() ...@@ -105,6 +111,9 @@ getQGCMapEngine()
return kMapEngine; return kMapEngine;
} }
//-----------------------------------------------------------------------------
const double QGCMapEngine::srtm1TileSize = 0.025;
//----------------------------------------------------------------------------- //-----------------------------------------------------------------------------
void void
destroyMapEngine() destroyMapEngine()
...@@ -296,10 +305,17 @@ QGCMapEngine::getTileCount(int zoom, double topleftLon, double topleftLat, doubl ...@@ -296,10 +305,17 @@ QGCMapEngine::getTileCount(int zoom, double topleftLon, double topleftLat, doubl
if(zoom < 1) zoom = 1; if(zoom < 1) zoom = 1;
if(zoom > MAX_MAP_ZOOM) zoom = MAX_MAP_ZOOM; if(zoom > MAX_MAP_ZOOM) zoom = MAX_MAP_ZOOM;
QGCTileSet set; QGCTileSet set;
set.tileX0 = long2tileX(topleftLon, zoom); if (mapType != UrlFactory::AirmapElevation) {
set.tileY0 = lat2tileY(topleftLat, zoom); set.tileX0 = long2tileX(topleftLon, zoom);
set.tileX1 = long2tileX(bottomRightLon, zoom); set.tileY0 = lat2tileY(topleftLat, zoom);
set.tileY1 = lat2tileY(bottomRightLat, zoom); set.tileX1 = long2tileX(bottomRightLon, zoom);
set.tileY1 = lat2tileY(bottomRightLat, zoom);
} else {
set.tileX0 = long2elevationTileX(topleftLon, zoom);
set.tileY0 = lat2elevationTileY(bottomRightLat, zoom);
set.tileX1 = long2elevationTileX(bottomRightLon, zoom);
set.tileY1 = lat2elevationTileY(topleftLat, zoom);
}
set.tileCount = (quint64)((quint64)set.tileX1 - (quint64)set.tileX0 + 1) * (quint64)((quint64)set.tileY1 - (quint64)set.tileY0 + 1); set.tileCount = (quint64)((quint64)set.tileX1 - (quint64)set.tileX0 + 1) * (quint64)((quint64)set.tileY1 - (quint64)set.tileY0 + 1);
set.tileSize = UrlFactory::averageSizeForType(mapType) * set.tileCount; set.tileSize = UrlFactory::averageSizeForType(mapType) * set.tileCount;
return set; return set;
...@@ -319,6 +335,22 @@ QGCMapEngine::lat2tileY(double lat, int z) ...@@ -319,6 +335,22 @@ QGCMapEngine::lat2tileY(double lat, int z)
return (int)(floor((1.0 - log( tan(lat * M_PI/180.0) + 1.0 / cos(lat * M_PI/180.0)) / M_PI) / 2.0 * pow(2.0, z))); return (int)(floor((1.0 - log( tan(lat * M_PI/180.0) + 1.0 / cos(lat * M_PI/180.0)) / M_PI) / 2.0 * pow(2.0, z)));
} }
//-----------------------------------------------------------------------------
int
QGCMapEngine::long2elevationTileX(double lon, int z)
{
Q_UNUSED(z);
return (int)(floor((lon + 180.0) / srtm1TileSize));
}
//-----------------------------------------------------------------------------
int
QGCMapEngine::lat2elevationTileY(double lat, int z)
{
Q_UNUSED(z);
return (int)(floor((lat + 90.0) / srtm1TileSize));
}
//----------------------------------------------------------------------------- //-----------------------------------------------------------------------------
UrlFactory::MapType UrlFactory::MapType
QGCMapEngine::getTypeFromName(const QString& name) QGCMapEngine::getTypeFromName(const QString& name)
...@@ -336,6 +368,10 @@ QGCMapEngine::getTypeFromName(const QString& name) ...@@ -336,6 +368,10 @@ QGCMapEngine::getTypeFromName(const QString& name)
if(name.compare(kEsriTypes[i].name, Qt::CaseInsensitive) == 0) if(name.compare(kEsriTypes[i].name, Qt::CaseInsensitive) == 0)
return kEsriTypes[i].type; 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; return UrlFactory::Invalid;
} }
...@@ -357,6 +393,9 @@ QGCMapEngine::getMapNameList() ...@@ -357,6 +393,9 @@ QGCMapEngine::getMapNameList()
mapList << kEsriTypes[i].name; mapList << kEsriTypes[i].name;
} }
} }
for(size_t i = 0; i < NUM_ELEVMAPS; i++) {
mapList << kElevationTypes[i].name;
}
return mapList; return mapList;
} }
...@@ -469,6 +508,7 @@ QGCMapEngine::concurrentDownloads(UrlFactory::MapType type) ...@@ -469,6 +508,7 @@ QGCMapEngine::concurrentDownloads(UrlFactory::MapType type)
case UrlFactory::EsriWorldStreet: case UrlFactory::EsriWorldStreet:
case UrlFactory::EsriWorldSatellite: case UrlFactory::EsriWorldSatellite:
case UrlFactory::EsriTerrain: case UrlFactory::EsriTerrain:
case UrlFactory::AirmapElevation:
return 12; return 12;
/* /*
case UrlFactory::MapQuestMap: case UrlFactory::MapQuestMap:
......
...@@ -94,12 +94,17 @@ public: ...@@ -94,12 +94,17 @@ public:
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, UrlFactory::MapType mapType);
static int long2tileX (double lon, int z); static int long2tileX (double lon, int z);
static int lat2tileY (double lat, 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 QString getTileHash (UrlFactory::MapType type, int x, int y, int z);
static UrlFactory::MapType getTypeFromName (const QString &name); static UrlFactory::MapType getTypeFromName (const QString &name);
static QString bigSizeToString (quint64 size); static QString bigSizeToString (quint64 size);
static QString numberToString (quint64 number); static QString numberToString (quint64 number);
static int concurrentDownloads (UrlFactory::MapType type); static int concurrentDownloads (UrlFactory::MapType type);
/// size of an elevation tile in degree
static const double srtm1TileSize;
private slots: private slots:
void _updateTotals (quint32 totaltiles, quint64 totalsize, quint32 defaulttiles, quint64 defaultsize); void _updateTotals (quint32 totaltiles, quint64 totalsize, quint32 defaulttiles, quint64 defaultsize);
void _pruned (); void _pruned ();
......
...@@ -36,6 +36,7 @@ ...@@ -36,6 +36,7 @@
static const unsigned char pngSignature[] = {0x89, 0x50, 0x4E, 0x47, 0x0D, 0x0A, 0x1A, 0x0A, 0x00}; static const unsigned char pngSignature[] = {0x89, 0x50, 0x4E, 0x47, 0x0D, 0x0A, 0x1A, 0x0A, 0x00};
static const unsigned char jpegSignature[] = {0xFF, 0xD8, 0xFF, 0x00}; static const unsigned char jpegSignature[] = {0xFF, 0xD8, 0xFF, 0x00};
static const unsigned char gifSignature[] = {0x47, 0x49, 0x46, 0x38, 0x00}; static const unsigned char gifSignature[] = {0x47, 0x49, 0x46, 0x38, 0x00};
static const unsigned char jsonSignature[] = {0x7A, 0x22, 0x00}; // two characters '{"'
//----------------------------------------------------------------------------- //-----------------------------------------------------------------------------
UrlFactory::UrlFactory() UrlFactory::UrlFactory()
...@@ -85,6 +86,8 @@ UrlFactory::getImageFormat(MapType type, const QByteArray& image) ...@@ -85,6 +86,8 @@ UrlFactory::getImageFormat(MapType type, const QByteArray& image)
format = "jpg"; format = "jpg";
else if (image.startsWith(reinterpret_cast<const char*>(gifSignature))) else if (image.startsWith(reinterpret_cast<const char*>(gifSignature)))
format = "gif"; format = "gif";
else if (image.startsWith(reinterpret_cast<const char*>(jsonSignature)))
format = "json";
else { else {
switch (type) { switch (type) {
case GoogleMap: case GoogleMap:
...@@ -119,6 +122,9 @@ UrlFactory::getImageFormat(MapType type, const QByteArray& image) ...@@ -119,6 +122,9 @@ UrlFactory::getImageFormat(MapType type, const QByteArray& image)
case BingHybrid: case BingHybrid:
format = "jpg"; format = "jpg";
break; break;
case AirmapElevation:
format = "json";
break;
default: default:
qWarning("UrlFactory::getImageFormat() Unknown map id %d", type); qWarning("UrlFactory::getImageFormat() Unknown map id %d", type);
break; break;
...@@ -177,6 +183,10 @@ UrlFactory::getTileURL(MapType type, int x, int y, int zoom, QNetworkAccessManag ...@@ -177,6 +183,10 @@ UrlFactory::getTileURL(MapType type, int x, int y, int zoom, QNetworkAccessManag
} }
return request; return request;
case AirmapElevation:
request.setRawHeader("Referrer", "https://api.airmap.com/");
break;
default: default:
break; break;
} }
...@@ -392,6 +402,14 @@ UrlFactory::_getURL(MapType type, int x, int y, int zoom, QNetworkAccessManager* ...@@ -392,6 +402,14 @@ UrlFactory::_getURL(MapType type, int x, int y, int zoom, QNetworkAccessManager*
} }
} }
break; break;
case AirmapElevation:
{
return QString("https://api.airmap.com/elevation/stage/srtm1/ele/carpet?points=%1,%2,%3,%4").arg(static_cast<double>(x)*QGCMapEngine::srtm1TileSize - 180.0).arg(
static_cast<double>(y)*QGCMapEngine::srtm1TileSize - 90.0).arg(
static_cast<double>(x + 1)*QGCMapEngine::srtm1TileSize - 180.0).arg(
static_cast<double>(y + 1)*QGCMapEngine::srtm1TileSize - 90.0);
}
break;
default: default:
qWarning("Unknown map id %d\n", type); qWarning("Unknown map id %d\n", type);
...@@ -534,6 +552,7 @@ UrlFactory::_tryCorrectGoogleVersions(QNetworkAccessManager* networkManager) ...@@ -534,6 +552,7 @@ UrlFactory::_tryCorrectGoogleVersions(QNetworkAccessManager* networkManager)
#define AVERAGE_MAPBOX_SAT_MAP 15739 #define AVERAGE_MAPBOX_SAT_MAP 15739
#define AVERAGE_MAPBOX_STREET_MAP 5648 #define AVERAGE_MAPBOX_STREET_MAP 5648
#define AVERAGE_TILE_SIZE 13652 #define AVERAGE_TILE_SIZE 13652
#define AVERAGE_AIRMAP_ELEV_SIZE 34000
//----------------------------------------------------------------------------- //-----------------------------------------------------------------------------
quint32 quint32
...@@ -557,6 +576,8 @@ UrlFactory::averageSizeForType(MapType type) ...@@ -557,6 +576,8 @@ UrlFactory::averageSizeForType(MapType type)
case MapboxStreetsBasic: case MapboxStreetsBasic:
case MapboxRunBikeHike: case MapboxRunBikeHike:
return AVERAGE_MAPBOX_STREET_MAP; return AVERAGE_MAPBOX_STREET_MAP;
case AirmapElevation:
return AVERAGE_AIRMAP_ELEV_SIZE;
case GoogleLabels: case GoogleLabels:
case MapboxDark: case MapboxDark:
case MapboxLight: case MapboxLight:
......
...@@ -72,7 +72,9 @@ public: ...@@ -72,7 +72,9 @@ public:
EsriWorldStreet = 7000, EsriWorldStreet = 7000,
EsriWorldSatellite = 7001, EsriWorldSatellite = 7001,
EsriTerrain = 7002 EsriTerrain = 7002,
AirmapElevation = 8000
}; };
UrlFactory (); UrlFactory ();
......
...@@ -732,6 +732,14 @@ QGCView { ...@@ -732,6 +732,14 @@ QGCView {
} }
} }
} }
QGCCheckBox {
anchors.left: parent.left
anchors.right: parent.right
text: qsTr("Fetch elevation data")
checked: QGroundControl.mapEngineManager.fetchElevation
onClicked: QGroundControl.mapEngineManager.fetchElevation = checked
visible: mapType != "Airmap Elevation Data"
}
} }
Rectangle { Rectangle {
......
...@@ -41,6 +41,7 @@ QGCMapEngineManager::QGCMapEngineManager(QGCApplication* app, QGCToolbox* toolbo ...@@ -41,6 +41,7 @@ QGCMapEngineManager::QGCMapEngineManager(QGCApplication* app, QGCToolbox* toolbo
, _setID(UINT64_MAX) , _setID(UINT64_MAX)
, _freeDiskSpace(0) , _freeDiskSpace(0)
, _diskSpace(0) , _diskSpace(0)
, _fetchElevation(true)
, _actionProgress(0) , _actionProgress(0)
, _importAction(ActionNone) , _importAction(ActionNone)
, _importReplace(false) , _importReplace(false)
...@@ -157,8 +158,26 @@ QGCMapEngineManager::startDownload(const QString& name, const QString& mapType) ...@@ -157,8 +158,26 @@ QGCMapEngineManager::startDownload(const QString& name, const QString& mapType)
} else { } else {
qWarning() << "QGCMapEngineManager::startDownload() No Tiles to save"; qWarning() << "QGCMapEngineManager::startDownload() No Tiles to save";
} }
// TODO: this could also get some feedback if (mapType != "Airmap Elevation Data" && _fetchElevation) {
_elevationProvider.cacheTerrainTiles(QGeoCoordinate(_bottomRightLat, _topleftLon), QGeoCoordinate(_topleftLat, _bottomRightLon)); QGCCachedTileSet* set = new QGCCachedTileSet(name + " Elevation");
set->setMapTypeStr("Airmap Elevation Data");
set->setTopleftLat(_topleftLat);
set->setTopleftLon(_topleftLon);
set->setBottomRightLat(_bottomRightLat);
set->setBottomRightLon(_bottomRightLon);
set->setMinZoom(1);
set->setMaxZoom(1);
set->setTotalTileSize(_totalSet.tileSize);
set->setTotalTileCount(_totalSet.tileCount);
set->setType(QGCMapEngine::getTypeFromName("Airmap Elevation Data"));
QGCCreateTileSetTask* task = new QGCCreateTileSetTask(set);
//-- Create Tile Set (it will also create a list of tiles to download)
connect(task, &QGCCreateTileSetTask::tileSetSaved, this, &QGCMapEngineManager::_tileSetSaved);
connect(task, &QGCMapTask::error, this, &QGCMapEngineManager::taskError);
getQGCMapEngine()->addTask(task);
} else {
qWarning() << "QGCMapEngineManager::startDownload() No Tiles to save";
}
} }
//----------------------------------------------------------------------------- //-----------------------------------------------------------------------------
......
...@@ -19,7 +19,6 @@ ...@@ -19,7 +19,6 @@
#include "QGCLoggingCategory.h" #include "QGCLoggingCategory.h"
#include "QGCMapEngine.h" #include "QGCMapEngine.h"
#include "QGCMapTileSet.h" #include "QGCMapTileSet.h"
#include "Terrain.h"
Q_DECLARE_LOGGING_CATEGORY(QGCMapEngineManagerLog) Q_DECLARE_LOGGING_CATEGORY(QGCMapEngineManagerLog)
...@@ -51,6 +50,7 @@ public: ...@@ -51,6 +50,7 @@ public:
Q_PROPERTY(quint32 maxMemCache READ maxMemCache WRITE setMaxMemCache NOTIFY maxMemCacheChanged) Q_PROPERTY(quint32 maxMemCache READ maxMemCache WRITE setMaxMemCache NOTIFY maxMemCacheChanged)
Q_PROPERTY(quint32 maxDiskCache READ maxDiskCache WRITE setMaxDiskCache NOTIFY maxDiskCacheChanged) Q_PROPERTY(quint32 maxDiskCache READ maxDiskCache WRITE setMaxDiskCache NOTIFY maxDiskCacheChanged)
Q_PROPERTY(QString errorMessage READ errorMessage NOTIFY errorMessageChanged) Q_PROPERTY(QString errorMessage READ errorMessage NOTIFY errorMessageChanged)
Q_PROPERTY(bool fetchElevation READ fetchElevation WRITE setFetchElevation NOTIFY fetchElevationChanged)
//-- Disk Space in MB //-- Disk Space in MB
Q_PROPERTY(quint32 freeDiskSpace READ freeDiskSpace NOTIFY freeDiskSpaceChanged) Q_PROPERTY(quint32 freeDiskSpace READ freeDiskSpace NOTIFY freeDiskSpaceChanged)
Q_PROPERTY(quint32 diskSpace READ diskSpace CONSTANT) Q_PROPERTY(quint32 diskSpace READ diskSpace CONSTANT)
...@@ -89,6 +89,7 @@ public: ...@@ -89,6 +89,7 @@ public:
quint32 maxMemCache (); quint32 maxMemCache ();
quint32 maxDiskCache (); quint32 maxDiskCache ();
QString errorMessage () { return _errorMessage; } QString errorMessage () { return _errorMessage; }
bool fetchElevation () { return _fetchElevation; }
quint64 freeDiskSpace () { return _freeDiskSpace; } quint64 freeDiskSpace () { return _freeDiskSpace; }
quint64 diskSpace () { return _diskSpace; } quint64 diskSpace () { return _diskSpace; }
int selectedCount (); int selectedCount ();
...@@ -101,6 +102,7 @@ public: ...@@ -101,6 +102,7 @@ public:
void setImportReplace (bool replace) { _importReplace = replace; emit importReplaceChanged(); } void setImportReplace (bool replace) { _importReplace = replace; emit importReplaceChanged(); }
void setImportAction (ImportAction action) {_importAction = action; emit importActionChanged(); } void setImportAction (ImportAction action) {_importAction = action; emit importActionChanged(); }
void setErrorMessage (const QString& error) { _errorMessage = error; emit errorMessageChanged(); } void setErrorMessage (const QString& error) { _errorMessage = error; emit errorMessageChanged(); }
void setFetchElevation (bool fetchElevation) { _fetchElevation = fetchElevation; emit fetchElevationChanged(); }
// Override from QGCTool // Override from QGCTool
void setToolbox(QGCToolbox *toolbox); void setToolbox(QGCToolbox *toolbox);
...@@ -116,6 +118,7 @@ signals: ...@@ -116,6 +118,7 @@ signals:
void maxMemCacheChanged (); void maxMemCacheChanged ();
void maxDiskCacheChanged (); void maxDiskCacheChanged ();
void errorMessageChanged (); void errorMessageChanged ();
void fetchElevationChanged ();
void freeDiskSpaceChanged (); void freeDiskSpaceChanged ();
void selectedCountChanged (); void selectedCountChanged ();
void actionProgressChanged (); void actionProgressChanged ();
...@@ -150,11 +153,10 @@ private: ...@@ -150,11 +153,10 @@ private:
quint32 _diskSpace; quint32 _diskSpace;
QmlObjectListModel _tileSets; QmlObjectListModel _tileSets;
QString _errorMessage; QString _errorMessage;
bool _fetchElevation;
int _actionProgress; int _actionProgress;
ImportAction _importAction; ImportAction _importAction;
bool _importReplace; bool _importReplace;
ElevationProvider _elevationProvider;
}; };
#endif #endif
...@@ -8,6 +8,7 @@ ...@@ -8,6 +8,7 @@
****************************************************************************/ ****************************************************************************/
#include "Terrain.h" #include "Terrain.h"
#include "QGCMapEngine.h"
#include <QUrl> #include <QUrl>
#include <QUrlQuery> #include <QUrlQuery>
...@@ -112,15 +113,15 @@ bool ElevationProvider::cacheTerrainTiles(const QGeoCoordinate& southWest, const ...@@ -112,15 +113,15 @@ bool ElevationProvider::cacheTerrainTiles(const QGeoCoordinate& southWest, const
// Correct corners of the tile to fixed grid // Correct corners of the tile to fixed grid
QGeoCoordinate southWestCorrected; QGeoCoordinate southWestCorrected;
southWestCorrected.setLatitude(floor(southWest.latitude()/TerrainTile::srtm1TileSize)*TerrainTile::srtm1TileSize); southWestCorrected.setLatitude(floor(southWest.latitude()/QGCMapEngine::srtm1TileSize)*QGCMapEngine::srtm1TileSize);
southWestCorrected.setLongitude(floor(southWest.longitude()/TerrainTile::srtm1TileSize)*TerrainTile::srtm1TileSize); southWestCorrected.setLongitude(floor(southWest.longitude()/QGCMapEngine::srtm1TileSize)*QGCMapEngine::srtm1TileSize);
QGeoCoordinate northEastCorrected; QGeoCoordinate northEastCorrected;
northEastCorrected.setLatitude(ceil(northEast.latitude()/TerrainTile::srtm1TileSize)*TerrainTile::srtm1TileSize); northEastCorrected.setLatitude(ceil(northEast.latitude()/QGCMapEngine::srtm1TileSize)*QGCMapEngine::srtm1TileSize);
northEastCorrected.setLongitude(ceil(northEast.longitude()/TerrainTile::srtm1TileSize)*TerrainTile::srtm1TileSize); northEastCorrected.setLongitude(ceil(northEast.longitude()/QGCMapEngine::srtm1TileSize)*QGCMapEngine::srtm1TileSize);
// Add all tiles to download queue // Add all tiles to download queue
for (double lat = southWestCorrected.latitude() + TerrainTile::srtm1TileSize / 2.0; lat < northEastCorrected.latitude(); lat += TerrainTile::srtm1TileSize) { for (double lat = southWestCorrected.latitude() + QGCMapEngine::srtm1TileSize / 2.0; lat < northEastCorrected.latitude(); lat += QGCMapEngine::srtm1TileSize) {
for (double lon = southWestCorrected.longitude() + TerrainTile::srtm1TileSize / 2.0; lon < northEastCorrected.longitude(); lon += TerrainTile::srtm1TileSize) { for (double lon = southWestCorrected.longitude() + QGCMapEngine::srtm1TileSize / 2.0; lon < northEastCorrected.longitude(); lon += QGCMapEngine::srtm1TileSize) {
QString uniqueTileId = _uniqueTileId(QGeoCoordinate(lat, lon)); QString uniqueTileId = _uniqueTileId(QGeoCoordinate(lat, lon));
_tilesMutex.lock(); _tilesMutex.lock();
if (_downloadQueue.contains(uniqueTileId) || _tiles.contains(uniqueTileId)) { if (_downloadQueue.contains(uniqueTileId) || _tiles.contains(uniqueTileId)) {
...@@ -252,11 +253,11 @@ QString ElevationProvider::_uniqueTileId(const QGeoCoordinate& coordinate) ...@@ -252,11 +253,11 @@ QString ElevationProvider::_uniqueTileId(const QGeoCoordinate& coordinate)
{ {
// Compute corners of the tile // Compute corners of the tile
QGeoCoordinate southWest; QGeoCoordinate southWest;
southWest.setLatitude(floor(coordinate.latitude()/TerrainTile::srtm1TileSize)*TerrainTile::srtm1TileSize); southWest.setLatitude(floor(coordinate.latitude()/QGCMapEngine::srtm1TileSize)*QGCMapEngine::srtm1TileSize);
southWest.setLongitude(floor(coordinate.longitude()/TerrainTile::srtm1TileSize)*TerrainTile::srtm1TileSize); southWest.setLongitude(floor(coordinate.longitude()/QGCMapEngine::srtm1TileSize)*QGCMapEngine::srtm1TileSize);
QGeoCoordinate northEast; QGeoCoordinate northEast;
northEast.setLatitude(ceil(coordinate.latitude()/TerrainTile::srtm1TileSize)*TerrainTile::srtm1TileSize); northEast.setLatitude(floor(coordinate.latitude()/QGCMapEngine::srtm1TileSize + 1)*QGCMapEngine::srtm1TileSize);
northEast.setLongitude(ceil(coordinate.longitude()/TerrainTile::srtm1TileSize)*TerrainTile::srtm1TileSize); northEast.setLongitude(floor(coordinate.longitude()/QGCMapEngine::srtm1TileSize + 1)*QGCMapEngine::srtm1TileSize);
// Generate uniquely identifying string // Generate uniquely identifying string
QString ret = QString::number(southWest.latitude(), 'f', 6) + "_" + QString::number(southWest.longitude(), 'f', 6) + "_" + QString ret = QString::number(southWest.latitude(), 'f', 6) + "_" + QString::number(southWest.longitude(), 'f', 6) + "_" +
......
#include "TerrainTile.h" #include "TerrainTile.h"
#include "JsonHelper.h" #include "JsonHelper.h"
#include "QGCMapEngine.h"
#include <QJsonDocument> #include <QJsonDocument>
#include <QJsonObject> #include <QJsonObject>
...@@ -7,7 +8,6 @@ ...@@ -7,7 +8,6 @@
QGC_LOGGING_CATEGORY(TerrainTileLog, "TerrainTileLog") QGC_LOGGING_CATEGORY(TerrainTileLog, "TerrainTileLog")
const double TerrainTile::srtm1TileSize = 0.025;
const char* TerrainTile::_jsonStatusKey = "status"; const char* TerrainTile::_jsonStatusKey = "status";
const char* TerrainTile::_jsonDataKey = "data"; const char* TerrainTile::_jsonDataKey = "data";
const char* TerrainTile::_jsonBoundsKey = "bounds"; const char* TerrainTile::_jsonBoundsKey = "bounds";
...@@ -141,8 +141,8 @@ float TerrainTile::elevation(const QGeoCoordinate& coordinate) const ...@@ -141,8 +141,8 @@ float TerrainTile::elevation(const QGeoCoordinate& coordinate) const
if (_isValid) { if (_isValid) {
qCDebug(TerrainTileLog) << "elevation: " << coordinate << " , in sw " << _southWest << " , ne " << _northEast; qCDebug(TerrainTileLog) << "elevation: " << coordinate << " , in sw " << _southWest << " , ne " << _northEast;
// Get the index at resolution of 1 arc second // Get the index at resolution of 1 arc second
int indexLat = round((coordinate.latitude() - _southWest.latitude()) * (gridSize - 1) / srtm1TileSize); int indexLat = round((coordinate.latitude() - _southWest.latitude()) * (gridSize - 1) / QGCMapEngine::srtm1TileSize);
int indexLon = round((coordinate.longitude() - _southWest.longitude()) * (gridSize - 1) / srtm1TileSize); int indexLon = round((coordinate.longitude() - _southWest.longitude()) * (gridSize - 1) / QGCMapEngine::srtm1TileSize);
qCDebug(TerrainTileLog) << "indexLat:indexLon" << indexLat << indexLon; // TODO (birchera): Move this down to the next debug output, once this is all properly working. qCDebug(TerrainTileLog) << "indexLat:indexLon" << indexLat << indexLon; // TODO (birchera): Move this down to the next debug output, once this is all properly working.
Q_ASSERT(indexLat >= 0); Q_ASSERT(indexLat >= 0);
Q_ASSERT(indexLat < gridSize); Q_ASSERT(indexLat < gridSize);
......
...@@ -76,9 +76,6 @@ public: ...@@ -76,9 +76,6 @@ public:
/// tile grid size in lat and lon /// tile grid size in lat and lon
static const int gridSize = TERRAIN_TILE_SIZE; static const int gridSize = TERRAIN_TILE_SIZE;
/// size of a tile in degree
static const double srtm1TileSize;
private: private:
QGeoCoordinate _southWest; /// South west corner of the tile QGeoCoordinate _southWest; /// South west corner of the tile
QGeoCoordinate _northEast; /// North east corner of the tile QGeoCoordinate _northEast; /// North east corner of the tile
......
Markdown is supported
0% or
You are about to add 0 people to the discussion. Proceed with caution.
Finish editing this message first!
Please register or to comment