Skip to content

Commit

Permalink
QtLocationPlugin: Add Elevation Provider Selection
Browse files Browse the repository at this point in the history
  • Loading branch information
HTRamsey committed Sep 7, 2024
1 parent 990189b commit 22e143e
Show file tree
Hide file tree
Showing 20 changed files with 216 additions and 82 deletions.
7 changes: 4 additions & 3 deletions src/QmlControls/QGroundControlQmlGlobal.cc
Original file line number Diff line number Diff line change
Expand Up @@ -11,9 +11,10 @@
#include "QGCApplication.h"
#include "LinkManager.h"
#include "MAVLinkProtocol.h"
#include "ElevationMapProvider.h"
#include "FirmwarePluginManager.h"
#include "AppSettings.h"
#include "FlightMapSettings.h"
#include "SettingsManager.h"
#include "PositionManager.h"
#include "QGCMapEngineManager.h"
#include "ADSBVehicleManager.h"
Expand Down Expand Up @@ -335,12 +336,12 @@ int QGroundControlQmlGlobal::mavlinkSystemID()

QString QGroundControlQmlGlobal::elevationProviderName()
{
return CopernicusElevationProvider::kProviderKey;
return _settingsManager->flightMapSettings()->elevationMapProvider()->rawValue().toString();
}

QString QGroundControlQmlGlobal::elevationProviderNotice()
{
return CopernicusElevationProvider::kProviderNotice;
return _settingsManager->flightMapSettings()->elevationMapProvider()->rawValue().toString();
}

QString QGroundControlQmlGlobal::parameterFileExtension() const
Expand Down
4 changes: 2 additions & 2 deletions src/QmlControls/QGroundControlQmlGlobal.h
Original file line number Diff line number Diff line change
Expand Up @@ -218,8 +218,8 @@ class QGroundControlQmlGlobal : public QGCTool
bool hasMAVLinkInspector () { return true; }
#endif

static QString elevationProviderName ();
static QString elevationProviderNotice ();
QString elevationProviderName ();
QString elevationProviderNotice ();

bool singleFirmwareSupport ();
bool singleVehicleSupport ();
Expand Down
56 changes: 56 additions & 0 deletions src/QtLocationPlugin/ElevationMapProvider.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -61,3 +61,59 @@ QByteArray CopernicusElevationProvider::serialize(const QByteArray &image) const
{
return TerrainTileCopernicus::serializeFromJson(image);
}

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

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

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

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

// 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;

const QString formattedStringYLat = (yForUrl > 0) ? QStringLiteral("N%1").arg(QString::number(yForUrl).rightJustified(2, '0')) :
QStringLiteral("S%1").arg(QString::number(-yForUrl).rightJustified(2, '0'));

const QString formattedStringXLong = (xForUrl > 0) ? QStringLiteral("E%1").arg(QString::number(xForUrl).rightJustified(3, '0')) :
QStringLiteral("W%1").arg(QString::number(-xForUrl).rightJustified(3, '0'));

return _mapUrl.arg(formattedStringYLat, formattedStringXLong);
}

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
{
return TerrainTileCopernicus::serializeFromJson(image);
}
32 changes: 31 additions & 1 deletion src/QtLocationPlugin/ElevationMapProvider.h
Original file line number Diff line number Diff line change
Expand Up @@ -2,7 +2,8 @@

#include "MapProvider.h"

static constexpr const quint32 AVERAGE_COPERNICUS_ELEV_SIZE = 2786;
static constexpr quint32 AVERAGE_COPERNICUS_ELEV_SIZE = 2786;
static constexpr quint32 AVERAGE_ARDUPILOT_ELEV_SIZE = 100000;

class ElevationProvider : public MapProvider
{
Expand Down Expand Up @@ -49,3 +50,32 @@ class CopernicusElevationProvider : public ElevationProvider

const QString _mapUrl = QStringLiteral("https://terrain-ce.suite.auterion.com/api/v1/carpet?points=%1,%2,%3,%4");
};

