Browse Source

feat: replace airmap terrain with copernicus

QGC4.4
leonardosimovic 2 years ago committed by Don Gagne
parent
commit
e7b7908152
  1. 6
      src/QmlControls/QGroundControlQmlGlobal.h
  2. 20
      src/QtLocationPlugin/ElevationMapProvider.cpp
  3. 5
      src/QtLocationPlugin/ElevationMapProvider.h
  4. 2
      src/QtLocationPlugin/QGCMapTileSet.cpp
  5. 4
      src/QtLocationPlugin/QGCMapUrlEngine.cpp
  6. 1
      src/QtLocationPlugin/QGCMapUrlEngine.h
  7. 2
      src/QtLocationPlugin/QMLControl/OfflineMap.qml
  8. 10
      src/QtLocationPlugin/QMLControl/QGCMapEngineManager.cc
  9. 24
      src/Terrain/TerrainQuery.cc
  10. 252
      src/TerrainTile.cc
  11. 27
      src/TerrainTile.h

6
src/QmlControls/QGroundControlQmlGlobal.h

@ -106,6 +106,10 @@ public: @@ -106,6 +106,10 @@ public:
Q_PROPERTY(bool hasMAVLinkInspector READ hasMAVLinkInspector CONSTANT)
//-------------------------------------------------------------------------
// Elevation Provider
Q_PROPERTY(QString elevationProviderName READ elevationProviderName CONSTANT)
#if defined(QGC_ENABLE_PAIRING)
Q_PROPERTY(PairingManager* pairingManager READ pairingManager CONSTANT)
#endif
@ -203,6 +207,8 @@ public: @@ -203,6 +207,8 @@ public:
bool hasMAVLinkInspector () { return true; }
#endif
QString elevationProviderName () { return UrlFactory::kCopernicusElevationProviderKey; }
bool singleFirmwareSupport ();
bool singleVehicleSupport ();
bool px4ProFirmwareSupported ();

20
src/QtLocationPlugin/ElevationMapProvider.cpp

