Unverified Commit 1d0a8d8e authored by Don Gagne's avatar Don Gagne Committed by GitHub

Merge pull request #5842 from wingtra/feature/offlineElevationData

Elevation data for offline use
parents 62a35531 9b71c8fe
...@@ -587,6 +587,7 @@ HEADERS += \ ...@@ -587,6 +587,7 @@ HEADERS += \
src/Settings/UnitsSettings.h \ src/Settings/UnitsSettings.h \
src/Settings/VideoSettings.h \ src/Settings/VideoSettings.h \
src/Terrain/TerrainQuery.h \ src/Terrain/TerrainQuery.h \
src/TerrainTile.h \
src/Vehicle/MAVLinkLogManager.h \ src/Vehicle/MAVLinkLogManager.h \
src/VehicleSetup/JoystickConfigController.h \ src/VehicleSetup/JoystickConfigController.h \
src/comm/LinkConfiguration.h \ src/comm/LinkConfiguration.h \
...@@ -779,6 +780,7 @@ SOURCES += \ ...@@ -779,6 +780,7 @@ SOURCES += \
src/Settings/UnitsSettings.cc \ src/Settings/UnitsSettings.cc \
src/Settings/VideoSettings.cc \ src/Settings/VideoSettings.cc \
src/Terrain/TerrainQuery.cc \ src/Terrain/TerrainQuery.cc \
src/TerrainTile.cc\
src/Vehicle/MAVLinkLogManager.cc \ src/Vehicle/MAVLinkLogManager.cc \
src/VehicleSetup/JoystickConfigController.cc \ src/VehicleSetup/JoystickConfigController.cc \
src/comm/LinkConfiguration.cc \ src/comm/LinkConfiguration.cc \
......
...@@ -92,6 +92,12 @@ stQGeoTileCacheQGCMapTypes kEsriTypes[] = { ...@@ -92,6 +92,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";
...@@ -106,6 +112,9 @@ getQGCMapEngine() ...@@ -106,6 +112,9 @@ getQGCMapEngine()
return kMapEngine; return kMapEngine;
} }
//-----------------------------------------------------------------------------
const double QGCMapEngine::srtm1TileSize = 0.01;
//----------------------------------------------------------------------------- //-----------------------------------------------------------------------------
void void
destroyMapEngine() destroyMapEngine()
...@@ -297,10 +306,17 @@ QGCMapEngine::getTileCount(int zoom, double topleftLon, double topleftLat, doubl ...@@ -297,10 +306,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;
if (mapType != UrlFactory::AirmapElevation) {
set.tileX0 = long2tileX(topleftLon, zoom); set.tileX0 = long2tileX(topleftLon, zoom);
set.tileY0 = lat2tileY(topleftLat, zoom); set.tileY0 = lat2tileY(topleftLat, zoom);
set.tileX1 = long2tileX(bottomRightLon, zoom); set.tileX1 = long2tileX(bottomRightLon, zoom);
set.tileY1 = lat2tileY(bottomRightLat, 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;
...@@ -320,6 +336,22 @@ QGCMapEngine::lat2tileY(double lat, int z) ...@@ -320,6 +336,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)
...@@ -337,6 +369,10 @@ QGCMapEngine::getTypeFromName(const QString& name) ...@@ -337,6 +369,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;
} }
...@@ -471,6 +507,7 @@ QGCMapEngine::concurrentDownloads(UrlFactory::MapType type) ...@@ -471,6 +507,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 ();
......
...@@ -19,6 +19,7 @@ ...@@ -19,6 +19,7 @@
#include "QGCMapEngine.h" #include "QGCMapEngine.h"
#include "QGCMapTileSet.h" #include "QGCMapTileSet.h"
#include "QGCMapEngineManager.h" #include "QGCMapEngineManager.h"
#include "TerrainTile.h"
#include <QSettings> #include <QSettings>
#include <math.h> #include <math.h>
...@@ -282,6 +283,9 @@ QGCCachedTileSet::_networkReplyFinished() ...@@ -282,6 +283,9 @@ QGCCachedTileSet::_networkReplyFinished()
qCDebug(QGCCachedTileSetLog) << "Tile fetched" << hash; qCDebug(QGCCachedTileSetLog) << "Tile fetched" << hash;
QByteArray image = reply->readAll(); QByteArray image = reply->readAll();
UrlFactory::MapType type = getQGCMapEngine()->hashToType(hash); UrlFactory::MapType type = getQGCMapEngine()->hashToType(hash);
if (type == UrlFactory::MapType::AirmapElevation) {
image = TerrainTile::serialize(image);
}
QString format = getQGCMapEngine()->urlFactory()->getImageFormat(type, image); QString format = getQGCMapEngine()->urlFactory()->getImageFormat(type, image);
if(!format.isEmpty()) { if(!format.isEmpty()) {
//-- Cache tile //-- Cache tile
......
...@@ -122,6 +122,9 @@ UrlFactory::getImageFormat(MapType type, const QByteArray& image) ...@@ -122,6 +122,9 @@ UrlFactory::getImageFormat(MapType type, const QByteArray& image)
case BingHybrid: case BingHybrid:
format = "jpg"; format = "jpg";
break; break;
case AirmapElevation:
format = "bin";
break;
default: default:
qWarning("UrlFactory::getImageFormat() Unknown map id %d", type); qWarning("UrlFactory::getImageFormat() Unknown map id %d", type);
break; break;
...@@ -183,6 +186,10 @@ UrlFactory::getTileURL(MapType type, int x, int y, int zoom, QNetworkAccessManag ...@@ -183,6 +186,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;
} }
...@@ -403,6 +410,14 @@ UrlFactory::_getURL(MapType type, int x, int y, int zoom, QNetworkAccessManager* ...@@ -403,6 +410,14 @@ UrlFactory::_getURL(MapType type, int x, int y, int zoom, QNetworkAccessManager*
} }
} }
break; break;
case AirmapElevation:
{
return QString("https://api.airmap.com/elevation/v1/ele/carpet?points=%1,%2,%3,%4").arg(static_cast<double>(y)*QGCMapEngine::srtm1TileSize - 90.0).arg(
static_cast<double>(x)*QGCMapEngine::srtm1TileSize - 180.0).arg(
static_cast<double>(y + 1)*QGCMapEngine::srtm1TileSize - 90.0).arg(
static_cast<double>(x + 1)*QGCMapEngine::srtm1TileSize - 180.0);
}
break;
default: default:
qWarning("Unknown map id %d\n", type); qWarning("Unknown map id %d\n", type);
...@@ -545,6 +560,7 @@ UrlFactory::_tryCorrectGoogleVersions(QNetworkAccessManager* networkManager) ...@@ -545,6 +560,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 2786
//----------------------------------------------------------------------------- //-----------------------------------------------------------------------------
quint32 quint32
...@@ -568,6 +584,8 @@ UrlFactory::averageSizeForType(MapType type) ...@@ -568,6 +584,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:
......
...@@ -73,7 +73,9 @@ public: ...@@ -73,7 +73,9 @@ public:
EsriWorldStreet = 7000, EsriWorldStreet = 7000,
EsriWorldSatellite = 7001, EsriWorldSatellite = 7001,
EsriTerrain = 7002 EsriTerrain = 7002,
AirmapElevation = 8000
}; };
UrlFactory (); UrlFactory ();
......
...@@ -51,6 +51,7 @@ ...@@ -51,6 +51,7 @@
#include <QtLocation/private/qgeotilespec_p.h> #include <QtLocation/private/qgeotilespec_p.h>
#include <QtNetwork/QNetworkAccessManager> #include <QtNetwork/QNetworkAccessManager>
#include <QFile> #include <QFile>
#include "TerrainTile.h"
int QGeoTiledMapReplyQGC::_requestCount = 0; int QGeoTiledMapReplyQGC::_requestCount = 0;
...@@ -104,6 +105,7 @@ QGeoTiledMapReplyQGC::abort() ...@@ -104,6 +105,7 @@ QGeoTiledMapReplyQGC::abort()
_timer.stop(); _timer.stop();
if (_reply) if (_reply)
_reply->abort(); _reply->abort();
emit aborted();
} }
//----------------------------------------------------------------------------- //-----------------------------------------------------------------------------
...@@ -112,14 +114,27 @@ QGeoTiledMapReplyQGC::networkReplyFinished() ...@@ -112,14 +114,27 @@ QGeoTiledMapReplyQGC::networkReplyFinished()
{ {
_timer.stop(); _timer.stop();
if (!_reply) { if (!_reply) {
emit aborted();
return; return;
} }
if (_reply->error() != QNetworkReply::NoError) { if (_reply->error() != QNetworkReply::NoError) {
emit aborted();
return; return;
} }
QByteArray a = _reply->readAll(); QByteArray a = _reply->readAll();
setMapImageData(a);
QString format = getQGCMapEngine()->urlFactory()->getImageFormat((UrlFactory::MapType)tileSpec().mapId(), a); QString format = getQGCMapEngine()->urlFactory()->getImageFormat((UrlFactory::MapType)tileSpec().mapId(), a);
// convert "a" to binary in case we have elevation data
if ((UrlFactory::MapType)tileSpec().mapId() == UrlFactory::MapType::AirmapElevation) {
a = TerrainTile::serialize(a);
if (a.isEmpty()) {
emit aborted();
return;
}
}
setMapImageData(a);
if(!format.isEmpty()) { if(!format.isEmpty()) {
setMapImageFormat(format); setMapImageFormat(format);
getQGCMapEngine()->cacheTile((UrlFactory::MapType)tileSpec().mapId(), tileSpec().x(), tileSpec().y(), tileSpec().zoom(), a, format); getQGCMapEngine()->cacheTile((UrlFactory::MapType)tileSpec().mapId(), tileSpec().x(), tileSpec().y(), tileSpec().zoom(), a, format);
...@@ -195,4 +210,5 @@ QGeoTiledMapReplyQGC::timeout() ...@@ -195,4 +210,5 @@ QGeoTiledMapReplyQGC::timeout()
if(_reply) { if(_reply) {
_reply->abort(); _reply->abort();
} }
emit aborted();
} }
...@@ -433,7 +433,7 @@ QGCView { ...@@ -433,7 +433,7 @@ QGCView {
Row { Row {
spacing: ScreenTools.defaultFontPixelWidth spacing: ScreenTools.defaultFontPixelWidth
anchors.horizontalCenter: parent.horizontalCenter anchors.horizontalCenter: parent.horizontalCenter
visible: !_defaultSet visible: !_defaultSet && mapType !== "Airmap Elevation Data"
QGCLabel { text: qsTr("Zoom Levels:"); width: infoView._labelWidth; } QGCLabel { text: qsTr("Zoom Levels:"); width: infoView._labelWidth; }
QGCLabel { text: offlineMapView._currentSelection ? (offlineMapView._currentSelection.minZoom + " - " + offlineMapView._currentSelection.maxZoom) : ""; horizontalAlignment: Text.AlignRight; width: infoView._valueWidth; } QGCLabel { text: offlineMapView._currentSelection ? (offlineMapView._currentSelection.minZoom + " - " + offlineMapView._currentSelection.maxZoom) : ""; horizontalAlignment: Text.AlignRight; width: infoView._valueWidth; }
} }
...@@ -730,6 +730,16 @@ QGCView { ...@@ -730,6 +730,16 @@ QGCView {
} }
} }
} }
QGCCheckBox {
anchors.left: parent.left
anchors.right: parent.right
text: qsTr("Fetch elevation data")
checked: QGroundControl.mapEngineManager.fetchElevation
onClicked: {
QGroundControl.mapEngineManager.fetchElevation = checked
handleChanges()
}
}
} }
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)
...@@ -82,6 +83,10 @@ QGCMapEngineManager::updateForCurrentView(double lon0, double lat0, double lon1, ...@@ -82,6 +83,10 @@ QGCMapEngineManager::updateForCurrentView(double lon0, double lat0, double lon1,
QGCTileSet set = QGCMapEngine::getTileCount(z, lon0, lat0, lon1, lat1, mapType); QGCTileSet set = QGCMapEngine::getTileCount(z, lon0, lat0, lon1, lat1, mapType);
_totalSet += set; _totalSet += set;
} }
if (_fetchElevation) {
QGCTileSet set = QGCMapEngine::getTileCount(1, lon0, lat0, lon1, lat1, UrlFactory::AirmapElevation);
_totalSet += set;
}
emit tileX0Changed(); emit tileX0Changed();
emit tileX1Changed(); emit tileX1Changed();
emit tileY0Changed(); emit tileY0Changed();
...@@ -157,6 +162,26 @@ QGCMapEngineManager::startDownload(const QString& name, const QString& mapType) ...@@ -157,6 +162,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";
} }
if (mapType != "Airmap Elevation Data" && _fetchElevation) {
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";
}
} }
//----------------------------------------------------------------------------- //-----------------------------------------------------------------------------
......
...@@ -50,6 +50,7 @@ public: ...@@ -50,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)
...@@ -88,6 +89,7 @@ public: ...@@ -88,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 ();
...@@ -100,6 +102,7 @@ public: ...@@ -100,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);
...@@ -115,6 +118,7 @@ signals: ...@@ -115,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 ();
...@@ -149,6 +153,7 @@ private: ...@@ -149,6 +153,7 @@ 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;
......
...@@ -8,6 +8,8 @@ ...@@ -8,6 +8,8 @@
****************************************************************************/ ****************************************************************************/
#include "TerrainQuery.h" #include "TerrainQuery.h"
#include "QGCMapEngine.h"
#include "QGeoMapReplyQGC.h"
#include <QUrl> #include <QUrl>
#include <QUrlQuery> #include <QUrlQuery>
...@@ -18,10 +20,13 @@ ...@@ -18,10 +20,13 @@
#include <QJsonObject> #include <QJsonObject>
#include <QJsonArray> #include <QJsonArray>
#include <QTimer> #include <QTimer>
#include <QtLocation/private/qgeotilespec_p.h>
#include <cmath>
QGC_LOGGING_CATEGORY(TerrainQueryLog, "TerrainQueryLog") QGC_LOGGING_CATEGORY(TerrainQueryLog, "TerrainQueryLog")
Q_GLOBAL_STATIC(TerrainAtCoordinateBatchManager, _TerrainAtCoordinateBatchManager) Q_GLOBAL_STATIC(TerrainAtCoordinateBatchManager, _TerrainAtCoordinateBatchManager)
Q_GLOBAL_STATIC(TerrainTileManager, _terrainTileManager)
TerrainAirMapQuery::TerrainAirMapQuery(QObject* parent) TerrainAirMapQuery::TerrainAirMapQuery(QObject* parent)
: TerrainQueryInterface(parent) : TerrainQueryInterface(parent)
...@@ -216,6 +221,220 @@ void TerrainAirMapQuery::_parseCarpetData(const QJsonValue& carpetJson) ...@@ -216,6 +221,220 @@ void TerrainAirMapQuery::_parseCarpetData(const QJsonValue& carpetJson)
emit carpetHeights(true /*success*/, minHeight, maxHeight, carpet); emit carpetHeights(true /*success*/, minHeight, maxHeight, carpet);
} }
TerrainOfflineAirMapQuery::TerrainOfflineAirMapQuery(QObject* parent)
: TerrainQueryInterface(parent)
{
}
void TerrainOfflineAirMapQuery::requestCoordinateHeights(const QList<QGeoCoordinate>& coordinates)
{
if (coordinates.length() == 0) {
return;
}
_terrainTileManager->addCoordinateQuery(this, coordinates);
}
void TerrainOfflineAirMapQuery::requestPathHeights(const QGeoCoordinate& fromCoord, const QGeoCoordinate& toCoord)
{
_terrainTileManager->addPathQuery(this, fromCoord, toCoord);
}
void TerrainOfflineAirMapQuery::requestCarpetHeights(const QGeoCoordinate& swCoord, const QGeoCoordinate& neCoord, bool statsOnly)
{
// TODO
Q_UNUSED(swCoord);
Q_UNUSED(neCoord);
Q_UNUSED(statsOnly);
qWarning() << "Carpet queries are currently not supported from offline air map data";
}
void TerrainOfflineAirMapQuery::_signalCoordinateHeights(bool success, QList<double> heights)
{
emit coordinateHeights(success, heights);
}
void TerrainOfflineAirMapQuery::_signalPathHeights(bool success, double latStep, double lonStep, const QList<double>& heights)
{
emit pathHeights(success, latStep, lonStep, heights);
}
void TerrainOfflineAirMapQuery::_signalCarpetHeights(bool success, double minHeight, double maxHeight, const QList<QList<double>>& carpet)
{
emit carpetHeights(success, minHeight, maxHeight, carpet);
}
TerrainTileManager::TerrainTileManager(void)
{
}
void TerrainTileManager::addCoordinateQuery(TerrainOfflineAirMapQuery* terrainQueryInterface, const QList<QGeoCoordinate>& coordinates)
{
if (coordinates.length() > 0) {
QList<double> altitudes;
if (!_getAltitudesForCoordinates(coordinates, altitudes)) {
QueuedRequestInfo_t queuedRequestInfo = { terrainQueryInterface, QueryMode::QueryModeCoordinates, coordinates };
_requestQueue.append(queuedRequestInfo);
return;
}
qCDebug(TerrainQueryLog) << "All altitudes taken from cached data";
terrainQueryInterface->_signalCoordinateHeights(coordinates.count() == altitudes.count(), altitudes);
}
}
void TerrainTileManager::addPathQuery(TerrainOfflineAirMapQuery* terrainQueryInterface, const QGeoCoordinate &startPoint, const QGeoCoordinate &endPoint)
{
QList<QGeoCoordinate> coordinates;
double lat = startPoint.latitude();
double lon = startPoint.longitude();
double latDiff = endPoint.latitude() - lat;
double lonDiff = endPoint.longitude() - lon;
double steps = ceil(endPoint.distanceTo(startPoint) / TerrainTile::terrainAltitudeSpacing);
for (double i = 0.0; i <= steps; i = i + 1) {
coordinates.append(QGeoCoordinate(lat + latDiff * i / steps, lon + lonDiff * i / steps));
}
QList<double> altitudes;
if (!_getAltitudesForCoordinates(coordinates, altitudes)) {
QueuedRequestInfo_t queuedRequestInfo = { terrainQueryInterface, QueryMode::QueryModePath, coordinates };
_requestQueue.append(queuedRequestInfo);
return;
}
qCDebug(TerrainQueryLog) << "All altitudes taken from cached data";
double stepLat = 0;
double stepLon = 0;
if (coordinates.count() > 1) {
stepLat = coordinates[1].latitude() - coordinates[0].latitude();
stepLon = coordinates[1].longitude() - coordinates[0].longitude();
}
terrainQueryInterface->_signalPathHeights(coordinates.count() == altitudes.count(), stepLat, stepLon, altitudes);
}
bool TerrainTileManager::_getAltitudesForCoordinates(const QList<QGeoCoordinate>& coordinates, QList<double>& altitudes)
{
foreach (const QGeoCoordinate& coordinate, coordinates) {
QString tileHash = _getTileHash(coordinate);
_tilesMutex.lock();
if (!_tiles.contains(tileHash)) {
qCDebug(TerrainQueryLog) << "Need to download tile " << tileHash;
// Schedule the fetch task
if (_state != State::Downloading) {
QNetworkRequest request = getQGCMapEngine()->urlFactory()->getTileURL(UrlFactory::AirmapElevation, QGCMapEngine::long2elevationTileX(coordinate.longitude(), 1), QGCMapEngine::lat2elevationTileY(coordinate.latitude(), 1), 1, &_networkManager);
QGeoTileSpec spec;
spec.setX(QGCMapEngine::long2elevationTileX(coordinate.longitude(), 1));
spec.setY(QGCMapEngine::lat2elevationTileY(coordinate.latitude(), 1));
spec.setZoom(1);
spec.setMapId(UrlFactory::AirmapElevation);
QGeoTiledMapReplyQGC* reply = new QGeoTiledMapReplyQGC(&_networkManager, request, spec);
connect(reply, &QGeoTiledMapReplyQGC::finished, this, &TerrainTileManager::_fetchedTile);
connect(reply, &QGeoTiledMapReplyQGC::aborted, this, &TerrainTileManager::_fetchedTile);
_state = State::Downloading;
}
_tilesMutex.unlock();
return false;
} else {
if (_tiles[tileHash].isIn(coordinate)) {
altitudes.push_back(_tiles[tileHash].elevation(coordinate));
} else {
qCDebug(TerrainQueryLog) << "Error: coordinate not in tile region";
altitudes.push_back(-1.0);
}
}
_tilesMutex.unlock();
}
return true;
}
void TerrainTileManager::_tileFailed(void)
{
QList<double> noAltitudes;
foreach (const QueuedRequestInfo_t& requestInfo, _requestQueue) {
if (requestInfo.queryMode == QueryMode::QueryModeCoordinates) {
requestInfo.terrainQueryInterface->_signalCoordinateHeights(false, noAltitudes);
}
}
_requestQueue.clear();
}
void TerrainTileManager::_fetchedTile()
{
QGeoTiledMapReplyQGC* reply = qobject_cast<QGeoTiledMapReplyQGC*>(QObject::sender());
_state = State::Idle;
if (!reply) {
qCDebug(TerrainQueryLog) << "Elevation tile fetched but invalid reply data type.";
return;
}
// remove from download queue
QGeoTileSpec spec = reply->tileSpec();
QString hash = QGCMapEngine::getTileHash(UrlFactory::AirmapElevation, spec.x(), spec.y(), spec.zoom());
// handle potential errors
if (reply->error() != QGeoTiledMapReply::NoError) {
if (reply->error() == QGeoTiledMapReply::CommunicationError) {
qCDebug(TerrainQueryLog) << "Elevation tile fetching returned communication error. " << reply->errorString();
} else {
qCDebug(TerrainQueryLog) << "Elevation tile fetching returned error. " << reply->errorString();
}
_tileFailed();
reply->deleteLater();
return;
}
if (!reply->isFinished()) {
qCDebug(TerrainQueryLog) << "Error in fetching elevation tile. Not finished. " << reply->errorString();
_tileFailed();
reply->deleteLater();
return;
}
// parse received data and insert into hash table
QByteArray responseBytes = reply->mapImageData();
qWarning() << "Received some bytes of terrain data: " << responseBytes.size();
TerrainTile* terrainTile = new TerrainTile(responseBytes);
if (terrainTile->isValid()) {
_tilesMutex.lock();
if (!_tiles.contains(hash)) {
_tiles.insert(hash, *terrainTile);
} else {
delete terrainTile;
}
_tilesMutex.unlock();
} else {
qCDebug(TerrainQueryLog) << "Received invalid tile";
}
reply->deleteLater();
// now try to query the data again
for (int i = _requestQueue.count() - 1; i >= 0; i--) {
QList<double> altitudes;
if (_getAltitudesForCoordinates(_requestQueue[i].coordinates, altitudes)) {
if (_requestQueue[i].queryMode == QueryMode::QueryModeCoordinates) {
_requestQueue[i].terrainQueryInterface->_signalCoordinateHeights(_requestQueue[i].coordinates.count() == altitudes.count(), altitudes);
}
_requestQueue.removeAt(i);
}
}
}
QString TerrainTileManager::_getTileHash(const QGeoCoordinate& coordinate)
{
QString ret = QGCMapEngine::getTileHash(UrlFactory::AirmapElevation, QGCMapEngine::long2elevationTileX(coordinate.longitude(), 1), QGCMapEngine::lat2elevationTileY(coordinate.latitude(), 1), 1);
qCDebug(TerrainQueryLog) << "Computing unique tile hash for " << coordinate << ret;
return ret;
}
TerrainAtCoordinateBatchManager::TerrainAtCoordinateBatchManager(void) TerrainAtCoordinateBatchManager::TerrainAtCoordinateBatchManager(void)
{ {
_batchTimer.setSingleShot(true); _batchTimer.setSingleShot(true);
...@@ -267,8 +486,8 @@ void TerrainAtCoordinateBatchManager::_sendNextBatch(void) ...@@ -267,8 +486,8 @@ void TerrainAtCoordinateBatchManager::_sendNextBatch(void)
qCDebug(TerrainQueryLog) << "Built request: coordinate count" << coords.count(); qCDebug(TerrainQueryLog) << "Built request: coordinate count" << coords.count();
_requestQueue = _requestQueue.mid(requestQueueAdded); _requestQueue = _requestQueue.mid(requestQueueAdded);
_terrainQuery.requestCoordinateHeights(coords);
_state = State::Downloading; _state = State::Downloading;
_terrainQuery.requestCoordinateHeights(coords);
} }
void TerrainAtCoordinateBatchManager::_batchFailed(void) void TerrainAtCoordinateBatchManager::_batchFailed(void)
......
...@@ -9,6 +9,8 @@ ...@@ -9,6 +9,8 @@
#pragma once #pragma once
#include "TerrainTile.h"
#include "QGCMapEngineData.h"
#include "QGCLoggingCategory.h" #include "QGCLoggingCategory.h"
#include <QObject> #include <QObject>
...@@ -16,6 +18,7 @@ ...@@ -16,6 +18,7 @@
#include <QNetworkAccessManager> #include <QNetworkAccessManager>
#include <QNetworkReply> #include <QNetworkReply>
#include <QTimer> #include <QTimer>
#include <QtLocation/private/qgeotiledmapreply_p.h>
Q_DECLARE_LOGGING_CATEGORY(TerrainQueryLog) Q_DECLARE_LOGGING_CATEGORY(TerrainQueryLog)
...@@ -84,6 +87,67 @@ private: ...@@ -84,6 +87,67 @@ private:
bool _carpetStatsOnly; bool _carpetStatsOnly;
}; };
/// AirMap offline cachable implementation of terrain queries
class TerrainOfflineAirMapQuery : public TerrainQueryInterface {
Q_OBJECT
public:
TerrainOfflineAirMapQuery(QObject* parent = NULL);
// Overrides from TerrainQueryInterface
void requestCoordinateHeights(const QList<QGeoCoordinate>& coordinates) final;
void requestPathHeights(const QGeoCoordinate& fromCoord, const QGeoCoordinate& toCoord) final;
void requestCarpetHeights(const QGeoCoordinate& swCoord, const QGeoCoordinate& neCoord, bool statsOnly) final;
// Internal methods
void _signalCoordinateHeights(bool success, QList<double> heights);
void _signalPathHeights(bool success, double latStep, double lonStep, const QList<double>& heights);
void _signalCarpetHeights(bool success, double minHeight, double maxHeight, const QList<QList<double>>& carpet);
};
/// Used internally by TerrainOfflineAirMapQuery to manage terrain tiles
class TerrainTileManager : public QObject {
Q_OBJECT
public:
TerrainTileManager(void);
void addCoordinateQuery (TerrainOfflineAirMapQuery* terrainQueryInterface, const QList<QGeoCoordinate>& coordinates);
void addPathQuery (TerrainOfflineAirMapQuery* terrainQueryInterface, const QGeoCoordinate& startPoint, const QGeoCoordinate& endPoint);
private slots:
void _fetchedTile (void); /// slot to handle fetched elevation tiles
private:
enum class State {
Idle,
Downloading,
};
enum QueryMode {
QueryModeCoordinates,
QueryModePath,
QueryModeCarpet
};
typedef struct {
TerrainOfflineAirMapQuery* terrainQueryInterface;
QueryMode queryMode;
QList<QGeoCoordinate> coordinates;
} QueuedRequestInfo_t;
void _tileFailed(void);
bool _getAltitudesForCoordinates(const QList<QGeoCoordinate>& coordinates, QList<double>& altitudes);
QString _getTileHash(const QGeoCoordinate& coordinate); /// Method to create a unique string for each tile
QList<QueuedRequestInfo_t> _requestQueue;
State _state = State::Idle;
QNetworkAccessManager _networkManager;
QMutex _tilesMutex;
QHash<QString, TerrainTile> _tiles;
};
/// Used internally by TerrainAtCoordinateQuery to batch coordinate requests together /// Used internally by TerrainAtCoordinateQuery to batch coordinate requests together
class TerrainAtCoordinateBatchManager : public QObject { class TerrainAtCoordinateBatchManager : public QObject {
Q_OBJECT Q_OBJECT
...@@ -124,7 +188,7 @@ private: ...@@ -124,7 +188,7 @@ private:
State _state = State::Idle; State _state = State::Idle;
const int _batchTimeout = 500; const int _batchTimeout = 500;
QTimer _batchTimer; QTimer _batchTimer;
TerrainAirMapQuery _terrainQuery; TerrainOfflineAirMapQuery _terrainQuery;
}; };
/// NOTE: TerrainAtCoordinateQuery is not thread safe. All instances/calls to ElevationProvider must be on main thread. /// NOTE: TerrainAtCoordinateQuery is not thread safe. All instances/calls to ElevationProvider must be on main thread.
...@@ -172,7 +236,7 @@ private slots: ...@@ -172,7 +236,7 @@ private slots:
void _pathHeights(bool success, double latStep, double lonStep, const QList<double>& heights); void _pathHeights(bool success, double latStep, double lonStep, const QList<double>& heights);
private: private:
TerrainAirMapQuery _terrainQuery; TerrainOfflineAirMapQuery _terrainQuery;
}; };
Q_DECLARE_METATYPE(TerrainPathQuery::PathHeightInfo_t) Q_DECLARE_METATYPE(TerrainPathQuery::PathHeightInfo_t)
......
#include "TerrainTile.h"
#include "JsonHelper.h"
#include "QGCMapEngine.h"
#include <QJsonDocument>
#include <QJsonObject>
#include <QJsonArray>
#include <QDataStream>
QGC_LOGGING_CATEGORY(TerrainTileLog, "TerrainTileLog")
const char* TerrainTile::_jsonStatusKey = "status";
const char* TerrainTile::_jsonDataKey = "data";
const char* TerrainTile::_jsonBoundsKey = "bounds";
const char* TerrainTile::_jsonSouthWestKey = "sw";
const char* TerrainTile::_jsonNorthEastKey = "ne";
const char* TerrainTile::_jsonStatsKey = "stats";
const char* TerrainTile::_jsonMaxElevationKey = "max";
const char* TerrainTile::_jsonMinElevationKey = "min";
const char* TerrainTile::_jsonAvgElevationKey = "avg";
const char* TerrainTile::_jsonCarpetKey = "carpet";
TerrainTile::TerrainTile()
: _minElevation(-1.0)
, _maxElevation(-1.0)
, _avgElevation(-1.0)
, _data(NULL)
, _gridSizeLat(-1)
, _gridSizeLon(-1)
, _isValid(false)
{
}
TerrainTile::~TerrainTile()
{
if (_data) {
for (int i = 0; i < _gridSizeLat; i++) {
delete _data[i];
}
delete _data;
_data = NULL;
}
}
TerrainTile::TerrainTile(QByteArray byteArray)
: _minElevation(-1.0)
, _maxElevation(-1.0)
, _avgElevation(-1.0)
, _data(NULL)
, _gridSizeLat(-1)
, _gridSizeLon(-1)
, _isValid(false)
{
QDataStream stream(byteArray);
float lat,lon;
stream >> lat
>> lon;
_southWest.setLatitude(lat);
_southWest.setLongitude(lon);
stream >> lat
>> lon;
_northEast.setLatitude(lat);
_northEast.setLongitude(lon);
stream >> _minElevation
>> _maxElevation
>> _avgElevation
>> _gridSizeLat
>> _gridSizeLon;
qCDebug(TerrainTileLog) << "Loading terrain tile: " << _southWest << " - " << _northEast;
qCDebug(TerrainTileLog) << "min:max:avg:sizeLat:sizeLon" << _minElevation << _maxElevation << _avgElevation << _gridSizeLat << _gridSizeLon;
for (int i = 0; i < _gridSizeLat; i++) {
if (i == 0) {
_data = new int16_t*[_gridSizeLat];
for (int k = 0; k < _gridSizeLat; k++) {
_data[k] = new int16_t[_gridSizeLon];
}
}
for (int j = 0; j < _gridSizeLon; j++) {
if (stream.atEnd()) {
qWarning() << "Terrain tile binary data does not contain all data";
return;
}
stream >> _data[i][j];
}
}
_isValid = true;
}
bool TerrainTile::isIn(const QGeoCoordinate& coordinate) const
{
if (!_isValid) {
qCDebug(TerrainTileLog) << "isIn requested, but tile not valid";
return false;
}
bool ret = coordinate.latitude() >= _southWest.latitude() && coordinate.longitude() >= _southWest.longitude() &&
coordinate.latitude() <= _northEast.latitude() && coordinate.longitude() <= _northEast.longitude();
qCDebug(TerrainTileLog) << "Checking isIn: " << coordinate << " , in sw " << _southWest << " , ne " << _northEast << ": " << ret;
return ret;
}
double TerrainTile::elevation(const QGeoCoordinate& coordinate) const
{
if (_isValid) {
qCDebug(TerrainTileLog) << "elevation: " << coordinate << " , in sw " << _southWest << " , ne " << _northEast;
// Get the index at resolution of 1 arc second
int indexLat = _latToDataIndex(coordinate.latitude());
int indexLon = _lonToDataIndex(coordinate.longitude());
qCDebug(TerrainTileLog) << "indexLat:indexLon" << indexLat << indexLon << "elevation" << _data[indexLat][indexLon];
return static_cast<double>(_data[indexLat][indexLon]);
} else {
qCDebug(TerrainTileLog) << "Asking for elevation, but no valid data.";
return -1.0;
}
}
QGeoCoordinate TerrainTile::centerCoordinate(void) const
{
return _southWest.atDistanceAndAzimuth(_southWest.distanceTo(_northEast) / 2.0, _southWest.azimuthTo(_northEast));
}
QByteArray TerrainTile::serialize(QByteArray input)
{
QJsonParseError parseError;
QJsonDocument document = QJsonDocument::fromJson(input, &parseError);
if (parseError.error != QJsonParseError::NoError) {
QByteArray emptyArray;
return emptyArray;
}
QByteArray byteArray;
QDataStream stream(&byteArray, QIODevice::WriteOnly);
if (!document.isObject()) {
qCDebug(TerrainTileLog) << "Terrain tile json doc is no object";
QByteArray emptyArray;
return emptyArray;
}
QJsonObject rootObject = document.object();
QString errorString;
QList<JsonHelper::KeyValidateInfo> rootVersionKeyInfoList = {
{ _jsonStatusKey, QJsonValue::String, true },
{ _jsonDataKey, QJsonValue::Object, true },
};
if (!JsonHelper::validateKeys(rootObject, rootVersionKeyInfoList, errorString)) {
qCDebug(TerrainTileLog) << "Error in reading json: " << errorString;
QByteArray emptyArray;
return emptyArray;
}
if (rootObject[_jsonStatusKey].toString() != "success") {
qCDebug(TerrainTileLog) << "Invalid terrain tile.";
QByteArray emptyArray;
return emptyArray;
}
const QJsonObject& dataObject = rootObject[_jsonDataKey].toObject();
QList<JsonHelper::KeyValidateInfo> dataVersionKeyInfoList = {
{ _jsonBoundsKey, QJsonValue::Object, true },
{ _jsonStatsKey, QJsonValue::Object, true },
{ _jsonCarpetKey, QJsonValue::Array, true },
};
if (!JsonHelper::validateKeys(dataObject, dataVersionKeyInfoList, errorString)) {
qCDebug(TerrainTileLog) << "Error in reading json: " << errorString;
QByteArray emptyArray;
return emptyArray;
}
// Bounds
const QJsonObject& boundsObject = dataObject[_jsonBoundsKey].toObject();
QList<JsonHelper::KeyValidateInfo> boundsVersionKeyInfoList = {
{ _jsonSouthWestKey, QJsonValue::Array, true },
{ _jsonNorthEastKey, QJsonValue::Array, true },
};
if (!JsonHelper::validateKeys(boundsObject, boundsVersionKeyInfoList, errorString)) {
qCDebug(TerrainTileLog) << "Error in reading json: " << errorString;
QByteArray emptyArray;
return emptyArray;
}
const QJsonArray& swArray = boundsObject[_jsonSouthWestKey].toArray();
const QJsonArray& neArray = boundsObject[_jsonNorthEastKey].toArray();
if (swArray.count() < 2 || neArray.count() < 2 ) {
qCDebug(TerrainTileLog) << "Incomplete bounding location";
QByteArray emptyArray;
return emptyArray;
}
stream << static_cast<float>(swArray[0].toDouble());
stream << static_cast<float>(swArray[1].toDouble());
stream << static_cast<float>(neArray[0].toDouble());
stream << static_cast<float>(neArray[1].toDouble());
// Stats
const QJsonObject& statsObject = dataObject[_jsonStatsKey].toObject();
QList<JsonHelper::KeyValidateInfo> statsVersionKeyInfoList = {
{ _jsonMinElevationKey, QJsonValue::Double, true },
{ _jsonMaxElevationKey, QJsonValue::Double, true },
{ _jsonAvgElevationKey, QJsonValue::Double, true },
};
if (!JsonHelper::validateKeys(statsObject, statsVersionKeyInfoList, errorString)) {
qCDebug(TerrainTileLog) << "Error in reading json: " << errorString;
QByteArray emptyArray;
return emptyArray;
}
stream << static_cast<int16_t>(statsObject[_jsonMinElevationKey].toInt());
stream << static_cast<int16_t>(statsObject[_jsonMaxElevationKey].toInt());
stream << static_cast<float>(statsObject[_jsonAvgElevationKey].toDouble());
// Carpet
const QJsonArray& carpetArray = dataObject[_jsonCarpetKey].toArray();
int gridSizeLat = carpetArray.count();
stream << static_cast<int16_t>(gridSizeLat);
int gridSizeLon = 0;
qCDebug(TerrainTileLog) << "Received tile has size in latitude direction: " << carpetArray.count();
for (int i = 0; i < gridSizeLat; i++) {
const QJsonArray& row = carpetArray[i].toArray();
if (i == 0) {
gridSizeLon = row.count();
stream << static_cast<int16_t>(gridSizeLon);
qCDebug(TerrainTileLog) << "Received tile has size in longitued direction: " << row.count();
}
if (row.count() < gridSizeLon) {
qCDebug(TerrainTileLog) << "Expected row array of " << gridSizeLon << ", instead got " << row.count();
QByteArray emptyArray;
return emptyArray;
}
for (int j = 0; j < gridSizeLon; j++) {
stream << static_cast<int16_t>(row[j].toDouble());
}
}
return byteArray;
}
int TerrainTile::_latToDataIndex(double latitude) const
{
if (isValid() && _southWest.isValid() && _northEast.isValid()) {
return qRound((latitude - _southWest.latitude()) / (_northEast.latitude() - _southWest.latitude()) * (_gridSizeLat - 1));
} else {
return -1;
}
}
int TerrainTile::_lonToDataIndex(double longitude) const
{
if (isValid() && _southWest.isValid() && _northEast.isValid()) {
return qRound((longitude - _southWest.longitude()) / (_northEast.longitude() - _southWest.longitude()) * (_gridSizeLon - 1));
} else {
return -1;
}
}
#ifndef TERRAINTILE_H
#define TERRAINTILE_H
#include "QGCLoggingCategory.h"
#include <QGeoCoordinate>
Q_DECLARE_LOGGING_CATEGORY(TerrainTileLog)
/**
* @brief The TerrainTile class
*
* Implements an interface for https://developers.airmap.com/v2.0/docs/elevation-api
*/
class TerrainTile
{
public:
TerrainTile();
~TerrainTile();
/**
* Constructor from json doc with elevation data (either from file or web)
*
* @param document
*/
TerrainTile(QJsonDocument document);
/**
* Constructor from serialized elevation data (either from file or web)
*
* @param document
*/
TerrainTile(QByteArray byteArray);
/**
* Check for whether a coordinate lies within this tile
*
* @param coordinate
* @return true if within
*/
bool isIn(const QGeoCoordinate& coordinate) const;
/**
* Check whether valid data is loaded
*
* @return true if data is valid
*/
bool isValid(void) const { return _isValid; }
/**
* Evaluates the elevation at the given coordinate
*
* @param coordinate
* @return elevation
*/
double elevation(const QGeoCoordinate& coordinate) const;
/**
* Accessor for the minimum elevation of the tile
*
* @return minimum elevation
*/
double minElevation(void) const { return _minElevation; }
/**
* Accessor for the maximum elevation of the tile
*
* @return maximum elevation
*/
double maxElevation(void) const { return _maxElevation; }
/**
* Accessor for the average elevation of the tile
*
* @return average elevation
*/
double avgElevation(void) const { return _avgElevation; }
/**
* Accessor for the center coordinate
*
* @return center coordinate
*/
QGeoCoordinate centerCoordinate(void) const;
/**
* Serialize data
*
* @return serialized data
*/
static QByteArray serialize(QByteArray input);
/// Approximate spacing of the elevation data measurement points
static constexpr double terrainAltitudeSpacing = 30.0;
private:
inline int _latToDataIndex(double latitude) const;
inline int _lonToDataIndex(double longitude) const;
QGeoCoordinate _southWest; /// South west corner of the tile
QGeoCoordinate _northEast; /// North east corner of the tile
int16_t _minElevation; /// Minimum elevation in tile
int16_t _maxElevation; /// Maximum elevation in tile
float _avgElevation; /// Average elevation of the tile
int16_t** _data; /// 2D elevation data array
int16_t _gridSizeLat; /// data grid size in latitude direction
int16_t _gridSizeLon; /// data grid size in longitude direction
bool _isValid; /// data loaded is valid
// Json keys
static const char* _jsonStatusKey;
static const char* _jsonDataKey;
static const char* _jsonBoundsKey;
static const char* _jsonSouthWestKey;
static const char* _jsonNorthEastKey;
static const char* _jsonStatsKey;
static const char* _jsonMaxElevationKey;
static const char* _jsonMinElevationKey;
static const char* _jsonAvgElevationKey;
static const char* _jsonCarpetKey;
};
#endif // TERRAINTILE_H
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