class ArduPilotTerrainElevationProvider : public ElevationProvider
{
public:
ArduPilotTerrainElevationProvider()
: ElevationProvider(
QStringLiteral("ArduPilot Terrain Elevation"),
QStringLiteral("https://terrain.ardupilot.org/SRTM1/"),
QStringLiteral("hgt"),
AVERAGE_ARDUPILOT_ELEV_SIZE,
QGeoMapType::StreetMap) {}

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 Terrain Elevation";
static constexpr const char *kProviderNotice = "© ArduPilot.org";

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

const QString _mapUrl = QStringLiteral("https://terrain.ardupilot.org/SRTM1/%1%2.hgt.zip");
};
1 change: 0 additions & 1 deletion src/QtLocationPlugin/QGCCachedTileSet.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -28,7 +28,6 @@
#include <QGCApplication.h>
#include <QGCFileDownload.h>
#include <QGCLoggingCategory.h>
#include <TerrainTile.h>

#include <QtNetwork/QNetworkProxy>

Expand Down
13 changes: 13 additions & 0 deletions src/QtLocationPlugin/QGCMapUrlEngine.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -63,6 +63,7 @@ const QList<SharedMapProvider> UrlFactory::_providers = {
std::make_shared<VWorldSatMapProvider>(),

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

std::make_shared<JapanStdMapProvider>(),
std::make_shared<JapanSeamlessMapProvider>(),
Expand Down Expand Up @@ -229,6 +230,18 @@ int UrlFactory::getQtMapIdFromProviderType(QStringView type)
return -1;
}

QStringList UrlFactory::getElevationProviderTypes()
{
QStringList types;
for (const SharedMapProvider &provider : _providers) {
if (provider->isElevationProvider()) {
(void) types.append(provider->getMapName());
}
}

return types;
}

QStringList UrlFactory::getProviderTypes()
{
QStringList types;
Expand Down
1 change: 1 addition & 0 deletions src/QtLocationPlugin/QGCMapUrlEngine.h
Original file line number Diff line number Diff line change
Expand Up @@ -45,6 +45,7 @@ class UrlFactory
QStringView mapType);

static const QList<std::shared_ptr<const MapProvider>>& getProviders() { return _providers; }
static QStringList getElevationProviderTypes();
static QStringList getProviderTypes();
static int getQtMapIdFromProviderType(QStringView type);
static QString getProviderTypeFromQtMapId(int qtMapId);
Expand Down
26 changes: 18 additions & 8 deletions src/QtLocationPlugin/QMLControl/QGCMapEngineManager.cc
Original file line number Diff line number Diff line change
Expand Up @@ -18,6 +18,8 @@
#include "ElevationMapProvider.h"
#include "QmlObjectListModel.h"
#include "QGCApplication.h"
#include "QGCToolbox.h"
#include "SettingsManager.h"
#include "QGCLoggingCategory.h"

#include <QtCore/qapplicationstatic.h>
Expand All @@ -28,9 +30,6 @@

QGC_LOGGING_CATEGORY(QGCMapEngineManagerLog, "qgc.qtlocation.qmlcontrol.qgcmapenginemanagerlog")

static const QString kQmlOfflineMapKeyName = QStringLiteral("QGCOfflineMap");
static const QString kElevationMapType = QString(CopernicusElevationProvider::kProviderKey); // TODO: Variable Elevation Provider Type

Q_APPLICATION_STATIC(QGCMapEngineManager, _mapEngineManager);

QGCMapEngineManager *QGCMapEngineManager::instance()
Expand Down Expand Up @@ -76,7 +75,8 @@ void QGCMapEngineManager::updateForCurrentView(double lon0, double lat0, double
}

if (_fetchElevation) {
const QGCTileSet set = UrlFactory::getTileCount(1, lon0, lat0, lon1, lat1, kElevationMapType);
const QString elevationProviderName = qgcApp()->toolbox()->settingsManager()->flightMapSettings()->elevationMapProvider()->rawValue().toString();
const QGCTileSet set = UrlFactory::getTileCount(1, lon0, lat0, lon1, lat1, elevationProviderName);
_elevationSet += set;
}

Expand Down Expand Up @@ -143,9 +143,11 @@ void QGCMapEngineManager::startDownload(const QString &name, const QString &mapT
qCWarning(QGCMapEngineManagerLog) << Q_FUNC_INFO << "No Tiles to save";
}

