Skip to content

Commit

Permalink
ElevationMapProvider, QGCMapUrlEngine: WIP commit, provisionally incl…
Browse files Browse the repository at this point in the history
…ude srtm1 ardupilot terrain servers
  • Loading branch information
Davidsastresas committed Jun 19, 2023
1 parent 43a7098 commit 4e8e42b
Show file tree
Hide file tree
Showing 3 changed files with 85 additions and 1 deletion.
62 changes: 61 additions & 1 deletion src/QtLocationPlugin/ElevationMapProvider.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -52,4 +52,64 @@ QGCTileSet AirmapElevationProvider::getTileCount(const int zoom, const double to

QByteArray AirmapElevationProvider::serializeTile(QByteArray image) {
return TerrainTile::serializeFromAirMapJson(image);
}
}
// Ardupilot STR1 elevation provider
//-----------------------------------------------------------------------------
int ApStr1ElevationProvider::long2tileX(const double lon, const int z) const {
Q_UNUSED(z)
qDebug() << "long2tileX, input lon: " << lon << " output tileX: " << static_cast<int>(floor((lon + 180.0)));
return static_cast<int>(floor((lon + 180.0)));
}

//-----------------------------------------------------------------------------
int ApStr1ElevationProvider::lat2tileY(const double lat, const int z) const {
Q_UNUSED(z)
qDebug() << "lat2tileY, input lat: " << lat << " output tileY: " << static_cast<int>(floor((lat + 90.0)));
return static_cast<int>(floor((lat + 90.0)));
}

//-----------------------------------------------------------------------------
QString ApStr1ElevationProvider::_getURL(const int x, const int y, const int zoom, QNetworkAccessManager* networkManager) {
Q_UNUSED(networkManager)
Q_UNUSED(zoom)

QString formattedString1;
QString formattedString2;

// For saving them internally we do 0-360 and 0-180 to avoid signs. Need to redo that to obtain proper format for call
int xForUrl = x - 180;
int yForUrl = y - 90;

formattedString1 = ( xForUrl > 0 ) ? QString("N%1").arg(QString::number(xForUrl).rightJustified(2, '0')) :
QString("S%1").arg(QString::number(-xForUrl).rightJustified(2, '0'));

formattedString2 = ( yForUrl > 0 ) ? QString("E%1").arg(QString::number(yForUrl).rightJustified(3, '0')) :
QString("W%1").arg(QString::number(-yForUrl).rightJustified(3, '0'));

QString urlString = QString("https://terrain.ardupilot.org/SRTM1/%1%2.hgt.zip")
.arg(QString(formattedString1))
.arg(QString(formattedString2))
;

return urlString;
}

//--------------------------------------------------------------------------------
QGCTileSet ApStr1ElevationProvider::getTileCount(const int zoom, const double topleftLon,
const double topleftLat, const double bottomRightLon,
const double bottomRightLat) const {
QGCTileSet set;
set.tileX0 = long2tileX(topleftLon, zoom);
set.tileY0 = lat2tileY(bottomRightLat, zoom);
set.tileX1 = long2tileX(bottomRightLon, zoom);
set.tileY1 = lat2tileY(topleftLat, zoom);

set.tileCount = (static_cast<quint64>(set.tileX1) -
static_cast<quint64>(set.tileX0) + 1) *
(static_cast<quint64>(set.tileY1) -
static_cast<quint64>(set.tileY0) + 1);

set.tileSize = getAverageSize() * set.tileCount;

return set;
}
23 changes: 23 additions & 0 deletions src/QtLocationPlugin/ElevationMapProvider.h
Original file line number Diff line number Diff line change
Expand Up @@ -11,6 +11,7 @@
#include <QString>

static const quint32 AVERAGE_AIRMAP_ELEV_SIZE = 2786;
static const quint32 AVERAGE_APSTR3_ELEV_SIZE = 100000; // Around 1 MB?

class ElevationProvider : public MapProvider {
Q_OBJECT
Expand Down Expand Up @@ -49,3 +50,25 @@ class AirmapElevationProvider : public ElevationProvider {
QString _getURL(const int x, const int y, const int zoom, QNetworkAccessManager* networkManager) override;
};

// -----------------------------------------------------------
// Ardupilot Terrain Server Elevation SRTM1
// https://terrain.ardupilot.org/SRTM1/

class ApStr1ElevationProvider : public ElevationProvider {
Q_OBJECT
public:
ApStr1ElevationProvider(QObject* parent = nullptr)
: ElevationProvider(QStringLiteral("bin"), AVERAGE_APSTR3_ELEV_SIZE,
QGeoMapType::StreetMap, QStringLiteral("https://terrain.ardupilot.org/SRTM1/"), parent) {}

int long2tileX(const double lon, const int z) const override;

int lat2tileY(const double lat, const int z) const override;

QGCTileSet getTileCount(const int zoom, const double topleftLon,
const double topleftLat, const double bottomRightLon,
const double bottomRightLat) const override;

protected:
QString _getURL(const int x, const int y, const int zoom, QNetworkAccessManager* networkManager) override;
};
1 change: 1 addition & 0 deletions src/QtLocationPlugin/QGCMapUrlEngine.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -76,6 +76,7 @@ UrlFactory::UrlFactory() : _timeout(5 * 1000) {
_providersTable["VWorld Satellite Map"] = new VWorldSatMapProvider(this);

_providersTable["Airmap Elevation"] = new AirmapElevationProvider(this);
_providersTable["Ardupilot-SRTM1 Elevation"] = new ApStr1ElevationProvider(this);

_providersTable["Japan-GSI Contour"] = new JapanStdMapProvider(this);
_providersTable["Japan-GSI Seamless"] = new JapanSeamlessMapProvider(this);
Expand Down

0 comments on commit 4e8e42b

Please sign in to comment.