Commit 54c7e7dd authored by Andreas Bircher's avatar Andreas Bircher

api calls

parent bfdc40f1
......@@ -569,7 +569,6 @@ HEADERS += \
src/Settings/UnitsSettings.h \
src/Settings/VideoSettings.h \
src/Terrain.h \
src/TerrainCacheTileServer.h \
src/TerrainTile.h \
src/Vehicle/MAVLinkLogManager.h \
src/VehicleSetup/JoystickConfigController.h \
......@@ -758,7 +757,6 @@ SOURCES += \
src/Settings/UnitsSettings.cc \
src/Settings/VideoSettings.cc \
src/Terrain.cc \
src/TerrainCacheTileServer.cc \
src/TerrainTile.cc\
src/Vehicle/MAVLinkLogManager.cc \
src/VehicleSetup/JoystickConfigController.cc \
......
......@@ -18,6 +18,8 @@
#include <QJsonObject>
#include <QJsonArray>
QGC_LOGGING_CATEGORY(TerrainLog, "TerrainLog")
ElevationProvider::ElevationProvider(QObject* parent)
: QObject(parent)
{
......@@ -26,7 +28,37 @@ ElevationProvider::ElevationProvider(QObject* parent)
bool ElevationProvider::queryTerrainData(const QList<QGeoCoordinate>& coordinates)
{
if (_state != State::Idle || coordinates.length() == 0) {
if (coordinates.length() == 0) {
return false;
}
bool fallBackToOnline = false;
QList<float> altitudes;
foreach (QGeoCoordinate coordinate, coordinates) {
QString uniqueTileId = _uniqueTileId(coordinate);
_tilesMutex.lock();
if (!_tiles.contains(uniqueTileId)) {
_tilesMutex.unlock();
fallBackToOnline = true;
break;
} else {
if (_tiles[uniqueTileId].isIn(coordinate)) {
altitudes.push_back(_tiles[uniqueTileId].elevation(coordinate));
} else {
qCDebug(TerrainLog) << "Error: coordinate not in tile region";
altitudes.push_back(-1.0);
}
}
_tilesMutex.unlock();
}
if (!fallBackToOnline) {
qCDebug(TerrainLog) << "All altitudes taken from cached data";
emit terrainData(true, altitudes);
return true;
}
if (_state != State::Idle) {
return false;
}
......@@ -59,6 +91,27 @@ bool ElevationProvider::queryTerrainData(const QList<QGeoCoordinate>& coordinate
return true;
}
bool ElevationProvider::cacheTerrainTiles(const QList<QGeoCoordinate>& coordinates)
{
if (coordinates.length() == 0) {
return false;
}
for (const auto& coordinate : coordinates) {
QString uniqueTileId = _uniqueTileId(coordinate);
_tilesMutex.lock();
if (_downloadQueue.contains(uniqueTileId) || _tiles.contains(uniqueTileId)) {
continue
}
_downloadQueue.append(uniqueTileId.replace("-", ","));
_tilesMutex.unlock();
qCDebug(TerrainLog) << "Adding tile to download queue: " << uniqueTileId;
}
_downloadTiles();
return true;
}
void ElevationProvider::_requestFinished()
{
QNetworkReply* reply = qobject_cast<QNetworkReply*>(QObject::sender());
......@@ -71,7 +124,7 @@ void ElevationProvider::_requestFinished()
QJsonParseError parseError;
QJsonDocument responseJson = QJsonDocument::fromJson(responseBytes, &parseError);
qDebug() << responseJson;
qCDebug(TerrainLog) << "Received " << responseJson;
emit terrainData(false, altitudes);
return;
}
......@@ -96,3 +149,87 @@ void ElevationProvider::_requestFinished()
}
emit terrainData(false, altitudes);
}
void ElevationProvider::_requestFinishedTile()
{
QNetworkReply* reply = qobject_cast<QNetworkReply*>(QObject::sender());
_state = State::Idle;
// When an error occurs we still end up here
if (reply->error() != QNetworkReply::NoError) {
QByteArray responseBytes = reply->readAll();
QJsonParseError parseError;
QJsonDocument responseJson = QJsonDocument::fromJson(responseBytes, &parseError);
qCDebug(TerrainLog) << "ERROR: Received " << responseJson;
// TODO: Handle error in downloading data
return;
}
QByteArray responseBytes = reply->readAll();
QJsonParseError parseError;
QJsonDocument responseJson = QJsonDocument::fromJson(responseBytes, &parseError);
if (parseError.error != QJsonParseError::NoError) {
// TODO: Handle error in downloading data
return;
}
TerrainTile* tile = new TerrainTile(responseJson);
if (tile->isValid()) {
_tilesMutex.lock();
if (!_tiles.contains(_uniqueTileId(tile->centerCoordinate()))) {
_tiles.insert(_uniqueTileId(tile->centerCoordinate()), *tile);
} else {
delete tile;
}
_tilesMutex.lock();
}
_downloadTiles();
}
void ElevationProvider::_downloadTiles(void)
{
if (_state == State::Idle && _downloadQueue.count() > 0) {
QUrlQuery query;
_tilesMutex.lock();
qCDebug(TerrainLog) << "Starting download for " << _downloadQueue.first();
query.addQueryItem(QStringLiteral("points"), _downloadQueue.first());
_downloadQueue.pop_front();
_tilesMutex.unlock();
QUrl url(QStringLiteral("https://api.airmap.com/elevation/stage/srtm1/carpet"));
url.setQuery(query);
QNetworkRequest request(url);
QNetworkProxy tProxy;
tProxy.setType(QNetworkProxy::DefaultProxy);
_networkManager.setProxy(tProxy);
QNetworkReply* networkReply = _networkManager.get(request);
if (!networkReply) {
return false;
}
connect(networkReply, &QNetworkReply::finished, this, &ElevationProvider::_requestFinishedTile);
_state = State::Downloading;
}
}
QString ElevationProvider::_uniqueTileId(const QGeoCoordinate& coordinate)
{
QGeoCoordinate southEast;
southEast.setLatitude(floor(coordinate.latitude()*40.0)/40.0);
southEast.setLongitude(floor(coordinate.longitude()*40.0)/40.0);
QGeoCoordinate northEast;
northEast.setLatitude(ceil(coordinate.latitude()*40.0)/40.0);
northEast.setLongitude(ceil(coordinate.longitude()*40.0)/40.0);
QString ret = QString::number(southEast.latitude(), 'f', 6) + "-" + QString::number(southEast.longitude(), 'f', 6) + "-" +
QString::number(northEast.latitude(), 'f', 6) + "-" + QString::number(northEast.longitude(), 'f', 6);
qCDebug << "Computing unique tile id for " << coordinate << ret;
return ret;
}
......@@ -9,11 +9,14 @@
#pragma once
#include "TerrainTile.h"
#include "QGCLoggingCategory.h"
#include <QObject>
#include <QGeoCoordinate>
#include <QNetworkAccessManager>
#include "TerrainCacheTileServer.h"
#include <QHash>
#include <QMutex>
/* usage example:
ElevationProvider *p = new ElevationProvider();
......@@ -25,6 +28,7 @@
p->queryTerrainData(coordinates);
*/
Q_DECLARE_LOGGING_CATEGORY(TerrainLog)
class ElevationProvider : public QObject
{
......@@ -41,24 +45,34 @@ public:
bool queryTerrainData(const QList<QGeoCoordinate>& coordinates);
/**
* Cache all data in rectangular region given by south west and north east corner.
*
*
*
* @param southWest
* @param northEast
*/
bool cacheTerrainData(const QGeoCoordinate& southWest, const QGeoCoordinate& northEast);
void cacheTerrainData(const QGeoCoordinate& southWest, const QGeoCoordinate& northEast);
signals:
void terrainData(bool success, QList<float> altitudes);
private slots:
void _requestFinished();
void _requestFinishedTile();
private:
QString _uniqueTileId(const QGeoCoordinate& coordinate);
void _downloadTiles(void);
enum class State {
Idle,
Downloading,
};
State _state = State::Idle;
QNetworkAccessManager _networkManager;
State _state = State::Idle;
QNetworkAccessManager _networkManager;
static QMutex _tilesMutex;
static QHash<QString, TerrainTile> _tiles;
QStringList _downloadQueue;
};
#include "TerrainCacheTileServer.h"
TerrainCacheTileServer::TerrainCacheTileServer()
{
}
#ifndef TERRAINCACHESERVER_H
#define TERRAINCACHESERVER_H
#include "TerrainTile.h"
class TerrainCacheTileServer
{
public:
TerrainCacheTileServer();
bool cacheTerrainData(const QGeoCoordinate& southWest, const QGeoCoordinate& northEast);
bool cached(const QGeoCoordinate& coord);
private:
QStringList _downloadQueue;
};
#endif // TERRAINCACHESERVER_H
......@@ -31,17 +31,17 @@ TerrainTile::~TerrainTile()
{
}
TerrainTile::TerrainTile(QJsonDocument doc)
TerrainTile::TerrainTile(QJsonDocument document)
: _minElevation(-1.0)
, _maxElevation(-1.0)
, _avgElevation(-1.0)
, _isValid(false)
{
if (!doc.isObject()) {
if (!document.isObject()) {
qCDebug(TerrainTileLog) << "Terrain tile json doc is no object";
return;
}
QJsonObject rootObject = doc.object();
QJsonObject rootObject = document.object();
QString errorString;
QList<JsonHelper::KeyValidateInfo> rootVersionKeyInfoList = {
......@@ -123,7 +123,7 @@ TerrainTile::TerrainTile(QJsonDocument doc)
_isValid = true;
}
bool TerrainTile::isIn(QGeoCoordinate coord)
bool TerrainTile::isIn(const QGeoCoordinate& coordinate) const
{
if (!_isValid) {
qCDebug(TerrainTileLog) << "isIn requested, but tile not valid";
......@@ -135,7 +135,7 @@ bool TerrainTile::isIn(QGeoCoordinate coord)
return ret;
}
float TerrainTile::elevation(const QGeoCoordinate& coord)
float TerrainTile::elevation(const QGeoCoordinate& coordinate) const
{
if (_isValid) {
qCDebug << "elevation: " << coord << " , in sw " << _southWest << " , ne " << _northEast;
......
......@@ -18,9 +18,9 @@ public:
/**
* Constructor from json doc with elevation data (either from file or web)
*
* @param json doc
* @param document
*/
TerrainTile(QJsonDocument doc);
TerrainTile(QJsonDocument document);
/**
* Check for whether a coordinate lies within this tile
......@@ -28,14 +28,14 @@ public:
* @param coordinate
* @return true if within
*/
bool isIn(QGeoCoordinate coord);
bool isIn(const QGeoCoordinate& coordinate) const;
/**
* Check whether valid data is loaded
*
* @return true if data is valid
*/
bool isValid(void) { return _isValid; }
bool isValid(void) const { return _isValid; }
/**
* Evaluates the elevation at the given coordinate
......@@ -43,28 +43,34 @@ public:
* @param coordinate
* @return elevation
*/
float elevation(const QGeoCoordinate& coord);
float elevation(const QGeoCoordinate& coordinate) const;
/**
* Accessor for the minimum elevation of the tile
*
* @return minimum elevation
*/
float minElevation(void) { return _minElevation; }
float minElevation(void) const { return _minElevation; }
/**
* Accessor for the maximum elevation of the tile
*
* @return maximum elevation
*/
float maxElevation(void) { return _maxElevation; }
float maxElevation(void) const { return _maxElevation; }
/**
* Accessor for the average elevation of the tile
*
* @return average elevation
*/
float avgElevation(void) { return _avgElevation; }
float avgElevation(void) const { return _avgElevation; }
/// tile grid size in lat and lon
static const int _gridSize = TERRAIN_TILE_SIZE;
/// grid spacing in degree
static const float _srtm1Increment = 1.0 / (60.0 * 60.0);
private:
QGeoCoordinate _southWest; /// South west corner of the tile
......@@ -76,8 +82,6 @@ private:
float _data[TERRAIN_TILE_SIZE][TERRAIN_TILE_SIZE]; /// elevation data
bool _isValid; /// data loaded is valid
static const int _gridSize = TERRAIN_TILE_SIZE; /// tile grid size in lat and lon
static const float _srtm1Increment = 1.0 / (60.0 * 60.0); /// grid spacing in degree
// Json keys
static const char* _jsonStatusKey;
......
Markdown is supported
0% or
You are about to add 0 people to the discussion. Proceed with caution.
Finish editing this message first!
Please register or to comment