if ((mapType != kElevationMapType) && _fetchElevation) {
const int mapid = UrlFactory::getQtMapIdFromProviderType(mapType);
if (_fetchElevation && !UrlFactory::isElevation(mapid)) {
QGCCachedTileSet* const set = new QGCCachedTileSet(name + QStringLiteral(" Elevation"));
set->setMapTypeStr(kElevationMapType);
const QString elevationProviderName = qgcApp()->toolbox()->settingsManager()->flightMapSettings()->elevationMapProvider()->rawValue().toString();
set->setMapTypeStr(elevationProviderName);
set->setTopleftLat(_topleftLat);
set->setTopleftLon(_topleftLon);
set->setBottomRightLat(_bottomRightLat);
Expand All @@ -154,7 +156,7 @@ void QGCMapEngineManager::startDownload(const QString &name, const QString &mapT
set->setMaxZoom(1);
set->setTotalTileSize(_elevationSet.tileSize);
set->setTotalTileCount(static_cast<quint32>(_elevationSet.tileCount));
set->setType(kElevationMapType);
set->setType(elevationProviderName);

QGCCreateTileSetTask* const task = new QGCCreateTileSetTask(set);
(void) connect(task, &QGCCreateTileSetTask::tileSetSaved, this, &QGCMapEngineManager::_tileSetSaved);
Expand Down Expand Up @@ -458,11 +460,19 @@ QStringList QGCMapEngineManager::mapList()
QStringList QGCMapEngineManager::mapProviderList()
{
QStringList mapStringList = mapList();
(void) mapStringList.removeAll(CopernicusElevationProvider::kProviderKey);
const QStringList elevationStringList = elevationProviderList();
for (const QString &elevationProviderName : elevationStringList) {
(void) mapStringList.removeAll(elevationProviderName);
}

static const QRegularExpression providerType = QRegularExpression(QStringLiteral("^([^\\ ]*) (.*)$"));
(void) mapStringList.replaceInStrings(providerType,"\\1");
(void) mapStringList.removeDuplicates();

return mapStringList;
}

QStringList QGCMapEngineManager::elevationProviderList()
{
return UrlFactory::getElevationProviderTypes();
}
28 changes: 16 additions & 12 deletions src/QtLocationPlugin/QMLControl/QGCMapEngineManager.h
Original file line number Diff line number Diff line change
Expand Up @@ -32,17 +32,18 @@ class QGCMapEngineManager : public QObject
Q_MOC_INCLUDE("QmlObjectListModel.h")
Q_MOC_INCLUDE("QGCCachedTileSet.h")

Q_PROPERTY(bool fetchElevation MEMBER _fetchElevation NOTIFY fetchElevationChanged)
Q_PROPERTY(bool importReplace MEMBER _importReplace NOTIFY importReplaceChanged)
Q_PROPERTY(ImportAction importAction READ importAction WRITE setImportAction NOTIFY importActionChanged)
Q_PROPERTY(int actionProgress READ actionProgress NOTIFY actionProgressChanged)
Q_PROPERTY(int selectedCount READ selectedCount NOTIFY selectedCountChanged)
Q_PROPERTY(QmlObjectListModel *tileSets READ tileSets NOTIFY tileSetsChanged)
Q_PROPERTY(QString errorMessage READ errorMessage NOTIFY errorMessageChanged)
Q_PROPERTY(QString tileCountStr READ tileCountStr NOTIFY tileCountChanged)
Q_PROPERTY(QString tileSizeStr READ tileSizeStr NOTIFY tileSizeChanged)
Q_PROPERTY(QStringList mapList READ mapList CONSTANT)
Q_PROPERTY(QStringList mapProviderList READ mapProviderList CONSTANT)
Q_PROPERTY(bool fetchElevation MEMBER _fetchElevation NOTIFY fetchElevationChanged)
Q_PROPERTY(bool importReplace MEMBER _importReplace NOTIFY importReplaceChanged)
Q_PROPERTY(ImportAction importAction READ importAction WRITE setImportAction NOTIFY importActionChanged)
Q_PROPERTY(int actionProgress READ actionProgress NOTIFY actionProgressChanged)
Q_PROPERTY(int selectedCount READ selectedCount NOTIFY selectedCountChanged)
Q_PROPERTY(QmlObjectListModel *tileSets READ tileSets NOTIFY tileSetsChanged)
Q_PROPERTY(QString errorMessage READ errorMessage NOTIFY errorMessageChanged)
Q_PROPERTY(QString tileCountStr READ tileCountStr NOTIFY tileCountChanged)
Q_PROPERTY(QString tileSizeStr READ tileSizeStr NOTIFY tileSizeChanged)
Q_PROPERTY(QStringList mapList READ mapList CONSTANT)
Q_PROPERTY(QStringList mapProviderList READ mapProviderList CONSTANT)
Q_PROPERTY(QStringList elevationProviderList READ elevationProviderList CONSTANT)
Q_PROPERTY(quint32 diskSpace READ diskSpace)
Q_PROPERTY(quint32 freeDiskSpace READ freeDiskSpace NOTIFY freeDiskSpaceChanged)
Q_PROPERTY(quint64 tileCount READ tileCount NOTIFY tileCountChanged)
Expand Down Expand Up @@ -97,6 +98,7 @@ class QGCMapEngineManager : public QObject

static QStringList mapList();
static QStringList mapProviderList();
static QStringList elevationProviderList();

signals:
void actionProgressChanged();
Expand All @@ -123,7 +125,7 @@ private slots:
void _updateTotals(quint32 totaltiles, quint64 totalsize, quint32 defaulttiles, quint64 defaultsize);

private:
void _updateDiskFreeSpace();
void _updateDiskFreeSpace();

QmlObjectListModel *_tileSets = nullptr;
QGCTileSet _imageSet;
Expand All @@ -142,4 +144,6 @@ private slots:
QString _errorMessage;
bool _fetchElevation = true;
bool _importReplace = false;

static constexpr const char *kQmlOfflineMapKeyName = "QGCOfflineMap";
};
6 changes: 6 additions & 0 deletions src/Settings/FlightMap.SettingsGroup.json
Original file line number Diff line number Diff line change
Expand Up @@ -14,6 +14,12 @@
"shortDesc": "Currently selected map type for flight maps",
"type": "string",
"default": "Hybrid"
},
{
"name": "elevationMapProvider",
"shortDesc": "Currently selected elevation map provider",
"type": "string",
"default": "Copernicus Elevation"
}
]
}
1 change: 1 addition & 0 deletions src/Settings/FlightMapSettings.cc
Original file line number Diff line number Diff line change
Expand Up @@ -18,3 +18,4 @@ DECLARE_SETTINGGROUP(FlightMap, "FlightMap")

