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, ...@@ -104,9 +104,10 @@ void JsonHelper::_saveGeoCoordinate(const QGeoCoordinate& coordinate,
bool JsonHelper::loadGeoCoordinate(const QJsonValue& jsonValue, bool JsonHelper::loadGeoCoordinate(const QJsonValue& jsonValue,
bool altitudeRequired, bool altitudeRequired,
QGeoCoordinate& coordinate, 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, void JsonHelper::saveGeoCoordinate(const QGeoCoordinate& coordinate,
...@@ -384,7 +385,7 @@ bool JsonHelper::loadPolygon(const QJsonArray& polygonArray, QmlObjectListModel& ...@@ -384,7 +385,7 @@ bool JsonHelper::loadPolygon(const QJsonArray& polygonArray, QmlObjectListModel&
const QJsonValue& pointValue = polygonArray[i]; const QJsonValue& pointValue = polygonArray[i];
QGeoCoordinate pointCoord; QGeoCoordinate pointCoord;
if (!JsonHelper::loadGeoCoordinate(pointValue, false /* altitudeRequired */, pointCoord, errorString)) { if (!JsonHelper::loadGeoCoordinate(pointValue, false /* altitudeRequired */, pointCoord, errorString, true)) {
list.clearAndDeleteContents(); list.clearAndDeleteContents();
return false; return false;
} }
......
...@@ -69,7 +69,8 @@ public: ...@@ -69,7 +69,8 @@ public:
static bool loadGeoCoordinate(const QJsonValue& jsonValue, ///< json value to load from static bool loadGeoCoordinate(const QJsonValue& jsonValue, ///< json value to load from
bool altitudeRequired, ///< true: altitude must be specified bool altitudeRequired, ///< true: altitude must be specified
QGeoCoordinate& coordinate, ///< returned QGeoCordinate QGeoCoordinate& coordinate, ///< returned QGeoCordinate
QString& errorString); ///< returned error string if load failure QString& errorString, ///< returned error string if load failure
bool geoJsonFormat = false); ///< if true, use [lon, lat], [lat, lon] otherwise
/// Saves a QGeoCoordinate /// Saves a QGeoCoordinate
/// Stored as array [ lat, lon, alt ] /// Stored as array [ lat, lon, alt ]
......
This diff is collapsed.
...@@ -22,39 +22,6 @@ ...@@ -22,39 +22,6 @@
Q_DECLARE_LOGGING_CATEGORY(AirMapManagerLog) 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 class AirspaceRestriction : public QObject
{ {
...@@ -92,4 +59,49 @@ private: ...@@ -92,4 +59,49 @@ private:
double _radius; 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 #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