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

[DRAFT] Include support for Ardupilot terrain servers as elevation data source #10715

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

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Jump to
Jump to file
Failed to load files.
Diff view
Diff view
14 changes: 13 additions & 1 deletion src/FlightDisplay/FlyViewMap.qml
Original file line number Diff line number Diff line change
Expand Up @@ -588,11 +588,23 @@ FlightMap {
globals.guidedControllerFlyView.confirmAction(globals.guidedControllerFlyView.actionROI, clickMenu.coord, roiLocationItem)
}
}

QGCButton {
Layout.fillWidth: true
text: "Set home here"
visible: globals.guidedControllerFlyView.showSetHome
onClicked: {
if (clickMenu.opened) {
clickMenu.close()
}
globals.guidedControllerFlyView.confirmAction(globals.guidedControllerFlyView.actionSetHome, clickMenu.coord)
}
}
}
}

onClicked: {
if (!globals.guidedControllerFlyView.guidedUIVisible && (globals.guidedControllerFlyView.showGotoLocation || globals.guidedControllerFlyView.showOrbit || globals.guidedControllerFlyView.showROI)) {
if (!globals.guidedControllerFlyView.guidedUIVisible && (globals.guidedControllerFlyView.showGotoLocation || globals.guidedControllerFlyView.showOrbit || globals.guidedControllerFlyView.showROI || globals.guidedControllerFlyView.showSetHome)) {
orbitMapCircle.hide()
gotoLocationItem.hide()
var clickCoord = _root.toCoordinate(Qt.point(mouse.x, mouse.y), false /* clipToViewPort */)
Expand Down
12 changes: 12 additions & 0 deletions src/FlightDisplay/GuidedActionsController.qml
Original file line number Diff line number Diff line change
Expand Up @@ -55,6 +55,7 @@ Item {
readonly property string gotoTitle: qsTr("Go To Location")
readonly property string vtolTransitionTitle: qsTr("VTOL Transition")
readonly property string roiTitle: qsTr("ROI")
readonly property string setHomeTitle: qsTr("Set Home")
readonly property string actionListTitle: qsTr("Action")

readonly property string armMessage: qsTr("Arm the vehicle.")
Expand All @@ -79,6 +80,7 @@ Item {
readonly property string vtolTransitionFwdMessage: qsTr("Transition VTOL to fixed wing flight.")
readonly property string vtolTransitionMRMessage: qsTr("Transition VTOL to multi-rotor flight.")
readonly property string roiMessage: qsTr("Make the specified location a Region Of Interest.")
readonly property string setHomeMessage: qsTr("Set vehicle home as the specified location. This will affect Return to Home position")

readonly property int actionRTL: 1
readonly property int actionLand: 2
Expand All @@ -105,6 +107,7 @@ Item {
readonly property int actionActionList: 23
readonly property int actionForceArm: 24
readonly property int actionChangeSpeed: 25
readonly property int actionSetHome: 26

property var _activeVehicle: QGroundControl.multiVehicleManager.activeVehicle
property bool _useChecklist: QGroundControl.settingsManager.appSettings.useChecklist.rawValue && QGroundControl.corePlugin.options.preFlightChecklistUrl.toString().length
Expand All @@ -130,6 +133,7 @@ Item {
property bool showROI: _guidedActionsEnabled && _vehicleFlying && __roiSupported && !_missionActive
property bool showLandAbort: _guidedActionsEnabled && _vehicleFlying && _fixedWingOnApproach
property bool showGotoLocation: _guidedActionsEnabled && _vehicleFlying
property bool showSetHome: _guidedActionsEnabled
property bool showActionList: _guidedActionsEnabled && (showStartMission || showResumeMission || showChangeAlt || showLandAbort || actionList.hasCustomActions)
property string changeSpeedTitle: _fixedWing ? changeAirspeedTitle : changeCruiseSpeedTitle
property string changeSpeedMessage: _fixedWing ? changeAirspeedMessage : changeCruiseSpeedMessage
Expand Down Expand Up @@ -496,6 +500,11 @@ Item {
confirmDialog.message = changeSpeedMessage
guidedValueSlider.visible = true
break
case actionSetHome:
confirmDialog.title = setHomeTitle
confirmDialog.message = setHomeMessage
confirmDialog.hideTrigger = Qt.binding(function() { return !showSetHome })
break
default:
console.warn("Unknown actionCode", actionCode)
return
Expand Down Expand Up @@ -585,6 +594,9 @@ Item {
}
}
break
case actionSetHome:
_activeVehicle.doSetHome(actionData)
break
default:
console.warn(qsTr("Internal error: unknown actionCode"), actionCode)
break
Expand Down
85 changes: 83 additions & 2 deletions src/QtLocationPlugin/ElevationMapProvider.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -6,8 +6,8 @@
#include "QGCMapEngine.h"
#include "TerrainTile.h"

ElevationProvider::ElevationProvider(const QString& imageFormat, quint32 averageSize, QGeoMapType::MapStyle mapType, QObject* parent)
: MapProvider(QStringLiteral("https://api.airmap.com/"), imageFormat, averageSize, mapType, parent) {}
ElevationProvider::ElevationProvider(const QString& imageFormat, quint32 averageSize, QGeoMapType::MapStyle mapType, const QString &referrer, QObject* parent)
: MapProvider(referrer, imageFormat, averageSize, mapType, parent) {}

//-----------------------------------------------------------------------------
int AirmapElevationProvider::long2tileX(const double lon, const int z) const {
Expand Down Expand Up @@ -49,3 +49,84 @@ QGCTileSet AirmapElevationProvider::getTileCount(const int zoom, const double to

return set;
}

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)
return static_cast<int>(floor((lon + 180.0)));
}

//-----------------------------------------------------------------------------
int ApStr1ElevationProvider::lat2tileY(const double lat, const int z) const {
Q_UNUSED(z)
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 formattedStringYLat;
QString formattedStringXLong;

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

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

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

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

qDebug() << "Ardupilot string: " << urlString;

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

QByteArray ApStr1ElevationProvider::unzipTile(QByteArray response) {

// This is not working, we need to use a proper zip library like zlib

int decompressedSize = 25000000; // Uncompressed AP terrain files STR1 are aprox 25 Mb.
response.prepend((unsigned char)((decompressedSize >> 24) & 0xFF));
response.prepend((unsigned char)((decompressedSize >> 16) & 0xFF));
response.prepend((unsigned char)((decompressedSize >> 8) & 0xFF));
response.prepend((unsigned char)((decompressedSize >> 0) & 0xFF));

qDebug() << "response before: " << response.size();
response = qUncompress(response);
qDebug() << "response aftery: " << response.size();

return response;
}
36 changes: 34 additions & 2 deletions src/QtLocationPlugin/ElevationMapProvider.h
Original file line number Diff line number Diff line change
Expand Up @@ -11,12 +11,14 @@
#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
public:
ElevationProvider(const QString& imageFormat, quint32 averageSize,
QGeoMapType::MapStyle mapType, QObject* parent = nullptr);
QGeoMapType::MapStyle mapType, const QString &referrer,
QObject* parent = nullptr);

virtual bool _isElevationProvider() const override { return true; }
};
Expand All @@ -29,7 +31,7 @@ class AirmapElevationProvider : public ElevationProvider {
public:
AirmapElevationProvider(QObject* parent = nullptr)
: ElevationProvider(QStringLiteral("bin"), AVERAGE_AIRMAP_ELEV_SIZE,
QGeoMapType::StreetMap, parent) {}
QGeoMapType::StreetMap, QStringLiteral("https://api.airmap.com/"), parent) {}

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

Expand All @@ -39,7 +41,37 @@ class AirmapElevationProvider : public ElevationProvider {
const double topleftLat, const double bottomRightLon,
const double bottomRightLat) const override;

// Airmap needs to serialize the tiles, because they are received in json format. This way we can work with
// them in the map tiles database
bool serializeTilesNeeded() override { return true; }
QByteArray serializeTile(QByteArray image) override;

protected:
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("hgt"), 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;

bool unzippingTilesNeeded() override { return true; }
QByteArray unzipTile(QByteArray response) override;

protected:
QString _getURL(const int x, const int y, const int zoom, QNetworkAccessManager* networkManager) override;
};
5 changes: 5 additions & 0 deletions src/QtLocationPlugin/MapProvider.h
Original file line number Diff line number Diff line change
Expand Up @@ -52,6 +52,11 @@ class MapProvider : public QObject {
const double topleftLat, const double bottomRightLon,
const double bottomRightLat) const;

virtual bool serializeTilesNeeded() { return false; }
virtual QByteArray serializeTile(QByteArray image) { return image; }
virtual bool unzippingTilesNeeded() { return false; }
virtual QByteArray unzipTile(QByteArray response) { return response; }

protected:
QString _tileXYToQuadKey(const int tileX, const int tileY, const int levelOfDetail) const;
int _getServerNum(const int x, const int y, const int max) const;
Expand Down
5 changes: 3 additions & 2 deletions src/QtLocationPlugin/QGCMapTileSet.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -287,8 +287,9 @@ QGCCachedTileSet::_networkReplyFinished()
qCDebug(QGCCachedTileSetLog) << "Tile fetched" << hash;
QByteArray image = reply->readAll();
QString type = getQGCMapEngine()->hashToType(hash);
if (type == "Airmap Elevation" ) {
image = TerrainTile::serializeFromAirMapJson(image);
// Some providers need the images to be serialized because the response is not directly a image based tile
if (getQGCMapEngine()->urlFactory()->needsSerializingTiles(type)) {
image = getQGCMapEngine()->urlFactory()->serializeTileForId(image, type);
}
QString format = getQGCMapEngine()->urlFactory()->getImageFormat(type, image);
if(!format.isEmpty()) {
Expand Down
21 changes: 21 additions & 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 Expand Up @@ -207,3 +208,23 @@ UrlFactory::getTileCount(int zoom, double topleftLon, double topleftLat, double
bool UrlFactory::isElevation(int mapId){
return _providersTable[getTypeFromId(mapId)]->_isElevationProvider();
}

bool UrlFactory::isElevation(QString mapType){
return _providersTable[mapType]->_isElevationProvider();
}

bool UrlFactory::needsSerializingTiles(QString mapType){
return _providersTable[mapType]->serializeTilesNeeded();
}

QByteArray UrlFactory::serializeTileForId(QByteArray image, QString mapType){
return _providersTable[mapType]->serializeTile(image);
}

bool UrlFactory::needsUnzippingTiles(QString mapType){
return _providersTable[mapType]->unzippingTilesNeeded();
}

QByteArray UrlFactory::unzipTileForType(QByteArray response, QString mapType) {
return _providersTable[mapType]->unzipTile(response);
}
5 changes: 5 additions & 0 deletions src/QtLocationPlugin/QGCMapUrlEngine.h
Original file line number Diff line number Diff line change
Expand Up @@ -54,7 +54,12 @@ class UrlFactory : public QObject {
double bottomRightLon, double bottomRightLat,
QString mapType);

bool isElevation(QString mapType);
bool isElevation(int mapId);
bool needsSerializingTiles(QString mapType);
QByteArray serializeTileForId(QByteArray image, QString mapType);
bool needsUnzippingTiles(QString mapType);
QByteArray unzipTileForType(QByteArray response, QString mapType);

private:
int _timeout;
Expand Down
15 changes: 14 additions & 1 deletion src/QtLocationPlugin/QGeoMapReplyQGC.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -132,15 +132,25 @@ QGeoTiledMapReplyQGC::networkReplyFinished()
UrlFactory* urlFactory = getQGCMapEngine()->urlFactory();
QString format = urlFactory->getImageFormat(tileSpec().mapId(), a);
//-- Test for a specialized, elevation data (not map tile)
qDebug() << "control point 0";
if( getQGCMapEngine()->urlFactory()->isElevation(tileSpec().mapId())){
a = TerrainTile::serializeFromAirMapJson(a);
QString type = getQGCMapEngine()->urlFactory()->getTypeFromId(tileSpec().mapId());
// Some providers need the images to be serialized because the response is not directly a image based tile
if (getQGCMapEngine()->urlFactory()->needsSerializingTiles(type)) {
a = getQGCMapEngine()->urlFactory()->serializeTileForId(a, type);
}
// Some providers return the tiles zipped, like Ardupilot terrain servers
if (getQGCMapEngine()->urlFactory()->needsUnzippingTiles(type)) {
a = getQGCMapEngine()->urlFactory()->unzipTileForType(a, type);
}
//-- Cache it if valid
if(!a.isEmpty()) {
getQGCMapEngine()->cacheTile(
getQGCMapEngine()->urlFactory()->getTypeFromId(
tileSpec().mapId()),
tileSpec().x(), tileSpec().y(), tileSpec().zoom(), a, format);
}
qDebug() << "control point 5";
emit terrainDone(a, QNetworkReply::NoError);
} else {
MapProvider* mapProvider = urlFactory->getMapProviderFromId(tileSpec().mapId());
Expand Down Expand Up @@ -173,6 +183,7 @@ QGeoTiledMapReplyQGC::networkReplyError(QNetworkReply::NetworkError error)
}
//-- Test for a specialized, elevation data (not map tile)
if( getQGCMapEngine()->urlFactory()->isElevation(tileSpec().mapId())){
qDebug() << "control point 1";
emit terrainDone(QByteArray(), error);
} else {
//-- Regular map tile
Expand All @@ -191,6 +202,7 @@ QGeoTiledMapReplyQGC::cacheError(QGCMapTask::TaskType type, QString /*errorStrin
{
if(!getQGCMapEngine()->isInternetActive()) {
if( getQGCMapEngine()->urlFactory()->isElevation(tileSpec().mapId())){
qDebug() << "control point 2";
emit terrainDone(QByteArray(), QNetworkReply::NetworkSessionFailedError);
} else {
setError(QGeoTiledMapReply::CommunicationError, "Network not available");
Expand Down Expand Up @@ -228,6 +240,7 @@ QGeoTiledMapReplyQGC::cacheReply(QGCCacheTile* tile)
{
//-- Test for a specialized, elevation data (not map tile)
if( getQGCMapEngine()->urlFactory()->isElevation(tileSpec().mapId())){
qDebug() << "control point 3";
emit terrainDone(tile->img(), QNetworkReply::NoError);
} else {
//-- Regular map tile
Expand Down