DECLARE_SETTINGSFACT(FlightMapSettings, mapProvider)
DECLARE_SETTINGSFACT(FlightMapSettings, mapType)
DECLARE_SETTINGSFACT(FlightMapSettings, elevationMapProvider)
2 changes: 1 addition & 1 deletion src/Settings/FlightMapSettings.h
Original file line number Diff line number Diff line change
Expand Up @@ -22,5 +22,5 @@ class FlightMapSettings : public SettingsGroup
DEFINE_SETTING_NAME_GROUP()
DEFINE_SETTINGFACT(mapProvider)
DEFINE_SETTINGFACT(mapType)

DEFINE_SETTINGFACT(elevationMapProvider)
};
6 changes: 3 additions & 3 deletions src/Terrain/TerrainQuery.cc
Original file line number Diff line number Diff line change
Expand Up @@ -8,7 +8,7 @@
****************************************************************************/

#include "TerrainQuery.h"
#include "TerrainQueryAirMap.h"
#include "TerrainQueryInterface.h"
#include "TerrainTileManager.h"
#include "QGCLoggingCategory.h"

Expand All @@ -22,7 +22,7 @@ Q_GLOBAL_STATIC(TerrainAtCoordinateBatchManager, _terrainAtCoordinateBatchManage
TerrainAtCoordinateBatchManager::TerrainAtCoordinateBatchManager(QObject *parent)
: QObject(parent)
, _batchTimer(new QTimer(this))
, _terrainQuery(new TerrainOfflineAirMapQuery(this))
, _terrainQuery(new TerrainOfflineQuery(this))
{
// qCDebug(TerrainQueryLog) << Q_FUNC_INFO << this;

Expand Down Expand Up @@ -225,7 +225,7 @@ void TerrainAtCoordinateQuery::signalTerrainData(bool success, const QList<doubl
TerrainPathQuery::TerrainPathQuery(bool autoDelete, QObject *parent)
: QObject(parent)
, _autoDelete(autoDelete)
, _terrainQuery(new TerrainOfflineAirMapQuery(this))
, _terrainQuery(new TerrainOfflineQuery(this))
{
// qCDebug(AudioOutputLog) << Q_FUNC_INFO << this;

Expand Down
Loading

0 comments on commit 22e143e

Please sign in to comment.