diff --git a/src/QtLocationPlugin/QGCMapTileSet.cpp b/src/QtLocationPlugin/QGCMapTileSet.cpp index 70e70f2e8cd2c0ea5ec6c9e260e775f0b594aa29..f2ac50f9e91642f8ec8c193ef837b32e96d0bd8e 100644 --- a/src/QtLocationPlugin/QGCMapTileSet.cpp +++ b/src/QtLocationPlugin/QGCMapTileSet.cpp @@ -19,6 +19,7 @@ #include "QGCMapEngine.h" #include "QGCMapTileSet.h" #include "QGCMapEngineManager.h" +#include "TerrainTile.h" #include #include @@ -282,6 +283,9 @@ QGCCachedTileSet::_networkReplyFinished() qCDebug(QGCCachedTileSetLog) << "Tile fetched" << hash; QByteArray image = reply->readAll(); UrlFactory::MapType type = getQGCMapEngine()->hashToType(hash); + if (type == UrlFactory::MapType::AirmapElevation) { + image = TerrainTile::serialize(image); + } QString format = getQGCMapEngine()->urlFactory()->getImageFormat(type, image); if(!format.isEmpty()) { //-- Cache tile diff --git a/src/QtLocationPlugin/QGCMapUrlEngine.cpp b/src/QtLocationPlugin/QGCMapUrlEngine.cpp index 6c2092050a7e32649ed4e86c236571681ba7a66f..ed57ec5a7b11b5440624953c84494efc8f0b8278 100644 --- a/src/QtLocationPlugin/QGCMapUrlEngine.cpp +++ b/src/QtLocationPlugin/QGCMapUrlEngine.cpp @@ -36,7 +36,6 @@ 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 gifSignature[] = {0x47, 0x49, 0x46, 0x38, 0x00}; -static const unsigned char jsonSignature[] = {0x7B, 0x22, 0x00}; // two characters '{"' //----------------------------------------------------------------------------- UrlFactory::UrlFactory() @@ -86,8 +85,6 @@ UrlFactory::getImageFormat(MapType type, const QByteArray& image) format = "jpg"; else if (image.startsWith(reinterpret_cast(gifSignature))) format = "gif"; - else if (image.startsWith(reinterpret_cast(jsonSignature))) - format = "json"; else { switch (type) { case GoogleMap: @@ -126,7 +123,7 @@ UrlFactory::getImageFormat(MapType type, const QByteArray& image) format = "jpg"; break; case AirmapElevation: - format = "json"; + format = "bin"; break; default: qWarning("UrlFactory::getImageFormat() Unknown map id %d", type); @@ -563,7 +560,7 @@ UrlFactory::_tryCorrectGoogleVersions(QNetworkAccessManager* networkManager) #define AVERAGE_MAPBOX_SAT_MAP 15739 #define AVERAGE_MAPBOX_STREET_MAP 5648 #define AVERAGE_TILE_SIZE 13652 -#define AVERAGE_AIRMAP_ELEV_SIZE 5360 +#define AVERAGE_AIRMAP_ELEV_SIZE 2786 //----------------------------------------------------------------------------- quint32 diff --git a/src/Terrain/TerrainQuery.cc b/src/Terrain/TerrainQuery.cc index 80a16e7d4143ffc7a430a59a34cd5721402ce168..19407984dbcac18e2595da6a9e56bb051cf11569 100644 --- a/src/Terrain/TerrainQuery.cc +++ b/src/Terrain/TerrainQuery.cc @@ -398,6 +398,8 @@ void TerrainTileManager::_fetchedTile() // 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(); diff --git a/src/Terrain/TerrainQuery.h b/src/Terrain/TerrainQuery.h index 96d98e24c40891a66c59c627f286751f908ad9bd..bc5ee91a947738b59475251132f1c14c526a120d 100644 --- a/src/Terrain/TerrainQuery.h +++ b/src/Terrain/TerrainQuery.h @@ -87,7 +87,7 @@ private: bool _carpetStatsOnly; }; -/// AirMap online implementation of terrain queries +/// AirMap offline cachable implementation of terrain queries class TerrainOfflineAirMapQuery : public TerrainQueryInterface { Q_OBJECT @@ -99,12 +99,10 @@ public: void requestPathHeights(const QGeoCoordinate& fromCoord, const QGeoCoordinate& toCoord) final; void requestCarpetHeights(const QGeoCoordinate& swCoord, const QGeoCoordinate& neCoord, bool statsOnly) final; - // Internal method + // Internal methods void _signalCoordinateHeights(bool success, QList heights); void _signalPathHeights(bool success, double latStep, double lonStep, const QList& heights); void _signalCarpetHeights(bool success, double minHeight, double maxHeight, const QList>& carpet); - - bool _carpetStatsOnly; }; /// Used internally by TerrainOfflineAirMapQuery to manage terrain tiles diff --git a/src/TerrainTile.cc b/src/TerrainTile.cc index 8e6a6d511c2d468810b09db531896a1f4c5c4a61..e95bf892a6a1b2e7cb7acbb9a1c2f4cd6b5e4769 100644 --- a/src/TerrainTile.cc +++ b/src/TerrainTile.cc @@ -55,31 +55,38 @@ TerrainTile::TerrainTile(QByteArray byteArray) { QDataStream stream(byteArray); - double lat,lon; + float lat,lon; stream >> lat - >> lon; + >> lon; _southWest.setLatitude(lat); _southWest.setLongitude(lon); stream >> lat - >> lon; + >> lon; _northEast.setLatitude(lat); _northEast.setLongitude(lon); stream >> _minElevation - >> _maxElevation - >> _avgElevation - >> _gridSizeLat - >> _gridSizeLon; + >> _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 double*[_gridSizeLat]; + _data = new int16_t*[_gridSizeLat]; for (int k = 0; k < _gridSizeLat; k++) { - _data[k] = new double[_gridSizeLon]; + _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]; } } @@ -108,7 +115,7 @@ double TerrainTile::elevation(const QGeoCoordinate& coordinate) const int indexLat = _latToDataIndex(coordinate.latitude()); int indexLon = _lonToDataIndex(coordinate.longitude()); qCDebug(TerrainTileLog) << "indexLat:indexLon" << indexLat << indexLon << "elevation" << _data[indexLat][indexLon]; - return _data[indexLat][indexLon]; + return static_cast(_data[indexLat][indexLon]); } else { qCDebug(TerrainTileLog) << "Asking for elevation, but no valid data."; return -1.0; @@ -141,7 +148,7 @@ QByteArray TerrainTile::serialize(QByteArray input) QString errorString; QList rootVersionKeyInfoList = { { _jsonStatusKey, QJsonValue::String, true }, - { _jsonDataKey, QJsonValue::Object, true }, + { _jsonDataKey, QJsonValue::Object, true }, }; if (!JsonHelper::validateKeys(rootObject, rootVersionKeyInfoList, errorString)) { qCDebug(TerrainTileLog) << "Error in reading json: " << errorString; @@ -157,7 +164,7 @@ QByteArray TerrainTile::serialize(QByteArray input) const QJsonObject& dataObject = rootObject[_jsonDataKey].toObject(); QList dataVersionKeyInfoList = { { _jsonBoundsKey, QJsonValue::Object, true }, - { _jsonStatsKey, QJsonValue::Object, true }, + { _jsonStatsKey, QJsonValue::Object, true }, { _jsonCarpetKey, QJsonValue::Array, true }, }; if (!JsonHelper::validateKeys(dataObject, dataVersionKeyInfoList, errorString)) { @@ -184,16 +191,16 @@ QByteArray TerrainTile::serialize(QByteArray input) QByteArray emptyArray; return emptyArray; } - stream << swArray[0].toDouble(); - stream << swArray[1].toDouble(); - stream << neArray[0].toDouble(); - stream << neArray[1].toDouble(); + stream << static_cast(swArray[0].toDouble()); + stream << static_cast(swArray[1].toDouble()); + stream << static_cast(neArray[0].toDouble()); + stream << static_cast(neArray[1].toDouble()); // Stats const QJsonObject& statsObject = dataObject[_jsonStatsKey].toObject(); QList statsVersionKeyInfoList = { - { _jsonMaxElevationKey, QJsonValue::Double, true }, { _jsonMinElevationKey, QJsonValue::Double, true }, + { _jsonMaxElevationKey, QJsonValue::Double, true }, { _jsonAvgElevationKey, QJsonValue::Double, true }, }; if (!JsonHelper::validateKeys(statsObject, statsVersionKeyInfoList, errorString)) { @@ -201,21 +208,21 @@ QByteArray TerrainTile::serialize(QByteArray input) QByteArray emptyArray; return emptyArray; } - stream << statsObject[_jsonMaxElevationKey].toInt(); - stream << statsObject[_jsonMinElevationKey].toInt(); - stream << statsObject[_jsonAvgElevationKey].toDouble(); + stream << static_cast(statsObject[_jsonMinElevationKey].toInt()); + stream << static_cast(statsObject[_jsonMaxElevationKey].toInt()); + stream << static_cast(statsObject[_jsonAvgElevationKey].toDouble()); // Carpet const QJsonArray& carpetArray = dataObject[_jsonCarpetKey].toArray(); int gridSizeLat = carpetArray.count(); - stream << gridSizeLat; + stream << static_cast(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 << gridSizeLon; + stream << static_cast(gridSizeLon); qCDebug(TerrainTileLog) << "Received tile has size in longitued direction: " << row.count(); } if (row.count() < gridSizeLon) { @@ -224,7 +231,7 @@ QByteArray TerrainTile::serialize(QByteArray input) return emptyArray; } for (int j = 0; j < gridSizeLon; j++) { - stream << row[j].toDouble(); + stream << static_cast(row[j].toDouble()); } } diff --git a/src/TerrainTile.h b/src/TerrainTile.h index 7db6679c32b48191bf43be395969f28ba300ecb2..adf217df8574e6f8f601d43aa3a3c6a6905ef4e4 100644 --- a/src/TerrainTile.h +++ b/src/TerrainTile.h @@ -101,13 +101,13 @@ private: QGeoCoordinate _southWest; /// South west corner of the tile QGeoCoordinate _northEast; /// North east corner of the tile - int _minElevation; /// Minimum elevation in tile - int _maxElevation; /// Maximum elevation in tile - double _avgElevation; /// Average elevation of the tile + int16_t _minElevation; /// Minimum elevation in tile + int16_t _maxElevation; /// Maximum elevation in tile + float _avgElevation; /// Average elevation of the tile - double** _data; /// 2D elevation data array - int _gridSizeLat; /// data grid size in latitude direction - int _gridSizeLon; /// data grid size in longitude direction + 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