@ -6,32 +6,40 @@ @@ -6,32 +6,40 @@
#include "QGCMapEngine.h"
#include "TerrainTile.h"
/*
License for the COPERNICUS dataset hosted on https://terrain-ce.suite.auterion.com/:
© DLR e.V. 2010-2014 and © Airbus Defence and Space GmbH 2014-2018 provided under COPERNICUS
by the European Union and ESA; all rights reserved.
*/
ElevationProvider::ElevationProvider(const QString& imageFormat, quint32 averageSize, QGeoMapType::MapStyle mapType, QObject* parent)
: MapProvider(QStringLiteral("https://api.airmap.com/"), imageFormat, averageSize, mapType, parent) {}
: MapProvider(QStringLiteral("https://terrain-ce.suite.auterion.com/"), imageFormat, averageSize, mapType, parent) {}
//-----------------------------------------------------------------------------
int AirmapElevationProvider::long2tileX(const double lon, const int z) const {
int CopernicusElevationProvider::long2tileX(const double lon, const int z) const {
Q_UNUSED(z)
return static_cast<int>(floor((lon + 180.0) / TerrainTile::tileSizeDegrees));
}
//-----------------------------------------------------------------------------
int AirmapElevationProvider::lat2tileY(const double lat, const int z) const {
int CopernicusElevationProvider::lat2tileY(const double lat, const int z) const {
Q_UNUSED(z)
return static_cast<int>(floor((lat + 90.0) / TerrainTile::tileSizeDegrees));
}
QString AirmapElevationProvider::_getURL(const int x, const int y, const int zoom, QNetworkAccessManager* networkManager) {
QString CopernicusElevationProvider::_getURL(const int x, const int y, const int zoom, QNetworkAccessManager* networkManager) {
Q_UNUSED(networkManager)
Q_UNUSED(zoom)
return QString("https://api.airmap.com/elevation/v1/ele/carpet?points=%1,%2,%3,%4")
return QString("https://terrain-ce.suite.auterion.com/api/v1/carpet?points=%1,%2,%3,%4")
.arg(static_cast<double>(y) * TerrainTile::tileSizeDegrees - 90.0)
.arg(static_cast<double>(x) * TerrainTile::tileSizeDegrees - 180.0)
.arg(static_cast<double>(y + 1) * TerrainTile::tileSizeDegrees - 90.0)
.arg(static_cast<double>(x + 1) * TerrainTile::tileSizeDegrees - 180.0);
}
QGCTileSet AirmapElevationProvider::getTileCount(const int zoom, const double topleftLon,
QGCTileSet CopernicusElevationProvider::getTileCount(const int zoom, const double topleftLon,
const double topleftLat, const double bottomRightLon,
const double bottomRightLat) const {
QGCTileSet set;

5
src/QtLocationPlugin/ElevationMapProvider.h

@ -24,10 +24,10 @@ class ElevationProvider : public MapProvider { @@ -24,10 +24,10 @@ class ElevationProvider : public MapProvider {
// -----------------------------------------------------------
// Airmap Elevation
class AirmapElevationProvider : public ElevationProvider {
class CopernicusElevationProvider : public ElevationProvider {
Q_OBJECT
public:
AirmapElevationProvider(QObject* parent = nullptr)
CopernicusElevationProvider(QObject* parent = nullptr)
: ElevationProvider(QStringLiteral("bin"), AVERAGE_AIRMAP_ELEV_SIZE,
QGeoMapType::StreetMap, parent) {}
@ -42,4 +42,3 @@ class AirmapElevationProvider : public ElevationProvider { @@ -42,4 +42,3 @@ class AirmapElevationProvider : public ElevationProvider {
protected:
QString _getURL(const int x, const int y, const int zoom, QNetworkAccessManager* networkManager) override;
};

2
src/QtLocationPlugin/QGCMapTileSet.cpp

@ -289,7 +289,7 @@ QGCCachedTileSet::_networkReplyFinished() @@ -289,7 +289,7 @@ QGCCachedTileSet::_networkReplyFinished()
qCDebug(QGCCachedTileSetLog) << "Tile fetched" << hash;
QByteArray image = reply->readAll();
QString type = getQGCMapEngine()->hashToType(hash);
if (type == "Airmap Elevation" ) {
if (type == UrlFactory::kCopernicusElevationProviderKey) {
image = TerrainTile::serializeFromAirMapJson(image);
}
QString format = getQGCMapEngine()->urlFactory()->getImageFormat(type, image);

4
src/QtLocationPlugin/QGCMapUrlEngine.cpp

@ -32,6 +32,8 @@ QGC_LOGGING_CATEGORY(QGCMapUrlEngineLog, "QGCMapUrlEngineLog") @@ -32,6 +32,8 @@ QGC_LOGGING_CATEGORY(QGCMapUrlEngineLog, "QGCMapUrlEngineLog")
#include <QString>
#include <QTimer>
const char* UrlFactory::kCopernicusElevationProviderKey = "Copernicus Elevation";
//-----------------------------------------------------------------------------
UrlFactory::UrlFactory() : _timeout(5 * 1000) {
@ -75,7 +77,7 @@ UrlFactory::UrlFactory() : _timeout(5 * 1000) { @@ -75,7 +77,7 @@ UrlFactory::UrlFactory() : _timeout(5 * 1000) {
_providersTable["VWorld Street Map"] = new VWorldStreetMapProvider(this);
_providersTable["VWorld Satellite Map"] = new VWorldSatMapProvider(this);
_providersTable["Airmap Elevation"] = new AirmapElevationProvider(this);
_providersTable[kCopernicusElevationProviderKey] = new CopernicusElevationProvider(this);
_providersTable["Japan-GSI Contour"] = new JapanStdMapProvider(this);
_providersTable["Japan-GSI Seamless"] = new JapanSeamlessMapProvider(this);

1
src/QtLocationPlugin/QGCMapUrlEngine.h

@ -29,6 +29,7 @@ @@ -29,6 +29,7 @@
class UrlFactory : public QObject {
Q_OBJECT
public:
static const char* kCopernicusElevationProviderKey;
UrlFactory ();
~UrlFactory ();

2
src/QtLocationPlugin/QMLControl/OfflineMap.qml

@ -522,7 +522,7 @@ Item { @@ -522,7 +522,7 @@ Item {
Row {
spacing: ScreenTools.defaultFontPixelWidth
anchors.horizontalCenter: parent.horizontalCenter
visible: !_defaultSet && mapType !== "Airmap Elevation"
visible: !_defaultSet && mapType !== QGroundControl.elevationProviderName
QGCLabel { text: qsTr("Zoom Levels:"); width: infoView._labelWidth; }
QGCLabel { text: offlineMapView._currentSelection ? (offlineMapView._currentSelection.minZoom + " - " + offlineMapView._currentSelection.maxZoom) : ""; horizontalAlignment: Text.AlignRight; width: infoView._valueWidth; }
}

10
src/QtLocationPlugin/QMLControl/QGCMapEngineManager.cc

@ -28,6 +28,8 @@ QGC_LOGGING_CATEGORY(QGCMapEngineManagerLog, "QGCMapEngineManagerLog") @@ -28,6 +28,8 @@ QGC_LOGGING_CATEGORY(QGCMapEngineManagerLog, "QGCMapEngineManagerLog")
static const char* kQmlOfflineMapKeyName = "QGCOfflineMap";
static const auto kElevationMapType = UrlFactory::kCopernicusElevationProviderKey;
//-----------------------------------------------------------------------------
QGCMapEngineManager::QGCMapEngineManager(QGCApplication* app, QGCToolbox* toolbox)
: QGCTool(app, toolbox)
@ -84,7 +86,7 @@ QGCMapEngineManager::updateForCurrentView(double lon0, double lat0, double lon1, @@ -84,7 +86,7 @@ QGCMapEngineManager::updateForCurrentView(double lon0, double lat0, double lon1,
_imageSet += set;
}
if (_fetchElevation) {
QGCTileSet set = QGCMapEngine::getTileCount(1, lon0, lat0, lon1, lat1, "Airmap Elevation");
QGCTileSet set = QGCMapEngine::getTileCount(1, lon0, lat0, lon1, lat1, kElevationMapType);
_elevationSet += set;
}
@ -159,9 +161,9 @@ QGCMapEngineManager::startDownload(const QString& name, const QString& mapType) @@ -159,9 +161,9 @@ QGCMapEngineManager::startDownload(const QString& name, const QString& mapType)
} else {
qWarning() << "QGCMapEngineManager::startDownload() No Tiles to save";
}
if (mapType != "Airmap Elevation" && _fetchElevation) {
if (mapType != kElevationMapType && _fetchElevation) {
QGCCachedTileSet* set = new QGCCachedTileSet(name + " Elevation");
set->setMapTypeStr("Airmap Elevation");
set->setMapTypeStr(kElevationMapType);
set->setTopleftLat(_topleftLat);
set->setTopleftLon(_topleftLon);
set->setBottomRightLat(_bottomRightLat);
@ -170,7 +172,7 @@ QGCMapEngineManager::startDownload(const QString& name, const QString& mapType) @@ -170,7 +172,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("Airmap Elevation");
set->setType(kElevationMapType);
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);

24
src/Terrain/TerrainQuery.cc

@ -33,6 +33,8 @@ QGC_LOGGING_CATEGORY(TerrainQueryVerboseLog, "TerrainQueryVerboseLog") @@ -33,6 +33,8 @@ QGC_LOGGING_CATEGORY(TerrainQueryVerboseLog, "TerrainQueryVerboseLog")
Q_GLOBAL_STATIC(TerrainAtCoordinateBatchManager, _TerrainAtCoordinateBatchManager)
Q_GLOBAL_STATIC(TerrainTileManager, _terrainTileManager)
static const auto kMapType = UrlFactory::kCopernicusElevationProviderKey;
TerrainAirMapQuery::TerrainAirMapQuery(QObject* parent)
: TerrainQueryInterface(parent)
{
@ -443,13 +445,17 @@ bool TerrainTileManager::getAltitudesForCoordinates(const QList<QGeoCoordinate>& @@ -443,13 +445,17 @@ bool TerrainTileManager::getAltitudesForCoordinates(const QList<QGeoCoordinate>&
altitudes.push_back(elevation);
} else {
if (_state != State::Downloading) {
QNetworkRequest request = getQGCMapEngine()->urlFactory()->getTileURL("Airmap Elevation", getQGCMapEngine()->urlFactory()->long2tileX("Airmap Elevation",coordinate.longitude(), 1), getQGCMapEngine()->urlFactory()->lat2tileY("Airmap Elevation", coordinate.latitude(), 1), 1, &_networkManager);
QNetworkRequest request = getQGCMapEngine()->urlFactory()->getTileURL(
kMapType, getQGCMapEngine()->urlFactory()->long2tileX(kMapType, coordinate.longitude(), 1),
getQGCMapEngine()->urlFactory()->lat2tileY(kMapType, coordinate.latitude(), 1),
1,
&_networkManager);
qCDebug(TerrainQueryLog) << "TerrainTileManager::getAltitudesForCoordinates query from database" << request.url();
QGeoTileSpec spec;
spec.setX(getQGCMapEngine()->urlFactory()->long2tileX("Airmap Elevation", coordinate.longitude(), 1));
spec.setY(getQGCMapEngine()->urlFactory()->lat2tileY("Airmap Elevation", coordinate.latitude(), 1));
spec.setX(getQGCMapEngine()->urlFactory()->long2tileX(kMapType, coordinate.longitude(), 1));
spec.setY(getQGCMapEngine()->urlFactory()->lat2tileY(kMapType, coordinate.latitude(), 1));
spec.setZoom(1);
spec.setMapId(getQGCMapEngine()->urlFactory()->getIdFromType("Airmap Elevation"));
spec.setMapId(getQGCMapEngine()->urlFactory()->getIdFromType(kMapType));
QGeoTiledMapReplyQGC* reply = new QGeoTiledMapReplyQGC(&_networkManager, request, spec);
connect(reply, &QGeoTiledMapReplyQGC::terrainDone, this, &TerrainTileManager::_terrainDone);
_state = State::Downloading;
@ -466,7 +472,7 @@ bool TerrainTileManager::getAltitudesForCoordinates(const QList<QGeoCoordinate>& @@ -466,7 +472,7 @@ bool TerrainTileManager::getAltitudesForCoordinates(const QList<QGeoCoordinate>&
void TerrainTileManager::_tileFailed(void)
{
QList<double> noAltitudes;
QList<double> noAltitudes;
for (const QueuedRequestInfo_t& requestInfo: _requestQueue) {
if (requestInfo.queryMode == QueryMode::QueryModeCoordinates) {
@ -490,7 +496,7 @@ void TerrainTileManager::_terrainDone(QByteArray responseBytes, QNetworkReply::N @@ -490,7 +496,7 @@ void TerrainTileManager::_terrainDone(QByteArray responseBytes, QNetworkReply::N
// remove from download queue
QGeoTileSpec spec = reply->tileSpec();
QString hash = QGCMapEngine::getTileHash("Airmap Elevation", spec.x(), spec.y(), spec.zoom());
QString hash = QGCMapEngine::getTileHash(kMapType, spec.x(), spec.y(), spec.zoom());
// handle potential errors
if (error != QNetworkReply::NoError) {
@ -557,9 +563,9 @@ void TerrainTileManager::_terrainDone(QByteArray responseBytes, QNetworkReply::N @@ -557,9 +563,9 @@ void TerrainTileManager::_terrainDone(QByteArray responseBytes, QNetworkReply::N
QString TerrainTileManager::_getTileHash(const QGeoCoordinate& coordinate)
{
QString ret = QGCMapEngine::getTileHash(
"Airmap Elevation",
getQGCMapEngine()->urlFactory()->long2tileX("Airmap Elevation", coordinate.longitude(), 1),
getQGCMapEngine()->urlFactory()->lat2tileY("Airmap Elevation", coordinate.latitude(), 1),
kMapType,
getQGCMapEngine()->urlFactory()->long2tileX(kMapType, coordinate.longitude(), 1),
getQGCMapEngine()->urlFactory()->lat2tileY(kMapType, coordinate.latitude(), 1),
1);
qCDebug(TerrainQueryVerboseLog) << "Computing unique tile hash for " << coordinate << ret;

252
src/TerrainTile.cc

@ -31,140 +31,120 @@ const char* TerrainTile::_jsonMinElevationKey = "min"; @@ -31,140 +31,120 @@ 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(nullptr)
, _gridSizeLat(-1)
, _gridSizeLon(-1)
, _isValid(false)
TerrainTile::TerrainTile(const QByteArray& byteArray)
{
// Copy tile info
_tileInfo = *reinterpret_cast<const TileInfo_t*>(byteArray.constData());
}
TerrainTile::~TerrainTile()
{
if (_data) {
for (int i = 0; i < _gridSizeLat; i++) {
delete[] _data[i];
}
delete[] _data;
_data = nullptr;
// Check feasibility
if ((_tileInfo.neLon - _tileInfo.swLon) < 0.0 || (_tileInfo.neLat - _tileInfo.swLat) < 0.0) {
qCWarning(TerrainTileLog) << this << "Tile extent is infeasible";
_isValid = false;
return;
}
}
TerrainTile::TerrainTile(QByteArray byteArray)
: _minElevation(-1.0)
, _maxElevation(-1.0)
, _avgElevation(-1.0)
, _data(nullptr)
, _gridSizeLat(-1)
, _gridSizeLon(-1)
, _isValid(false)
{
_cellSizeLat = (_tileInfo.neLat - _tileInfo.swLat) / _tileInfo.gridSizeLat;
_cellSizeLon = (_tileInfo.neLon - _tileInfo.swLon) / _tileInfo.gridSizeLon;
qCDebug(TerrainTileLog) << this << "TileInfo: south west: " << _tileInfo.swLat << _tileInfo.swLon;
qCDebug(TerrainTileLog) << this << "TileInfo: north east: " << _tileInfo.neLat << _tileInfo.neLon;
qCDebug(TerrainTileLog) << this << "TileInfo: dimensions: " << _tileInfo.gridSizeLat << "by" << _tileInfo.gridSizeLat;
qCDebug(TerrainTileLog) << this << "TileInfo: min, max, avg: " << _tileInfo.minElevation << _tileInfo.maxElevation << _tileInfo.avgElevation;
qCDebug(TerrainTileLog) << this << "TileInfo: cell size: " << _cellSizeLat << _cellSizeLon;
int cTileHeaderBytes = static_cast<int>(sizeof(TileInfo_t));
int cTileBytesAvailable = byteArray.size();
if (cTileBytesAvailable < cTileHeaderBytes) {
qWarning() << "Terrain tile binary data too small for TileInfo_s header";
qCWarning(TerrainTileLog) << "Terrain tile binary data too small for TileInfo_s header";
return;
}
const TileInfo_t* tileInfo = reinterpret_cast<const TileInfo_t*>(byteArray.constData());
_southWest.setLatitude(tileInfo->swLat);
_southWest.setLongitude(tileInfo->swLon);
_northEast.setLatitude(tileInfo->neLat);
_northEast.setLongitude(tileInfo->neLon);
_minElevation = tileInfo->minElevation;
_maxElevation = tileInfo->maxElevation;
_avgElevation = tileInfo->avgElevation;
_gridSizeLat = tileInfo->gridSizeLat;
_gridSizeLon = tileInfo->gridSizeLon;
qCDebug(TerrainTileLog) << "Loading terrain tile: " << _southWest << " - " << _northEast;
qCDebug(TerrainTileLog) << "min:max:avg:sizeLat:sizeLon" << _minElevation << _maxElevation << _avgElevation << _gridSizeLat << _gridSizeLon;
int cTileDataBytes = static_cast<int>(sizeof(int16_t)) * _gridSizeLat * _gridSizeLon;
int cTileDataBytes = static_cast<int>(sizeof(int16_t)) * _tileInfo.gridSizeLat * _tileInfo.gridSizeLon;
if (cTileBytesAvailable < cTileHeaderBytes + cTileDataBytes) {
qWarning() << "Terrain tile binary data too small for tile data";
qCWarning(TerrainTileLog) << "Terrain tile binary data too small for tile data";
return;
}
_data = new int16_t*[_gridSizeLat];
for (int k = 0; k < _gridSizeLat; k++) {
_data[k] = new int16_t[_gridSizeLon];
_data = new int16_t*[_tileInfo.gridSizeLat];
for (int k = 0; k < _tileInfo.gridSizeLat; k++) {
_data[k] = new int16_t[_tileInfo.gridSizeLon];
}
int valueIndex = 0;
const int16_t* pTileData = reinterpret_cast<const int16_t*>(&reinterpret_cast<const uint8_t*>(byteArray.constData())[cTileHeaderBytes]);
for (int i = 0; i < _gridSizeLat; i++) {
for (int j = 0; j < _gridSizeLon; j++) {
for (int i = 0; i < _tileInfo.gridSizeLat; i++) {
for (int j = 0; j < _tileInfo.gridSizeLon; j++) {
_data[i][j] = pTileData[valueIndex++];
}
}
_isValid = true;
}
return;
TerrainTile::~TerrainTile()
{
if (!_data) {
return;
}
for (unsigned i = 0; i < static_cast<unsigned>(_tileInfo.gridSizeLat); i++) {
delete[] _data[i];
}
delete[] _data;
}
double TerrainTile::elevation(const QGeoCoordinate& coordinate) const
{
if (_isValid && _southWest.isValid() && _northEast.isValid()) {
qCDebug(TerrainTileLog) << "elevation: " << coordinate << " , in sw " << _southWest << " , ne " << _northEast;
// The lat/lon values in _northEast and _southWest coordinates can have rounding errors such that the coordinate
// request may be slightly outside the tile box specified by these values. So we clamp the incoming values to the
// edges of the tile if needed.
double clampedLon = qMax(coordinate.longitude(), _southWest.longitude());
double clampedLat = qMax(coordinate.latitude(), _southWest.latitude());
// Calc the index of the southernmost and westernmost index data value
int lonIndex = qFloor((clampedLon - _southWest.longitude()) / tileValueSpacingDegrees);
int latIndex = qFloor((clampedLat - _southWest.latitude()) / tileValueSpacingDegrees);
// Calc how far along in between the known values the requested lat/lon is fractionally
double lonIndexLongitude = _southWest.longitude() + (static_cast<double>(lonIndex) * tileValueSpacingDegrees);
double lonFraction = (clampedLon - lonIndexLongitude) / tileValueSpacingDegrees;
double latIndexLatitude = _southWest.latitude() + (static_cast<double>(latIndex) * tileValueSpacingDegrees);
double latFraction = (clampedLat - latIndexLatitude) / tileValueSpacingDegrees;
// Calc the elevation as the average across the four known points
double known00 = _data[latIndex][lonIndex];
double known01 = _data[latIndex][lonIndex+1];
double known10 = _data[latIndex+1][lonIndex];
double known11 = _data[latIndex+1][lonIndex+1];
double lonValue1 = known00 + ((known01 - known00) * lonFraction);
double lonValue2 = known10 + ((known11 - known10) * lonFraction);
double latValue = lonValue1 + ((lonValue2 - lonValue1) * latFraction);
return latValue;
} else {
qCWarning(TerrainTileLog) << "elevation: Internal error - invalid tile";
if (!_isValid || !_data) {
qCWarning(TerrainTileLog) << this << "Request for elevation, but tile is invalid.";
return qQNaN();
}
}
QGeoCoordinate TerrainTile::centerCoordinate(void) const
{
return _southWest.atDistanceAndAzimuth(_southWest.distanceTo(_northEast) / 2.0, _southWest.azimuthTo(_northEast));
const double latDeltaSw = coordinate.latitude() - _tileInfo.swLat;
const double lonDeltaSw = coordinate.longitude() - _tileInfo.swLon;
const int16_t latIndex = qFloor(latDeltaSw / _cellSizeLat);
const int16_t lonIndex = qFloor(lonDeltaSw / _cellSizeLon);
const bool latIndexInvalid = latIndex < 0 || latIndex > (_tileInfo.gridSizeLat - 1);
const bool lonIndexInvalid = lonIndex < 0 || lonIndex > (_tileInfo.gridSizeLon - 1);
if (latIndexInvalid || lonIndexInvalid) {
qCWarning(TerrainTileLog) << this << "Internal error: coordinate" << coordinate << "outside tile bounds";
return qQNaN();
}
const auto elevation = _data[latIndex][lonIndex];
// Print warning if elevation is outside min/max of tile meta data
if (elevation < _tileInfo.minElevation) {
qCWarning(TerrainTileLog) << this << "Warning: elevation read is below min elevation in tile:" << elevation << "<" << _tileInfo.minElevation;
}
else if (elevation > _tileInfo.maxElevation) {
qCWarning(TerrainTileLog) << this << "Warning: elevation read is above max elevation in tile:" << elevation << ">" << _tileInfo.maxElevation;
}
#ifdef QT_DEBUG
qCDebug(TerrainTileLog) << this << "latIndex, lonIndex:" << latIndex << lonIndex << "elevation:" << elevation;
#endif
return static_cast<double>(elevation);
}
QByteArray TerrainTile::serializeFromAirMapJson(QByteArray input)
QByteArray TerrainTile::serializeFromAirMapJson(const QByteArray& input)
{
QJsonParseError parseError;
QJsonDocument document = QJsonDocument::fromJson(input, &parseError);
if (parseError.error != QJsonParseError::NoError) {
QByteArray emptyArray;
return emptyArray;
qCWarning(TerrainTileLog) << "TerrainTile::serializeFromAirMapJson: Terrain tile json doc parse error" << parseError.errorString();
return QByteArray();
}
if (!document.isObject()) {
qCDebug(TerrainTileLog) << "Terrain tile json doc is no object";
QByteArray emptyArray;
return emptyArray;
qCWarning(TerrainTileLog) << "TerrainTile::serializeFromAirMapJson: Terrain tile json doc is no object";
return QByteArray();
}
QJsonObject rootObject = document.object();
@ -174,15 +154,13 @@ QByteArray TerrainTile::serializeFromAirMapJson(QByteArray input) @@ -174,15 +154,13 @@ QByteArray TerrainTile::serializeFromAirMapJson(QByteArray input)
{ _jsonDataKey, QJsonValue::Object, true },
};
if (!JsonHelper::validateKeys(rootObject, rootVersionKeyInfoList, errorString)) {
qCDebug(TerrainTileLog) << "Error in reading json: " << errorString;
QByteArray emptyArray;
return emptyArray;
qCWarning(TerrainTileLog) << "TerrainTile::serializeFromAirMapJson: Error in reading json: " << errorString;
return QByteArray();
}
if (rootObject[_jsonStatusKey].toString() != "success") {
qCDebug(TerrainTileLog) << "Invalid terrain tile.";
QByteArray emptyArray;
return emptyArray;
qCWarning(TerrainTileLog) << "TerrainTile::serializeFromAirMapJson: Invalid terrain tile.";
return QByteArray();
}
const QJsonObject& dataObject = rootObject[_jsonDataKey].toObject();
QList<JsonHelper::KeyValidateInfo> dataVersionKeyInfoList = {
@ -191,9 +169,8 @@ QByteArray TerrainTile::serializeFromAirMapJson(QByteArray input) @@ -191,9 +169,8 @@ QByteArray TerrainTile::serializeFromAirMapJson(QByteArray input)
{ _jsonCarpetKey, QJsonValue::Array, true },
};
if (!JsonHelper::validateKeys(dataObject, dataVersionKeyInfoList, errorString)) {
qCDebug(TerrainTileLog) << "Error in reading json: " << errorString;
QByteArray emptyArray;
return emptyArray;
qCWarning(TerrainTileLog) << "TerrainTile::serializeFromAirMapJson: Error in reading json: " << errorString;
return QByteArray();
}
// Bounds
@ -203,18 +180,24 @@ QByteArray TerrainTile::serializeFromAirMapJson(QByteArray input) @@ -203,18 +180,24 @@ QByteArray TerrainTile::serializeFromAirMapJson(QByteArray input)
{ _jsonNorthEastKey, QJsonValue::Array, true },
};
if (!JsonHelper::validateKeys(boundsObject, boundsVersionKeyInfoList, errorString)) {
qCDebug(TerrainTileLog) << "Error in reading json: " << errorString;
QByteArray emptyArray;
return emptyArray;
qCWarning(TerrainTileLog) << "TerrainTile::serializeFromAirMapJson: Error in reading json: " << errorString;
return QByteArray();
}
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;
qCWarning(TerrainTileLog) << "TerrainTile::serializeFromAirMapJson: Incomplete bounding location";
return QByteArray();
}
const double swLat = swArray[0].toDouble();
const double swLon = swArray[1].toDouble();
const double neLat = neArray[0].toDouble();
const double neLon = neArray[1].toDouble();
qCDebug(TerrainTileLog) << "Serialize: swArray: south west: " << (40.42 - swLat) << (-3.23 - swLon);
qCDebug(TerrainTileLog) << "Serialize: neArray: north east: " << neLat << neLon;
// Stats
const QJsonObject& statsObject = dataObject[_jsonStatsKey].toObject();
QList<JsonHelper::KeyValidateInfo> statsVersionKeyInfoList = {
@ -223,18 +206,14 @@ QByteArray TerrainTile::serializeFromAirMapJson(QByteArray input) @@ -223,18 +206,14 @@ QByteArray TerrainTile::serializeFromAirMapJson(QByteArray input)
{ _jsonAvgElevationKey, QJsonValue::Double, true },
};
if (!JsonHelper::validateKeys(statsObject, statsVersionKeyInfoList, errorString)) {
qCDebug(TerrainTileLog) << "Error in reading json: " << errorString;
QByteArray emptyArray;
return emptyArray;
qCWarning(TerrainTileLog) << "TerrainTile::serializeFromAirMapJson: Error in reading json: " << errorString;
return QByteArray();
}
// Carpet
const QJsonArray& carpetArray = dataObject[_jsonCarpetKey].toArray();
int gridSizeLat = carpetArray.count();
int gridSizeLon = carpetArray[0].toArray().count();
TileInfo_t tileInfo;
// Tile meta data
TerrainTile::TileInfo_t tileInfo;
tileInfo.swLat = swArray[0].toDouble();
tileInfo.swLon = swArray[1].toDouble();
tileInfo.neLat = neArray[0].toDouble();
@ -242,41 +221,34 @@ QByteArray TerrainTile::serializeFromAirMapJson(QByteArray input) @@ -242,41 +221,34 @@ QByteArray TerrainTile::serializeFromAirMapJson(QByteArray input)
tileInfo.minElevation = static_cast<int16_t>(statsObject[_jsonMinElevationKey].toInt());
tileInfo.maxElevation = static_cast<int16_t>(statsObject[_jsonMaxElevationKey].toInt());
tileInfo.avgElevation = statsObject[_jsonAvgElevationKey].toDouble();
tileInfo.gridSizeLat = static_cast<int16_t>(gridSizeLat);
tileInfo.gridSizeLon = static_cast<int16_t>(gridSizeLon);
// We require 1-arc second value spacing
double neCornerLatExpected = tileInfo.swLat + ((tileInfo.gridSizeLat - 1) * tileValueSpacingDegrees);
double neCornerLonExpected = tileInfo.swLon + ((tileInfo.gridSizeLon - 1) * tileValueSpacingDegrees);
if (!QGC::fuzzyCompare(tileInfo.neLat, neCornerLatExpected) || !QGC::fuzzyCompare(tileInfo.neLon, neCornerLonExpected)) {
qCWarning(TerrainTileLog) << QStringLiteral("serialize: Internal error - distance between values incorrect neExpected(%1, %2) neActual(%3, %4) sw(%5, %6) gridSize(%7, %8)")
.arg(neCornerLatExpected).arg(neCornerLonExpected).arg(tileInfo.neLat).arg(tileInfo.neLon).arg(tileInfo.swLat).arg(tileInfo.swLon).arg(tileInfo.gridSizeLat).arg(tileInfo.gridSizeLon);
QByteArray emptyArray;
return emptyArray;
}
tileInfo.gridSizeLat = static_cast<int16_t>(carpetArray.count());
tileInfo.gridSizeLon = static_cast<int16_t>(carpetArray[0].toArray().count());
int cTileHeaderBytes = static_cast<int>(sizeof(TileInfo_t));
int cTileDataBytes = static_cast<int>(sizeof(int16_t)) * gridSizeLat * gridSizeLon;
qCDebug(TerrainTileLog) << "Serialize: TileInfo: south west: " << tileInfo.swLat << tileInfo.swLon;
qCDebug(TerrainTileLog) << "Serialize: TileInfo: north east: " << tileInfo.neLat << tileInfo.neLon;
const auto cTileNumHeaderBytes = static_cast<int>(sizeof(TileInfo_t));
const auto cTileNumDataBytes = static_cast<int>(sizeof(int16_t)) * tileInfo.gridSizeLat * tileInfo.gridSizeLon;
QByteArray byteArray(cTileHeaderBytes + cTileDataBytes, 0);
QByteArray res;
res.resize(cTileNumHeaderBytes + cTileNumDataBytes);
TileInfo_t* pTileInfo = reinterpret_cast<TileInfo_t*>(byteArray.data());
int16_t* pTileData = reinterpret_cast<int16_t*>(&reinterpret_cast<uint8_t*>(byteArray.data())[cTileHeaderBytes]);
TileInfo_t* pTileInfo = reinterpret_cast<TileInfo_t*>(res.data());
int16_t* pTileData = reinterpret_cast<int16_t*>(&reinterpret_cast<uint8_t*>(res.data())[cTileNumHeaderBytes]);
*pTileInfo = tileInfo;
int valueIndex = 0;
for (int i = 0; i < gridSizeLat; i++) {
for (unsigned i = 0; i < static_cast<unsigned>(tileInfo.gridSizeLat); i++) {
const QJsonArray& row = carpetArray[i].toArray();
if (row.count() < gridSizeLon) {
qCDebug(TerrainTileLog) << "Expected row array of " << gridSizeLon << ", instead got " << row.count();
QByteArray emptyArray;
return emptyArray;
if (row.count() < tileInfo.gridSizeLon) {
qCDebug(TerrainTileLog) << "Expected row array of " << tileInfo.gridSizeLon << ", instead got " << row.count();
return QByteArray();
}
for (int j = 0; j < gridSizeLon; j++) {
for (unsigned j = 0; j < static_cast<unsigned>(tileInfo.gridSizeLon); j++) {
pTileData[valueIndex++] = static_cast<int16_t>(row[j].toDouble());
}
}
return byteArray;
return res;
}

27
src/TerrainTile.h

@ -16,7 +16,7 @@ Q_DECLARE_LOGGING_CATEGORY(TerrainTileLog) @@ -16,7 +16,7 @@ Q_DECLARE_LOGGING_CATEGORY(TerrainTileLog)
class TerrainTile
{
public:
TerrainTile();
TerrainTile() = default;
~TerrainTile();
/**
@ -24,7 +24,7 @@ public: @@ -24,7 +24,7 @@ public:
*
* @param document
*/
TerrainTile(QByteArray byteArray);
TerrainTile(const QByteArray& byteArray);
/**
* Check whether valid data is loaded
@ -46,30 +46,29 @@ public: @@ -46,30 +46,29 @@ public:
*
* @return minimum elevation
*/
double minElevation(void) const { return _minElevation; }
double minElevation(void) const { return _isValid ? static_cast<double>(_tileInfo.minElevation) : qQNaN(); }
/**
* Accessor for the maximum elevation of the tile
*
* @return maximum elevation
*/
double maxElevation(void) const { return _maxElevation; }
double maxElevation(void) const { return _isValid ? static_cast<double>(_tileInfo.maxElevation) : qQNaN(); }
/**
* Accessor for the average elevation of the tile
*
* @return average elevation
*/
double avgElevation(void) const { return _avgElevation; }
double avgElevation(void) const { return _isValid ? _tileInfo.avgElevation : qQNaN(); }
/**
* Accessor for the center coordinate
*
* @return center coordinate
*/
QGeoCoordinate centerCoordinate(void) const;
static QByteArray serializeFromAirMapJson(QByteArray input);
static QByteArray serializeFromAirMapJson(const QByteArray& input);
static constexpr double tileSizeDegrees = 0.01; ///< Each terrain tile represents a square area .01 degrees in lat/lon
static constexpr double tileValueSpacingDegrees = 1.0 / 3600; ///< 1 Arc-Second spacing of elevation values
@ -77,7 +76,7 @@ public: @@ -77,7 +76,7 @@ public:
private:
typedef struct {
double swLat,swLon, neLat, neLon;
double swLat, swLon, neLat, neLon;
int16_t minElevation;
int16_t maxElevation;
double avgElevation;
@ -85,16 +84,10 @@ private: @@ -85,16 +84,10 @@ private:
int16_t gridSizeLon;
} TileInfo_t;
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
double _avgElevation; /// Average elevation of the tile
TileInfo_t _tileInfo;
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
double _cellSizeLat; /// data grid size in latitude direction
double _cellSizeLon; /// data grid size in longitude direction
bool _isValid; /// data loaded is valid
// Json keys

Loading…
Cancel
Save