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

QtLocationPlugin: Add ArduPilot SRTM Elevation Provider #12117

Draft
wants to merge 1 commit into
base: master
Choose a base branch
from
Draft
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
115 changes: 115 additions & 0 deletions src/QtLocationPlugin/Providers/ElevationMapProvider.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -14,6 +14,8 @@

#include "ElevationMapProvider.h"
#include "TerrainTileCopernicus.h"
#include "TerrainTileArduPilot.h"
#include "QGCZip.h"

#include <QtCore/QDir>
#include <QtCore/QTemporaryFile>
Expand Down Expand Up @@ -65,3 +67,116 @@ QByteArray CopernicusElevationProvider::serialize(const QByteArray &image) const
{
return TerrainTileCopernicus::serializeFromData(image);
}

/*===========================================================================*/

int ArduPilotTerrainElevationProvider::long2tileX(double lon, int z) const
{
Q_UNUSED(z)
return static_cast<int>(floor((lon + 180.0) / TerrainTileArduPilot::kTileSizeDegrees));
}

int ArduPilotTerrainElevationProvider::lat2tileY(double lat, int z) const
{
Q_UNUSED(z)
return static_cast<int>(floor((lat + 90.0) / TerrainTileArduPilot::kTileSizeDegrees));
}

QString ArduPilotTerrainElevationProvider::_getURL(int x, int y, int zoom) const
{
Q_UNUSED(zoom)

const int xForUrl = (static_cast<double>(x) * TerrainTileArduPilot::kTileSizeDegrees) - 180.0;
const int yForUrl = (static_cast<double>(y) * TerrainTileArduPilot::kTileSizeDegrees) - 90.0;

if ((xForUrl < -180) || (xForUrl > 180) || (yForUrl < -180) || (yForUrl > 180)) {
qCWarning(MapProviderLog) << "Invalid x or y values for URL generation:" << x << y;
return QString();
}

QString formattedYLat;
if (yForUrl >= 0) {
formattedYLat = QString("N%1").arg(QString::number(yForUrl).rightJustified(2, '0'));
} else {
formattedYLat = QString("S%1").arg(QString::number(-yForUrl).rightJustified(2, '0'));
}

QString formattedXLong;
if (xForUrl >= 0) {
formattedXLong = QString("E%1").arg(QString::number(xForUrl).rightJustified(3, '0'));
} else {
formattedXLong = QString("W%1").arg(QString::number(-xForUrl).rightJustified(3, '0'));
}

const QString url = _mapUrl.arg(formattedYLat, formattedXLong);
return url;
}

QGCTileSet ArduPilotTerrainElevationProvider::getTileCount(int zoom, double topleftLon,
double topleftLat, double bottomRightLon,
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;
}

QByteArray ArduPilotTerrainElevationProvider::serialize(const QByteArray &image) const
{
QTemporaryFile tempFile;
tempFile.setFileTemplate(QDir::tempPath() + "/XXXXXX.zip");

if (!tempFile.open()) {
qCDebug(MapProviderLog) << "Could not create temporary file for zip data.";
return QByteArray();
}

if (tempFile.write(image) != image.size()) {
qCDebug(MapProviderLog) << "Incorrect number of bytes written.";
}
tempFile.close();

// QTemporaryDir
const QString outputDirectoryPath = QDir::tempPath() + "/QGC/Location/Elevation/SRTM1";
QDir outputDirectory(outputDirectoryPath);
if (!outputDirectory.exists()) {
if (!outputDirectory.mkpath(outputDirectoryPath)) {
return QByteArray();
}
}

if (!QGCZip::unzipFile(tempFile.fileName(), outputDirectoryPath)) {
qCDebug(MapProviderLog) << "Unzipping failed!";
return QByteArray();
}

const QStringList files = outputDirectory.entryList(QDir::Files);
if (files.isEmpty()) {
qCDebug(MapProviderLog) << "No files found in the unzipped directory!";
return QByteArray();
}

const QString filename = files.constFirst();
const QString unzippedFilePath = outputDirectoryPath + "/" + filename;
QFile file(unzippedFilePath);
if (!file.open(QIODevice::ReadOnly)) {
qCDebug(MapProviderLog) << "Could not open unzipped file for reading:" << unzippedFilePath;
return QByteArray();
}

const QByteArray result = file.readAll();
file.close();

return TerrainTileArduPilot::serializeFromData(filename, result);
}
35 changes: 35 additions & 0 deletions src/QtLocationPlugin/Providers/ElevationMapProvider.h
Original file line number Diff line number Diff line change
Expand Up @@ -28,6 +28,8 @@ class ElevationProvider : public MapProvider
virtual QByteArray serialize(const QByteArray &image) const = 0;
};

/*===========================================================================*/

