Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

feat: replace Airmap terrain data with Copernicus #10740

Merged
Merged
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
13 changes: 13 additions & 0 deletions src/PlanView/PlanView.qml
Original file line number Diff line number Diff line change
Expand Up @@ -730,6 +730,19 @@ Item {
}
}

QGCLabel {
// Elevation provider notice on top of terrain plot
readonly property string _licenseString: QGroundControl.elevationProviderNotice

id: licenseLabel
visible: terrainStatus.visible && _licenseString !== ""
anchors.bottom: terrainStatus.top
anchors.horizontalCenter: terrainStatus.horizontalCenter
anchors.bottomMargin: ScreenTools.defaultFontPixelWidth * 0.5
font.pointSize: ScreenTools.smallFontPointSize
text: qsTr("Powered by %1").arg(_licenseString)
}

TerrainStatus {
id: terrainStatus
anchors.margins: _toolsMargin
Expand Down
1 change: 0 additions & 1 deletion src/PlanView/TerrainStatus.qml
Original file line number Diff line number Diff line change
Expand Up @@ -50,7 +50,6 @@ Rectangle {

QGCFlickable {
id: terrainProfileFlickable
//anchors.margins: _margins
anchors.top: parent.top
anchors.bottom: parent.bottom
anchors.leftMargin: titleLabel.contentHeight
Expand Down
9 changes: 9 additions & 0 deletions src/QmlControls/QGroundControlQmlGlobal.h
Original file line number Diff line number Diff line change
Expand Up @@ -106,6 +106,12 @@ class QGroundControlQmlGlobal : public QGCTool
Q_PROPERTY(bool hasMAVLinkInspector READ hasMAVLinkInspector CONSTANT)


//-------------------------------------------------------------------------
// Elevation Provider
Q_PROPERTY(QString elevationProviderName READ elevationProviderName CONSTANT)
Q_PROPERTY(QString elevationProviderNotice READ elevationProviderNotice CONSTANT)


#if defined(QGC_ENABLE_PAIRING)
Q_PROPERTY(PairingManager* pairingManager READ pairingManager CONSTANT)
#endif
Expand Down Expand Up @@ -203,6 +209,9 @@ class QGroundControlQmlGlobal : public QGCTool
bool hasMAVLinkInspector () { return true; }
#endif

QString elevationProviderName () { return UrlFactory::kCopernicusElevationProviderKey; }
QString elevationProviderNotice () { return UrlFactory::kCopernicusElevationProviderNotice; }

bool singleFirmwareSupport ();
bool singleVehicleSupport ();
bool px4ProFirmwareSupported ();
Expand Down
20 changes: 14 additions & 6 deletions src/QtLocationPlugin/ElevationMapProvider.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -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;
Expand Down
5 changes: 2 additions & 3 deletions src/QtLocationPlugin/ElevationMapProvider.h
Original file line number Diff line number Diff line change
Expand Up @@ -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) {}

Expand All @@ -42,4 +42,3 @@ class AirmapElevationProvider : public ElevationProvider {
protected:
QString _getURL(const int x, const int y, const int zoom, QNetworkAccessManager* networkManager) override;
};

12 changes: 6 additions & 6 deletions src/QtLocationPlugin/QGCMapEngine.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -200,15 +200,15 @@ QGCMapEngine::addTask(QGCMapTask* task)

//-----------------------------------------------------------------------------
void
QGCMapEngine::cacheTile(QString type, int x, int y, int z, const QByteArray& image, const QString &format, qulonglong set)
QGCMapEngine::cacheTile(const QString& type, int x, int y, int z, const QByteArray& image, const QString &format, qulonglong set)
{
QString hash = getTileHash(type, x, y, z);
cacheTile(type, hash, image, format, set);
}

//-----------------------------------------------------------------------------
void
QGCMapEngine::cacheTile(QString type, const QString& hash, const QByteArray& image, const QString& format, qulonglong set)
QGCMapEngine::cacheTile(const QString& type, const QString& hash, const QByteArray& image, const QString& format, qulonglong set)
{
AppSettings* appSettings = qgcApp()->toolbox()->settingsManager()->appSettings();
//-- If we are allowed to persist data, save tile to cache
Expand All @@ -220,7 +220,7 @@ QGCMapEngine::cacheTile(QString type, const QString& hash, const QByteArray& ima

//-----------------------------------------------------------------------------
QString
QGCMapEngine::getTileHash(QString type, int x, int y, int z)
QGCMapEngine::getTileHash(const QString& type, int x, int y, int z)
{
return QString::asprintf("%010d%08d%08d%03d", getQGCMapEngine()->urlFactory()->getIdFromType(type), x, y, z);
}
Expand All @@ -235,7 +235,7 @@ QGCMapEngine::hashToType(const QString& hash)

//-----------------------------------------------------------------------------
QGCFetchTileTask*
QGCMapEngine::createFetchTileTask(QString type, int x, int y, int z)
QGCMapEngine::createFetchTileTask(const QString& type, int x, int y, int z)
{
QString hash = getTileHash(type, x, y, z);
QGCFetchTileTask* task = new QGCFetchTileTask(hash);
Expand All @@ -244,7 +244,7 @@ QGCMapEngine::createFetchTileTask(QString type, int x, int y, int z)

//-----------------------------------------------------------------------------
QGCTileSet
QGCMapEngine::getTileCount(int zoom, double topleftLon, double topleftLat, double bottomRightLon, double bottomRightLat, QString mapType)
QGCMapEngine::getTileCount(int zoom, double topleftLon, double topleftLat, double bottomRightLon, double bottomRightLat, const QString& mapType)
{
if(zoom < 1) zoom = 1;
if(zoom > MAX_MAP_ZOOM) zoom = MAX_MAP_ZOOM;
Expand Down Expand Up @@ -368,7 +368,7 @@ QGCMapEngine::_pruned()

//-----------------------------------------------------------------------------
int
QGCMapEngine::concurrentDownloads(QString type)
QGCMapEngine::concurrentDownloads(const QString& type)
{
Q_UNUSED(type);
// TODO : We may want different values depending on
Expand Down
16 changes: 8 additions & 8 deletions src/QtLocationPlugin/QGCMapEngine.h
Original file line number Diff line number Diff line change
Expand Up @@ -36,13 +36,13 @@ class QGCMapEngine : public QObject

void init ();
void addTask (QGCMapTask *task);
void cacheTile (QString type, int x, int y, int z, const QByteArray& image, const QString& format, qulonglong set = UINT64_MAX);
void cacheTile (QString type, const QString& hash, const QByteArray& image, const QString& format, qulonglong set = UINT64_MAX);
QGCFetchTileTask* createFetchTileTask (QString type, int x, int y, int z);
void cacheTile (const QString& type, int x, int y, int z, const QByteArray& image, const QString& format, qulonglong set = UINT64_MAX);
void cacheTile (const QString& type, const QString& hash, const QByteArray& image, const QString& format, qulonglong set = UINT64_MAX);
QGCFetchTileTask* createFetchTileTask (const QString& type, int x, int y, int z);
QStringList getMapNameList ();
const QString userAgent () { return _userAgent; }
void setUserAgent (const QString& ua) { _userAgent = ua; }
QString hashToType (const QString& hash);
QString hashToType (const QString& hash);
quint32 getMaxDiskCache ();
void setMaxDiskCache (quint32 size);
quint32 getMaxMemCache ();
Expand All @@ -56,13 +56,13 @@ class QGCMapEngine : public QObject
UrlFactory* urlFactory () { return _urlFactory; }

//-- Tile Math
static QGCTileSet getTileCount (int zoom, double topleftLon, double topleftLat, double bottomRightLon, double bottomRightLat, QString mapType);
static QString getTileHash (QString type, int x, int y, int z);
static QString getTypeFromName (const QString &name);
static QGCTileSet getTileCount (int zoom, double topleftLon, double topleftLat, double bottomRightLon, double bottomRightLat, const QString& mapType);
static QString getTileHash (const QString& type, int x, int y, int z);
static QString getTypeFromName (const QString& name);
static QString bigSizeToString (quint64 size);
static QString storageFreeSizeToString(quint64 size_MB);
static QString numberToString (quint64 number);
static int concurrentDownloads (QString type);
static int concurrentDownloads (const QString& type);

private slots:
void _updateTotals (quint32 totaltiles, quint64 totalsize, quint32 defaulttiles, quint64 defaultsize);
Expand Down
2 changes: 1 addition & 1 deletion src/QtLocationPlugin/QGCMapEngineData.h
Original file line number Diff line number Diff line change
Expand Up @@ -76,7 +76,7 @@ class QGCCacheTile : public QObject
{
Q_OBJECT
public:
QGCCacheTile (const QString hash, const QByteArray img, const QString format, QString type, qulonglong set = UINT64_MAX)
QGCCacheTile (const QString& hash, const QByteArray& img, const QString& format, const QString& type, qulonglong set = UINT64_MAX)
: _set(set)
, _hash(hash)
, _img(img)
Expand Down
2 changes: 1 addition & 1 deletion src/QtLocationPlugin/QGCMapTileSet.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -287,7 +287,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);
Expand Down
32 changes: 20 additions & 12 deletions src/QtLocationPlugin/QGCMapUrlEngine.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -32,6 +32,9 @@ QGC_LOGGING_CATEGORY(QGCMapUrlEngineLog, "QGCMapUrlEngineLog")
#include <QString>
#include <QTimer>

const char* UrlFactory::kCopernicusElevationProviderKey = "Copernicus Elevation";
const char* UrlFactory::kCopernicusElevationProviderNotice = "© Airbus Defence and Space GmbH";

//-----------------------------------------------------------------------------
UrlFactory::UrlFactory() : _timeout(5 * 1000) {

Expand Down Expand Up @@ -71,20 +74,20 @@ UrlFactory::UrlFactory() : _timeout(5 * 1000) {

//_providersTable["MapQuest Map"] = new MapQuestMapMapProvider(this);
//_providersTable["MapQuest Sat"] = new MapQuestSatMapProvider(this);

_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);
_providersTable["Japan-GSI Anaglyph"] = new JapanAnaglyphMapProvider(this);
_providersTable["Japan-GSI Slope"] = new JapanSlopeMapProvider(this);
_providersTable["Japan-GSI Relief"] = new JapanReliefMapProvider(this);

_providersTable["LINZ Basemap"] = new LINZBasemapMapProvider(this);

_providersTable["CustomURL Custom"] = new CustomURLMapProvider(this);
}

Expand All @@ -106,7 +109,7 @@ QString UrlFactory::getImageFormat(int id, const QByteArray& image) {
}

//-----------------------------------------------------------------------------
QString UrlFactory::getImageFormat(QString type, const QByteArray& image) {
QString UrlFactory::getImageFormat(const QString& type, const QByteArray& image) {
if (_providersTable.find(type) != _providersTable.end()) {
return _providersTable[type]->getImageFormat(image);
} else {
Expand All @@ -127,7 +130,7 @@ QNetworkRequest UrlFactory::getTileURL(int id, int x, int y, int zoom,
}

//-----------------------------------------------------------------------------
QNetworkRequest UrlFactory::getTileURL(QString type, int x, int y, int zoom,
QNetworkRequest UrlFactory::getTileURL(const QString& type, int x, int y, int zoom,
QNetworkAccessManager* networkManager) {
if (_providersTable.find(type) != _providersTable.end()) {
return _providersTable[type]->getTileURL(x, y, zoom, networkManager);
Expand All @@ -137,10 +140,10 @@ QNetworkRequest UrlFactory::getTileURL(QString type, int x, int y, int zoom,
}

//-----------------------------------------------------------------------------
quint32 UrlFactory::averageSizeForType(QString type) {
quint32 UrlFactory::averageSizeForType(const QString& type) {
if (_providersTable.find(type) != _providersTable.end()) {
return _providersTable[type]->getAverageSize();
}
}
qCDebug(QGCMapUrlEngineLog) << "UrlFactory::averageSizeForType " << type
<< " Not registered";

Expand Down Expand Up @@ -177,29 +180,34 @@ MapProvider* UrlFactory::getMapProviderFromId(int id)
return nullptr;
}

//-----------------------------------------------------------------------------
// Todo : qHash produce a uint bigger than max(int)
// There is still a low probability for this to
// generate similar hash for different types
int UrlFactory::getIdFromType(QString type) { return (int)(qHash(type)>>1); }
int
UrlFactory::getIdFromType(const QString& type)
{
return (int)(qHash(type)>>1);
}

//-----------------------------------------------------------------------------
int
UrlFactory::long2tileX(QString mapType, double lon, int z)
UrlFactory::long2tileX(const QString& mapType, double lon, int z)
{
return _providersTable[mapType]->long2tileX(lon, z);
}

//-----------------------------------------------------------------------------
int
UrlFactory::lat2tileY(QString mapType, double lat, int z)
UrlFactory::lat2tileY(const QString& mapType, double lat, int z)
{
return _providersTable[mapType]->lat2tileY(lat, z);
}


//-----------------------------------------------------------------------------
QGCTileSet
UrlFactory::getTileCount(int zoom, double topleftLon, double topleftLat, double bottomRightLon, double bottomRightLat, QString mapType)
UrlFactory::getTileCount(int zoom, double topleftLon, double topleftLat, double bottomRightLon, double bottomRightLat, const QString& mapType)
{
return _providersTable[mapType]->getTileCount(zoom, topleftLon, topleftLat, bottomRightLon, bottomRightLat);
}
Expand Down
16 changes: 9 additions & 7 deletions src/QtLocationPlugin/QGCMapUrlEngine.h
Original file line number Diff line number Diff line change
Expand Up @@ -29,30 +29,32 @@
class UrlFactory : public QObject {
Q_OBJECT
public:
static const char* kCopernicusElevationProviderKey;
static const char* kCopernicusElevationProviderNotice;

UrlFactory ();
~UrlFactory ();

QNetworkRequest getTileURL (QString type, int x, int y, int zoom, QNetworkAccessManager* networkManager);
QNetworkRequest getTileURL (const QString& type, int x, int y, int zoom, QNetworkAccessManager* networkManager);
QNetworkRequest getTileURL (int id, int x, int y, int zoom, QNetworkAccessManager* networkManager);

QString getImageFormat (QString type, const QByteArray& image);
QString getImageFormat (const QString& type, const QByteArray& image);
QString getImageFormat (int id , const QByteArray& image);

quint32 averageSizeForType (QString type);
quint32 averageSizeForType (const QString& type);

int long2tileX(QString mapType, double lon, int z);
int lat2tileY(QString mapType, double lat, int z);
int long2tileX(const QString& mapType, double lon, int z);
int lat2tileY(const QString& mapType, double lat, int z);

QHash<QString, MapProvider*> getProviderTable(){return _providersTable;}

int getIdFromType(QString type);
int getIdFromType(const QString& type);
QString getTypeFromId(int id);
MapProvider* getMapProviderFromId(int id);

QGCTileSet getTileCount(int zoom, double topleftLon, double topleftLat,
double bottomRightLon, double bottomRightLat,
QString mapType);
const QString& mapType);

bool isElevation(int mapId);

Expand Down
6 changes: 3 additions & 3 deletions src/QtLocationPlugin/QGCTileCacheWorker.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -329,11 +329,11 @@ QGCCacheWorker::_getTile(QGCMapTask* mtask)
QString s = QString("SELECT tile, format, type FROM Tiles WHERE hash = \"%1\"").arg(task->hash());
if(query.exec(s)) {
if(query.next()) {
QByteArray ar = query.value(0).toByteArray();
QString format = query.value(1).toString();
const QByteArray& arrray = query.value(0).toByteArray();
const QString& format = query.value(1).toString();
QString type = getQGCMapEngine()->urlFactory()->getTypeFromId(query.value(2).toInt());
qCDebug(QGCTileCacheLog) << "_getTile() (Found in DB) HASH:" << task->hash();
QGCCacheTile* tile = new QGCCacheTile(task->hash(), ar, format, type);
QGCCacheTile* tile = new QGCCacheTile(task->hash(), arrray, format, type);
task->setTileFetched(tile);
found = true;
}
Expand Down
2 changes: 1 addition & 1 deletion src/QtLocationPlugin/QMLControl/OfflineMap.qml
Original file line number Diff line number Diff line change
Expand Up @@ -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; }
}
Expand Down
Loading