Commit ca2c3722 authored by Beat Küng's avatar Beat Küng

AirMap: display polygons from api.airmap.com/status/alpha/point

parent c92f9ca0
......@@ -104,9 +104,10 @@ void JsonHelper::_saveGeoCoordinate(const QGeoCoordinate& coordinate,
bool JsonHelper::loadGeoCoordinate(const QJsonValue& jsonValue,
bool altitudeRequired,
QGeoCoordinate& coordinate,
QString& errorString)
QString& errorString,
bool geoJsonFormat)
{
return _loadGeoCoordinate(jsonValue, altitudeRequired, coordinate, errorString, false /* geoJsonFormat */);
return _loadGeoCoordinate(jsonValue, altitudeRequired, coordinate, errorString, geoJsonFormat);
}
void JsonHelper::saveGeoCoordinate(const QGeoCoordinate& coordinate,
......@@ -384,7 +385,7 @@ bool JsonHelper::loadPolygon(const QJsonArray& polygonArray, QmlObjectListModel&
const QJsonValue& pointValue = polygonArray[i];
QGeoCoordinate pointCoord;
if (!JsonHelper::loadGeoCoordinate(pointValue, false /* altitudeRequired */, pointCoord, errorString)) {
if (!JsonHelper::loadGeoCoordinate(pointValue, false /* altitudeRequired */, pointCoord, errorString, true)) {
list.clearAndDeleteContents();
return false;
}
......
......@@ -66,10 +66,11 @@ public:
/// Loads a QGeoCoordinate
/// Stored as array [ lat, lon, alt ]
/// @return false: validation failed
static bool loadGeoCoordinate(const QJsonValue& jsonValue, ///< json value to load from
bool altitudeRequired, ///< true: altitude must be specified
QGeoCoordinate& coordinate, ///< returned QGeoCordinate
QString& errorString); ///< returned error string if load failure
static bool loadGeoCoordinate(const QJsonValue& jsonValue, ///< json value to load from
bool altitudeRequired, ///< true: altitude must be specified
QGeoCoordinate& coordinate, ///< returned QGeoCordinate
QString& errorString, ///< returned error string if load failure
bool geoJsonFormat = false); ///< if true, use [lon, lat], [lat, lon] otherwise
/// Saves a QGeoCoordinate
/// Stored as array [ lat, lon, alt ]
......
......@@ -13,19 +13,21 @@
#include "JsonHelper.h"
#include "SettingsManager.h"
#include "AppSettings.h"
#include "QGCQGeoCoordinate.h"
#include <QNetworkAccessManager>
#include <QUrlQuery>
#include <QJsonDocument>
#include <QJsonArray>
#include <QNetworkProxy>
#include <QSet>
QGC_LOGGING_CATEGORY(AirMapManagerLog, "AirMapManagerLog")
AirMapManager::AirMapManager(QGCApplication* app, QGCToolbox* toolbox)
: QGCTool(app, toolbox)
{
_updateTimer.setInterval(5000);
_updateTimer.setInterval(2000);
_updateTimer.setSingleShot(true);
connect(&_updateTimer, &QTimer::timeout, this, &AirMapManager::_updateToROI);
}
......@@ -46,10 +48,10 @@ void AirMapManager::_get(QUrl url)
{
QNetworkRequest request(url);
qDebug() << url.toString(QUrl::FullyEncoded);
qDebug() << _toolbox->settingsManager()->appSettings()->airMapKey()->rawValueString();
//qDebug() << url.toString(QUrl::FullyEncoded);
//qDebug() << "Settings API key: " << _toolbox->settingsManager()->appSettings()->airMapKey()->rawValueString();
request.setRawHeader("X-API-Key", _toolbox->settingsManager()->appSettings()->airMapKey()->rawValueString().toUtf8());
request.setRawHeader("X-API-Key", _toolbox->settingsManager()->appSettings()->airMapKey()->rawValueString().toUtf8());
QNetworkProxy tProxy;
tProxy.setType(QNetworkProxy::DefaultProxy);
......@@ -113,61 +115,75 @@ void AirMapManager::_getError(QNetworkReply::NetworkError code)
errorMsg = QString("Error during download. Error: (%1, %2)").arg(code).arg(reply->errorString());
}
if (_state == State::RetrieveItems) {
if (--_numAwaitingItems == 0) {
_state = State::Idle;
// TODO: handle properly
}
}
// FIXME
qWarning() << errorMsg;
}
void AirMapManager::_updateToROI(void)
{
// Build up the polygon for the query
QJsonObject polygonJson;
polygonJson["type"] = "Polygon";
QGeoCoordinate left = _roiCenter.atDistanceAndAzimuth(_roiRadius, -90);
QGeoCoordinate right = _roiCenter.atDistanceAndAzimuth(_roiRadius, 90);
QGeoCoordinate top = _roiCenter.atDistanceAndAzimuth(_roiRadius, 0);
QGeoCoordinate bottom = _roiCenter.atDistanceAndAzimuth(_roiRadius, 180);
QGeoCoordinate topLeft(top.latitude(), left.longitude());
QGeoCoordinate topRight(top.latitude(), right.longitude());
QGeoCoordinate bottomLeft(bottom.latitude(), left.longitude());
QGeoCoordinate bottomRight(bottom.latitude(), left.longitude());
QJsonValue coordValue;
QJsonArray rgVertex;
// GeoJson polygons are right handed and include duplicate first and last vertex
JsonHelper::saveGeoJsonCoordinate(topLeft, false /* writeAltitude */, coordValue);
rgVertex.append(coordValue);
JsonHelper::saveGeoJsonCoordinate(bottomLeft, false /* writeAltitude */, coordValue);
rgVertex.append(coordValue);
JsonHelper::saveGeoJsonCoordinate(bottomRight, false /* writeAltitude */, coordValue);
rgVertex.append(coordValue);
JsonHelper::saveGeoJsonCoordinate(topRight, false /* writeAltitude */, coordValue);
rgVertex.append(coordValue);
JsonHelper::saveGeoJsonCoordinate(topLeft, false /* writeAltitude */, coordValue);
rgVertex.append(coordValue);
if (_state != State::Idle) {
qDebug() << "Error: state not idle (yet)";
// restart timer?
return;
}
QJsonArray rgPolygon;
rgPolygon.append(rgVertex);
// Build up the polygon for the query
polygonJson["coordinates"] = rgPolygon;
QJsonDocument polygonJsonDoc(polygonJson);
// QJsonObject polygonJson;
//
// polygonJson["type"] = "Polygon";
//
// QGeoCoordinate left = _roiCenter.atDistanceAndAzimuth(_roiRadius, -90);
// QGeoCoordinate right = _roiCenter.atDistanceAndAzimuth(_roiRadius, 90);
// QGeoCoordinate top = _roiCenter.atDistanceAndAzimuth(_roiRadius, 0);
// QGeoCoordinate bottom = _roiCenter.atDistanceAndAzimuth(_roiRadius, 180);
//
// QGeoCoordinate topLeft(top.latitude(), left.longitude());
// QGeoCoordinate topRight(top.latitude(), right.longitude());
// QGeoCoordinate bottomLeft(bottom.latitude(), left.longitude());
// QGeoCoordinate bottomRight(bottom.latitude(), left.longitude());
//
// QJsonValue coordValue;
// QJsonArray rgVertex;
//
// // GeoJson polygons are right handed and include duplicate first and last vertex
// JsonHelper::saveGeoJsonCoordinate(topLeft, false /* writeAltitude */, coordValue);
// rgVertex.append(coordValue);
// JsonHelper::saveGeoJsonCoordinate(bottomLeft, false /* writeAltitude */, coordValue);
// rgVertex.append(coordValue);
// JsonHelper::saveGeoJsonCoordinate(bottomRight, false /* writeAltitude */, coordValue);
// rgVertex.append(coordValue);
// JsonHelper::saveGeoJsonCoordinate(topRight, false /* writeAltitude */, coordValue);
// rgVertex.append(coordValue);
// JsonHelper::saveGeoJsonCoordinate(topLeft, false /* writeAltitude */, coordValue);
// rgVertex.append(coordValue);
//
// QJsonArray rgPolygon;
// rgPolygon.append(rgVertex);
//
// polygonJson["coordinates"] = rgPolygon;
// QJsonDocument polygonJsonDoc(polygonJson);
// Build up the http query
QUrlQuery airspaceQuery;
airspaceQuery.addQueryItem(QStringLiteral("geometry"), QString::fromUtf8(polygonJsonDoc.toJson(QJsonDocument::Compact)));
airspaceQuery.addQueryItem(QStringLiteral("types"), QStringLiteral("airport,controlled_airspace,tfr,wildfire"));
airspaceQuery.addQueryItem(QStringLiteral("full"), QStringLiteral("true"));
airspaceQuery.addQueryItem(QStringLiteral("geometry_format"), QStringLiteral("geojson"));
airspaceQuery.addQueryItem(QStringLiteral("latitude"), QString::number(_roiCenter.latitude(), 'f', 10));
airspaceQuery.addQueryItem(QStringLiteral("longitude"), QString::number(_roiCenter.longitude(), 'f', 10));
airspaceQuery.addQueryItem(QStringLiteral("weather"), QStringLiteral("true"));
airspaceQuery.addQueryItem(QStringLiteral("buffer"), QString::number(_roiRadius, 'f', 0));
QUrl airMapAirspaceUrl(QStringLiteral("https://api.airmap.com/airspace/v2/search"));
QUrl airMapAirspaceUrl(QStringLiteral("https://api.airmap.com/status/alpha/point"));
airMapAirspaceUrl.setQuery(airspaceQuery);
_state = State::RetrieveList;
_get(airMapAirspaceUrl);
}
......@@ -178,22 +194,98 @@ void AirMapManager::_parseAirspaceJson(const QJsonDocument& airspaceDoc)
return;
}
_polygonList.clearAndDeleteContents();
_circleList.clearAndDeleteContents();
QJsonObject rootObject = airspaceDoc.object();
const QJsonArray& airspaceArray = rootObject["data"].toArray();
for (int i=0; i< airspaceArray.count(); i++) {
const QJsonObject& airspaceObject = airspaceArray[i].toObject();
QString airspaceType(airspaceObject["type"].toString());
qDebug() << airspaceType;
qDebug() << airspaceObject["name"].toString();
QGeoCoordinate center(airspaceObject["latitude"].toDouble(), airspaceObject["longitude"].toDouble());
qDebug() << center;
if (airspaceType == "airport") {
_circleList.append(new CircularAirspaceRestriction(center, 8046.72));
switch(_state) {
case State::RetrieveList:
{
QSet<QString> advisorySet;
const QJsonArray& advisoriesArray = rootObject["data"].toObject()["advisories"].toArray();
for (int i=0; i< advisoriesArray.count(); i++) {
const QJsonObject& advisoryObject = advisoriesArray[i].toObject();
QString advisoryId(advisoryObject["id"].toString());
qDebug() << "Adivsory id: " << advisoryId;
advisorySet.insert(advisoryId);
}
for (const auto& advisoryId : advisorySet) {
QUrl url(QStringLiteral("https://api.airmap.com/airspace/v2/")+advisoryId);
_get(url);
}
_numAwaitingItems = advisorySet.size();
_state = State::RetrieveItems;
}
break;
case State::RetrieveItems:
{
qDebug() << "got item";
const QJsonArray& airspaceArray = rootObject["data"].toArray();
for (int i=0; i< airspaceArray.count(); i++) {
const QJsonObject& airspaceObject = airspaceArray[i].toObject();
QString airspaceType(airspaceObject["type"].toString());
QString airspaceId(airspaceObject["id"].toString());
QString airspaceName(airspaceObject["name"].toString());
const QJsonObject& airspaceGeometry(airspaceObject["geometry"].toObject());
QString geometryType(airspaceGeometry["type"].toString());
qDebug() << "Airspace ID:" << airspaceId << "name:" << airspaceName << "type:" << airspaceType << "geometry:" << geometryType;
if (geometryType == "Polygon") {
const QJsonArray& airspaceCoordinates(airspaceGeometry["coordinates"].toArray()[0].toArray());
QString errorString;
QmlObjectListModel list;
if (JsonHelper::loadPolygon(airspaceCoordinates, list, this, errorString)) {
QVariantList polygon;
for (int i = 0; i < list.count(); ++i) {
polygon.append(QVariant::fromValue(((QGCQGeoCoordinate*)list[i])->coordinate()));
}
list.clearAndDeleteContents();
_nextPolygonList.append(new PolygonAirspaceRestriction(polygon));
} else {
//FIXME
qDebug() << errorString;
}
} else {
// TODO: are there any circles?
qDebug() << "Unknown geometry type:" << geometryType;
}
}
if (--_numAwaitingItems == 0) {
_polygonList.clearAndDeleteContents();
_circleList.clearAndDeleteContents();
for (const auto& circle : _nextcircleList) {
_circleList.append(circle);
}
_nextcircleList.clear();
for (const auto& polygon : _nextPolygonList) {
_polygonList.append(polygon);
}
_nextPolygonList.clear();
_state = State::Idle;
}
}
break;
default:
qDebug() << "Error: wrong state";
break;
}
// https://api.airmap.com/airspace/v2/search API
// const QJsonArray& airspaceArray = rootObject["data"].toArray();
// for (int i=0; i< airspaceArray.count(); i++) {
// const QJsonObject& airspaceObject = airspaceArray[i].toObject();
// QString airspaceType(airspaceObject["type"].toString());
// qDebug() << airspaceType;
// qDebug() << airspaceObject["name"].toString();
// QGeoCoordinate center(airspaceObject["latitude"].toDouble(), airspaceObject["longitude"].toDouble());
// qDebug() << center;
// if (airspaceType == "airport") {
// _circleList.append(new CircularAirspaceRestriction(center, 5000));
// }
// }
}
AirspaceRestriction::AirspaceRestriction(QObject* parent)
......
......@@ -22,39 +22,6 @@
Q_DECLARE_LOGGING_CATEGORY(AirMapManagerLog)
/// AirMap server communication support.
class AirMapManager : public QGCTool
{
Q_OBJECT
public:
AirMapManager(QGCApplication* app, QGCToolbox* toolbox);
~AirMapManager();
/// Set the ROI for airspace information
/// @param center Center coordinate for ROI
/// @param radiusMeters Radius in meters around center which is of interest
void setROI(QGeoCoordinate& center, double radiusMeters);
QmlObjectListModel* polygonRestrictions(void) { return &_polygonList; }
QmlObjectListModel* circularRestrictions(void) { return &_circleList; }
private slots:
void _getFinished(void);
void _getError(QNetworkReply::NetworkError code);
void _updateToROI(void);
private:
void _get(QUrl url);
void _parseAirspaceJson(const QJsonDocument& airspaceDoc);
QGeoCoordinate _roiCenter;
double _roiRadius;
QNetworkAccessManager _networkManager;
QTimer _updateTimer;
QmlObjectListModel _polygonList;
QmlObjectListModel _circleList;
};
class AirspaceRestriction : public QObject
{
......@@ -92,4 +59,49 @@ private:
double _radius;
};
/// AirMap server communication support.
class AirMapManager : public QGCTool
{
Q_OBJECT
public:
AirMapManager(QGCApplication* app, QGCToolbox* toolbox);
~AirMapManager();
/// Set the ROI for airspace information
/// @param center Center coordinate for ROI
/// @param radiusMeters Radius in meters around center which is of interest
void setROI(QGeoCoordinate& center, double radiusMeters);
QmlObjectListModel* polygonRestrictions(void) { return &_polygonList; }
QmlObjectListModel* circularRestrictions(void) { return &_circleList; }
private slots:
void _getFinished(void);
void _getError(QNetworkReply::NetworkError code);
void _updateToROI(void);
private:
void _get(QUrl url);
void _parseAirspaceJson(const QJsonDocument& airspaceDoc);
enum class State {
Idle,
RetrieveList,
RetrieveItems,
};
State _state = State::Idle;
int _numAwaitingItems = 0;
QGeoCoordinate _roiCenter;
double _roiRadius;
QNetworkAccessManager _networkManager;
QTimer _updateTimer;
QmlObjectListModel _polygonList;
QmlObjectListModel _circleList;
QList<PolygonAirspaceRestriction*> _nextPolygonList;
QList<CircularAirspaceRestriction*> _nextcircleList;
};
#endif
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