/// https://spacedata.copernicus.eu/collections/copernicus-digital-elevation-model
class CopernicusElevationProvider : public ElevationProvider
{
Expand Down Expand Up @@ -59,3 +61,36 @@ class CopernicusElevationProvider : public ElevationProvider

const QString _mapUrl = QString(kProviderURL) + QStringLiteral("/api/v1/carpet?points=%1,%2,%3,%4");
};

/*===========================================================================*/

class ArduPilotTerrainElevationProvider : public ElevationProvider
{
public:
ArduPilotTerrainElevationProvider()
: ElevationProvider(
kProviderKey,
kProviderURL,
QStringLiteral("hgt"),
kAvgElevSize,
QGeoMapType::TerrainMap) {}

int long2tileX(double lon, int z) const final;
int lat2tileY(double lat, int z) const final;

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

QByteArray serialize(const QByteArray &image) const final;

static constexpr const char *kProviderKey = "ArduPilot SRTM1";
static constexpr const char *kProviderNotice = "© ArduPilot.org";
static constexpr const char *kProviderURL = "https://terrain.ardupilot.org/SRTM1";
static constexpr quint32 kAvgElevSize = 50000;

private:
QString _getURL(int x, int y, int zoom) const final;

const QString _mapUrl = QString(kProviderURL) + QStringLiteral("/%1%2.hgt.zip");
};
2 changes: 1 addition & 1 deletion src/QtLocationPlugin/QGCCachedTileSet.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -216,7 +216,7 @@ void QGCCachedTileSet::_networkReplyFinished()
return;
}

const QString type = UrlFactory::tileHashToType(hash);
const QString type = UrlFactory::tileHashToType(hash); // TODO: Type is null for elevation
const SharedMapProvider mapProvider = UrlFactory::getMapProviderFromProviderType(type);
Q_CHECK_PTR(mapProvider);

Expand Down
3 changes: 2 additions & 1 deletion src/QtLocationPlugin/QGCMapUrlEngine.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -72,7 +72,8 @@ const QList<SharedMapProvider> UrlFactory::_providers = {

std::make_shared<CustomURLMapProvider>(),

std::make_shared<CopernicusElevationProvider>()
std::make_shared<CopernicusElevationProvider>(),
std::make_shared<ArduPilotTerrainElevationProvider>()
};

QString UrlFactory::getImageFormat(int qtMapId, QByteArrayView image)
Expand Down
5 changes: 5 additions & 0 deletions src/Terrain/CMakeLists.txt
Original file line number Diff line number Diff line change
@@ -1,8 +1,12 @@
find_package(Qt6 REQUIRED COMPONENTS Core Location Network Positioning)

qt_add_library(Terrain STATIC
Providers/TerrainQueryArduPilot.cc
Providers/TerrainQueryArduPilot.h
Providers/TerrainQueryCopernicus.cc
Providers/TerrainQueryCopernicus.h
Providers/TerrainTileArduPilot.cc
Providers/TerrainTileArduPilot.h
Providers/TerrainTileCopernicus.cc
Providers/TerrainTileCopernicus.h
TerrainQuery.cc
Expand All @@ -18,6 +22,7 @@ qt_add_library(Terrain STATIC
target_link_libraries(Terrain
PRIVATE
Qt6::LocationPrivate
Compression
QGCLocation
Utilities
PUBLIC
Expand Down
131 changes: 131 additions & 0 deletions src/Terrain/Providers/TerrainQueryArduPilot.cc
Original file line number Diff line number Diff line change
@@ -0,0 +1,131 @@
/****************************************************************************
*
* (c) 2009-2020 QGROUNDCONTROL PROJECT <http://www.qgroundcontrol.org>
*
* QGroundControl is licensed according to the terms in the file
* COPYING.md in the root of the source code directory.
*
****************************************************************************/

#include "TerrainQueryArduPilot.h"
#include "TerrainTileArduPilot.h"
#include "ElevationMapProvider.h"
#include "QGCFileDownload.h"
#include "QGCLoggingCategory.h"
#include "QGCMapUrlEngine.h"
#include "QGCZip.h"

#include <QtCore/QDir>
#include <QtCore/QStandardPaths>
#include <QtCore/QUrl>
#include <QtCore/QUrlQuery>
#include <QtNetwork/QNetworkAccessManager>
#include <QtNetwork/QNetworkReply>
#include <QtNetwork/QNetworkRequest>
#include <QtNetwork/QSslConfiguration>
#include <QtPositioning/QGeoCoordinate>

QGC_LOGGING_CATEGORY(TerrainQueryArduPilotLog, "qgc.terrain.terrainqueryardupilot")

TerrainQueryArduPilot::TerrainQueryArduPilot(QObject *parent)
: TerrainOnlineQuery(parent)
{
// qCDebug(TerrainQueryArduPilotLog) << Q_FUNC_INFO << this;
}

TerrainQueryArduPilot::~TerrainQueryArduPilot()
{
// qCDebug(TerrainQueryArduPilotLog) << Q_FUNC_INFO << this;
}

void TerrainQueryArduPilot::requestCoordinateHeights(const QList<QGeoCoordinate> &coordinates)
{
if (coordinates.isEmpty()) {
return;
}

_queryMode = TerrainQuery::QueryModeCoordinates;

QSet<QUrl> urls;
urls.reserve(coordinates.size());

const SharedMapProvider provider = UrlFactory::getMapProviderFromProviderType(QString(ArduPilotTerrainElevationProvider::kProviderKey));
for (const QGeoCoordinate &coord : coordinates) {
if (!coord.isValid()) {
continue;
}
const int x = provider->long2tileX(coord.longitude(), 1);
const int y = provider->lat2tileY(coord.latitude(), 1);
const QUrl url = provider->getTileURL(x, y, 1);
(void) urls.insert(url);
}

const QList <QUrl> urlList = urls.values();
for (const QUrl &url : urlList) {
_sendQuery(url);
}
}

void TerrainQueryArduPilot::_sendQuery(const QUrl &url)
{
qCDebug(TerrainQueryArduPilotLog) << Q_FUNC_INFO << url;

QGCFileDownload *const download = new QGCFileDownload(this);
(void) connect(download, &QGCFileDownload::downloadComplete, this, &TerrainQueryArduPilot::_parseZipFile);
(void) connect(download, &QGCFileDownload::downloadComplete, download, &QGCFileDownload::deleteLater);
if (!download->download(url.toString())) {
qCWarning(TerrainQueryArduPilotLog) << "Failed To Download File";
_requestFailed();
}
}

void TerrainQueryArduPilot::_parseZipFile(const QString &remoteFile, const QString &localFile, const QString &errorMsg)
{
if (!errorMsg.isEmpty()) {
qCWarning(TerrainQueryArduPilotLog) << "Error During Download:" << errorMsg;
_requestFailed();
return;
}

// TODO: verify .endsWith(".hgt")

const QString outputDirectoryPath = QDir(QStandardPaths::writableLocation(QStandardPaths::TempLocation)).path() + "/QGC/SRTM1";
if (!QGCZip::unzipFile(localFile, outputDirectoryPath)) {
qCWarning(TerrainQueryArduPilotLog) << "Failed To Unzip File" << localFile;
_requestFailed();
return;
}

QFile file(outputDirectoryPath + "/" + localFile);
if (!file.open(QIODevice::ReadOnly)) {
qCWarning(TerrainQueryArduPilotLog) << "Failed To Unzip File" << localFile;
_requestFailed();
return;
}

const QByteArray hgtData = file.readAll();
file.close();

qCDebug(TerrainQueryArduPilotLog) << Q_FUNC_INFO << "success";
switch (_queryMode) {
case TerrainQuery::QueryModeCoordinates:
_parseCoordinateData(localFile, hgtData);
break;
default:
qCWarning(TerrainQueryArduPilotLog) << Q_FUNC_INFO << "Query Mode Not Supported";
break;
}
}

void TerrainQueryArduPilot::_parseCoordinateData(const QString &localFile, const QByteArray &hgtData)
{
const QList<QGeoCoordinate> coordinates = TerrainTileArduPilot::parseCoordinateData(localFile, hgtData);

QList<double> heights;
heights.reserve(coordinates.size());
for (const QGeoCoordinate &coord: coordinates) {
heights.append(coord.altitude());
}

emit coordinateHeightsReceived(!heights.isEmpty(), heights);
}
35 changes: 35 additions & 0 deletions src/Terrain/Providers/TerrainQueryArduPilot.h
Original file line number Diff line number Diff line change
@@ -0,0 +1,35 @@
/****************************************************************************
*
* (c) 2009-2020 QGROUNDCONTROL PROJECT <http://www.qgroundcontrol.org>
*
* QGroundControl is licensed according to the terms in the file
* COPYING.md in the root of the source code directory.
*
****************************************************************************/

#pragma once

#include <QtCore/QLoggingCategory>
#include <QtCore/QObject>

#include "TerrainQueryInterface.h"

Q_DECLARE_LOGGING_CATEGORY(TerrainQueryArduPilotLog)

class QGeoCoordinate;

class TerrainQueryArduPilot : public TerrainOnlineQuery
{
Q_OBJECT

public:
explicit TerrainQueryArduPilot(QObject *parent = nullptr);
~TerrainQueryArduPilot();

void requestCoordinateHeights(const QList<QGeoCoordinate> &coordinates) final;

private:
void _sendQuery(const QUrl &path);
void _parseZipFile(const QString &remoteFile, const QString &localFile, const QString &errorMsg);
void _parseCoordinateData(const QString &localFile, const QByteArray &hgtData);
};
Loading
Loading