From 888788b7995d9f91a499975c19741d9c9c915325 Mon Sep 17 00:00:00 2001 From: Gus Grubba Date: Thu, 25 Jan 2018 17:38:26 -0500 Subject: [PATCH] Rules and Advisories --- qgroundcontrol.pro | 4 ++ src/Airmap/AirMapManager.cc | 11 +++- src/Airmap/AirMapManager.h | 2 + src/Airmap/AirMapRulesetsManager.cc | 26 ++++++-- src/Airmap/AirMapRulesetsManager.h | 35 ++++++++-- src/Airmap/AirMapWeatherInformation.cc | 27 ++------ src/Airmap/AirMapWeatherInformation.h | 37 +++++------ src/Airmap/AirmapAdvisories.cc | 66 +++++++++++++++++++ src/Airmap/AirmapAdvisories.h | 48 ++++++++++++++ .../AirspaceAdvisoryProvider.cc | 15 +++++ .../AirspaceAdvisoryProvider.h | 39 +++++++++++ src/AirspaceManagement/AirspaceController.cc | 13 ++++ src/AirspaceManagement/AirspaceController.h | 6 ++ src/AirspaceManagement/AirspaceManager.cc | 27 ++++++-- src/AirspaceManagement/AirspaceManager.h | 10 +++ .../AirspaceRulesetsProvider.cc | 5 ++ .../AirspaceRulesetsProvider.h | 39 +++++++++-- 17 files changed, 344 insertions(+), 66 deletions(-) create mode 100644 src/Airmap/AirmapAdvisories.cc create mode 100644 src/Airmap/AirmapAdvisories.h create mode 100644 src/AirspaceManagement/AirspaceAdvisoryProvider.cc create mode 100644 src/AirspaceManagement/AirspaceAdvisoryProvider.h diff --git a/qgroundcontrol.pro b/qgroundcontrol.pro index 583a5f764..d89013fa5 100644 --- a/qgroundcontrol.pro +++ b/qgroundcontrol.pro @@ -1064,6 +1064,7 @@ contains (DEFINES, QGC_AIRMAP_ENABLED) { src/AirspaceManagement HEADERS += \ + src/AirspaceManagement/AirspaceAdvisoryProvider.h \ src/AirspaceManagement/AirspaceAuthorization.h \ src/AirspaceManagement/AirspaceController.h \ src/AirspaceManagement/AirspaceManager.h \ @@ -1074,6 +1075,7 @@ contains (DEFINES, QGC_AIRMAP_ENABLED) { src/AirspaceManagement/AirspaceWeatherInfoProvider.h \ SOURCES += \ + src/AirspaceManagement/AirspaceAdvisoryProvider.cc \ src/AirspaceManagement/AirspaceController.cc \ src/AirspaceManagement/AirspaceManager.cc \ src/AirspaceManagement/AirspaceRestriction.cc \ @@ -1090,6 +1092,7 @@ contains (DEFINES, QGC_AIRMAP_ENABLED) { src/Airmap HEADERS += \ + src/Airmap/AirMapAdvisories.h \ src/Airmap/AirMapFlightManager.h \ src/Airmap/AirMapManager.h \ src/Airmap/AirMapRestrictionManager.h \ @@ -1103,6 +1106,7 @@ contains (DEFINES, QGC_AIRMAP_ENABLED) { src/Airmap/LifetimeChecker.h \ SOURCES += \ + src/Airmap/AirMapAdvisories.cc \ src/Airmap/AirMapFlightManager.cc \ src/Airmap/AirMapManager.cc \ src/Airmap/AirMapRestrictionManager.cc \ diff --git a/src/Airmap/AirMapManager.cc b/src/Airmap/AirMapManager.cc index 39d3ae554..c6df502a4 100644 --- a/src/Airmap/AirMapManager.cc +++ b/src/Airmap/AirMapManager.cc @@ -8,6 +8,7 @@ ****************************************************************************/ #include "AirMapManager.h" +#include "AirMapAdvisories.h" #include "AirMapWeatherInformation.h" #include "AirMapRestrictionManager.h" #include "AirMapRulesetsManager.h" @@ -34,7 +35,7 @@ AirMapManager::AirMapManager(QGCApplication* app, QGCToolbox* toolbox) { _logger = std::make_shared(); qt::register_types(); // TODO: still needed?s - _logger->logging_category().setEnabled(QtDebugMsg, false); + _logger->logging_category().setEnabled(QtDebugMsg, true); _logger->logging_category().setEnabled(QtInfoMsg, true); _logger->logging_category().setEnabled(QtWarningMsg, true); _dispatchingLogger = std::make_shared(_logger); @@ -134,3 +135,11 @@ AirMapManager::instatiateAirspaceWeatherInfoProvider() connect(weatherInfo, &AirMapWeatherInformation::error, this, &AirMapManager::_error); return weatherInfo; } + +AirspaceAdvisoryProvider* +AirMapManager::instatiateAirspaceAdvisoryProvider() +{ + AirMapAdvisories* advisories = new AirMapAdvisories(_shared); + connect(advisories, &AirMapAdvisories::error, this, &AirMapManager::_error); + return advisories; +} diff --git a/src/Airmap/AirMapManager.h b/src/Airmap/AirMapManager.h index 3966c6911..cea6af5de 100644 --- a/src/Airmap/AirMapManager.h +++ b/src/Airmap/AirMapManager.h @@ -23,6 +23,7 @@ class AirspaceVehicleManager; class AirspaceRestrictionProvider; class AirspaceRulesetsProvider; class AirspaceWeatherInfoProvider; +class AirspaceAdvisoryProvider; Q_DECLARE_LOGGING_CATEGORY(AirMapManagerLog) @@ -46,6 +47,7 @@ public: AirspaceRestrictionProvider* instantiateRestrictionProvider () override; AirspaceRulesetsProvider* instantiateRulesetsProvider () override; AirspaceWeatherInfoProvider* instatiateAirspaceWeatherInfoProvider () override; + AirspaceAdvisoryProvider* instatiateAirspaceAdvisoryProvider () override; QString name () const override { return "AirMap"; } diff --git a/src/Airmap/AirMapRulesetsManager.cc b/src/Airmap/AirMapRulesetsManager.cc index 5e8473e91..cb98e88bf 100644 --- a/src/Airmap/AirMapRulesetsManager.cc +++ b/src/Airmap/AirMapRulesetsManager.cc @@ -10,10 +10,15 @@ #include "AirMapRulesetsManager.h" #include "AirMapManager.h" -#include "airmap/rulesets.h" - using namespace airmap; +//----------------------------------------------------------------------------- +AirMapRule::AirMapRule(QObject* parent) + : AirspaceRule(parent) + , _isDefault(false) +{ +} + //----------------------------------------------------------------------------- AirMapRulesetsManager::AirMapRulesetsManager(AirMapSharedState& shared) : _shared(shared) @@ -32,6 +37,7 @@ void AirMapRulesetsManager::setROI(const QGeoCoordinate& center) return; } qCDebug(AirMapManagerLog) << "Setting ROI for Rulesets"; + _rules.clearAndDeleteContents(); _state = State::RetrieveItems; RuleSets::Search::Parameters params; params.geometry = Geometry::point(center.latitude(), center.longitude()); @@ -41,9 +47,16 @@ void AirMapRulesetsManager::setROI(const QGeoCoordinate& center) if (!isAlive.lock()) return; if (_state != State::RetrieveItems) return; if (result) { - const std::vector& rulesets = result.value(); - qCDebug(AirMapManagerLog)<<"Successful rulesets search. Items:" << rulesets.size(); - for (const auto& ruleset : rulesets) { + const std::vector rules = result.value(); + qCDebug(AirMapManagerLog)<<"Successful rulesets search. Items:" << rules.size(); + for (const auto& ruleset : rules) { + AirMapRule* pRule = new AirMapRule(this); + pRule->_id = QString::fromStdString(ruleset.id); + pRule->_name = QString::fromStdString(ruleset.short_name); + pRule->_description = QString::fromStdString(ruleset.description); + pRule->_isDefault = ruleset.is_default; + _rules.append(pRule); + /* qDebug() << "------------------------------------------"; qDebug() << "Jurisdiction:" << ruleset.jurisdiction.name.data() << (int)ruleset.jurisdiction.region; qDebug() << "Name: " << ruleset.name.data(); @@ -68,13 +81,14 @@ void AirMapRulesetsManager::setROI(const QGeoCoordinate& center) qDebug() << " " << (int)feature.status; } } + */ } } else { QString description = QString::fromStdString(result.error().description() ? result.error().description().get() : ""); emit error("Failed to retrieve RuleSets", QString::fromStdString(result.error().message()), description); } - emit requestDone(true); _state = State::Idle; + emit rulesChanged(); }); } diff --git a/src/Airmap/AirMapRulesetsManager.h b/src/Airmap/AirMapRulesetsManager.h index 4327cf446..a25458fb3 100644 --- a/src/Airmap/AirMapRulesetsManager.h +++ b/src/Airmap/AirMapRulesetsManager.h @@ -15,29 +15,54 @@ #include +#include + /** * @file AirMapRulesetsManager.h * Class to download rulesets from AirMap */ +//----------------------------------------------------------------------------- +class AirMapRule : public AirspaceRule +{ + Q_OBJECT + friend class AirMapRulesetsManager; +public: + AirMapRule (QObject* parent = NULL); + QString id () override { return _id; } + QString description () override { return _description; } + bool isDefault () override { return _isDefault; } + QString name () override { return _name; } +private: + QString _id; + QString _description; + bool _isDefault; + QString _name; +}; + +//----------------------------------------------------------------------------- class AirMapRulesetsManager : public AirspaceRulesetsProvider, public LifetimeChecker { Q_OBJECT public: - AirMapRulesetsManager (AirMapSharedState& shared); + AirMapRulesetsManager (AirMapSharedState& shared); - void setROI (const QGeoCoordinate& center) override; + bool valid () override { return _valid; } + QmlObjectListModel* rules () override { return &_rules; } + void setROI (const QGeoCoordinate& center) override; signals: - void error (const QString& what, const QString& airmapdMessage, const QString& airmapdDetails); + void error (const QString& what, const QString& airmapdMessage, const QString& airmapdDetails); private: enum class State { Idle, RetrieveItems, }; - State _state = State::Idle; - AirMapSharedState& _shared; + bool _valid; + State _state = State::Idle; + AirMapSharedState& _shared; + QmlObjectListModel _rules; }; diff --git a/src/Airmap/AirMapWeatherInformation.cc b/src/Airmap/AirMapWeatherInformation.cc index 2cffed63e..4c6fdc978 100644 --- a/src/Airmap/AirMapWeatherInformation.cc +++ b/src/Airmap/AirMapWeatherInformation.cc @@ -18,13 +18,6 @@ using namespace airmap; AirMapWeatherInformation::AirMapWeatherInformation(AirMapSharedState& shared, QObject *parent) : AirspaceWeatherInfoProvider(parent) , _valid(false) - , _windHeading(0) - , _windSpeed(0) - , _windGusting(0) - , _temperature(0) - , _humidity(0.0f) - , _visibility(0) - , _precipitation(0) , _shared(shared) { } @@ -57,25 +50,17 @@ AirMapWeatherInformation::_requestWeatherUpdate(const QGeoCoordinate& coordinate return; } Status::GetStatus::Parameters params; - params.longitude = coordinate.longitude(); - params.latitude = coordinate.latitude(); - params.weather = true; + params.longitude= coordinate.longitude(); + params.latitude = coordinate.latitude(); + params.weather = true; _shared.client()->status().get_status_by_point(params, [this, coordinate](const Status::GetStatus::Result& result) { if (result) { const Status::Weather& weather = result.value().weather; - _valid = true; - _condition = QString::fromStdString(weather.condition); - _icon = QStringLiteral("qrc:/airmapweather/") + QString::fromStdString(weather.icon) + QStringLiteral(".svg"); - _windHeading = weather.wind.heading; - _windSpeed = weather.wind.speed; - _windGusting = weather.wind.gusting; - _temperature = weather.temperature; - _humidity = weather.humidity; - _visibility = weather.visibility; - _precipitation = weather.precipitation; + _valid = true; + _icon = QStringLiteral("qrc:/airmapweather/") + QString::fromStdString(weather.icon) + QStringLiteral(".svg"); qCDebug(AirMapManagerLog) << "Weather Info: " << _valid << _icon; } else { - _valid = false; + _valid = false; qCDebug(AirMapManagerLog) << "Request Weather Failed"; } emit weatherChanged(); diff --git a/src/Airmap/AirMapWeatherInformation.h b/src/Airmap/AirMapWeatherInformation.h index 4e77ffd47..e7a884ba7 100644 --- a/src/Airmap/AirMapWeatherInformation.h +++ b/src/Airmap/AirMapWeatherInformation.h @@ -17,6 +17,8 @@ #include #include +#include "airmap/status.h" + /** * @file AirMapWeatherInformation.h * Weather information provided by AirMap. @@ -29,15 +31,15 @@ public: AirMapWeatherInformation(AirMapSharedState &shared, QObject *parent = nullptr); bool valid () override { return _valid; } - QString condition () override { return _condition; } + QString condition () override { return QString::fromStdString(_weather.condition); } QString icon () override { return _icon; } - quint32 windHeading () override { return _windHeading; } - quint32 windSpeed () override { return _windSpeed; } - quint32 windGusting () override { return _windGusting; } - qint32 temperature () override { return _temperature; } - float humidity () override { return _humidity; } - quint32 visibility () override { return _visibility; } - quint32 precipitation () override { return _precipitation; } + quint32 windHeading () override { return _weather.wind.heading; } + quint32 windSpeed () override { return _weather.wind.speed; } + quint32 windGusting () override { return _weather.wind.gusting; } + qint32 temperature () override { return _weather.temperature; } + float humidity () override { return _weather.humidity; } + quint32 visibility () override { return _weather.visibility; } + quint32 precipitation () override { return _weather.precipitation; } void setROI (const QGeoCoordinate& center) override; @@ -48,18 +50,11 @@ private: void _requestWeatherUpdate (const QGeoCoordinate& coordinate); private: - bool _valid; - QString _condition; - QString _icon; - quint32 _windHeading; - quint32 _windSpeed; - quint32 _windGusting; - qint32 _temperature; - float _humidity; - quint32 _visibility; - quint32 _precipitation; + bool _valid; + QString _icon; + airmap::Status::Weather _weather; //-- Don't check the weather every time the user moves the map - AirMapSharedState& _shared; - QGeoCoordinate _lastRoiCenter; - QTime _weatherTime; + AirMapSharedState& _shared; + QGeoCoordinate _lastRoiCenter; + QTime _weatherTime; }; diff --git a/src/Airmap/AirmapAdvisories.cc b/src/Airmap/AirmapAdvisories.cc new file mode 100644 index 000000000..b234ab979 --- /dev/null +++ b/src/Airmap/AirmapAdvisories.cc @@ -0,0 +1,66 @@ +/**************************************************************************** + * + * (c) 2009-2016 QGROUNDCONTROL PROJECT + * + * QGroundControl is licensed according to the terms in the file + * COPYING.md in the root of the source code directory. + * + ****************************************************************************/ + +#include "AirMapAdvisories.h" +#include "AirMapManager.h" + +#define ADVISORY_UPDATE_DISTANCE 500 //-- 500m threshold for updates + +using namespace airmap; + +AirMapAdvisories::AirMapAdvisories(AirMapSharedState& shared, QObject *parent) + : AirspaceAdvisoryProvider(parent) + , _valid(false) + , _shared(shared) +{ +} + +void +AirMapAdvisories::setROI(const QGeoCoordinate& center, double radiusMeters) +{ + //-- If first time or we've moved more than ADVISORY_UPDATE_DISTANCE, ask for updates. + if(!_lastRoiCenter.isValid() || _lastRoiCenter.distanceTo(center) > ADVISORY_UPDATE_DISTANCE) { + _lastRoiCenter = center; + _requestAdvisories(center, radiusMeters); + } +} + +void +AirMapAdvisories::_requestAdvisories(const QGeoCoordinate& coordinate, double radiusMeters) +{ + qCDebug(AirMapManagerLog) << "Advisories Request"; + if (!_shared.client()) { + qCDebug(AirMapManagerLog) << "No AirMap client instance. Not updating Advisories"; + _valid = false; + emit advisoryChanged(); + return; + } + _advisories.clear(); + _valid = false; + Status::GetStatus::Parameters params; + params.longitude = coordinate.longitude(); + params.latitude = coordinate.latitude(); + params.weather = false; + params.buffer = radiusMeters; + _shared.client()->status().get_status_by_point(params, [this, coordinate](const Status::GetStatus::Result& result) { + if (result) { + qCDebug(AirMapManagerLog) << _advisories.size() << "Advisories Received"; + _advisories = result.value().advisories; + _advisory_color = result.value().advisory_color; + if(_advisories.size()) { + _valid = true; + qCDebug(AirMapManagerLog) << "Advisory Info: " << _advisories.size() << _advisories[0].airspace.name().data(); + } + } else { + qCDebug(AirMapManagerLog) << "Advisories Request Failed"; + _valid = false; + } + emit advisoryChanged(); + }); +} diff --git a/src/Airmap/AirmapAdvisories.h b/src/Airmap/AirmapAdvisories.h new file mode 100644 index 000000000..b4afa657e --- /dev/null +++ b/src/Airmap/AirmapAdvisories.h @@ -0,0 +1,48 @@ +/**************************************************************************** + * + * (c) 2017 QGROUNDCONTROL PROJECT + * + * QGroundControl is licensed according to the terms in the file + * COPYING.md in the root of the source code directory. + * + ****************************************************************************/ + +#pragma once + +#include "LifetimeChecker.h" + +#include "AirspaceAdvisoryProvider.h" +#include "AirMapSharedState.h" + +#include + +#include "airmap/status.h" + +/** + * @file AirMapAdvisories.h + * Advisory information provided by AirMap. + */ + +class AirMapAdvisories : public AirspaceAdvisoryProvider, public LifetimeChecker +{ + Q_OBJECT +public: + AirMapAdvisories (AirMapSharedState &shared, QObject *parent = nullptr); + + bool valid () override { return _valid; } + + void setROI (const QGeoCoordinate& center, double radiusMeters) override; + +signals: + void error (const QString& what, const QString& airmapdMessage, const QString& airmapdDetails); + +private: + void _requestAdvisories (const QGeoCoordinate& coordinate, double radiusMeters); + +private: + bool _valid; + AirMapSharedState& _shared; + QGeoCoordinate _lastRoiCenter; + airmap::Status::Color _advisory_color; + std::vector _advisories; +}; diff --git a/src/AirspaceManagement/AirspaceAdvisoryProvider.cc b/src/AirspaceManagement/AirspaceAdvisoryProvider.cc new file mode 100644 index 000000000..d2d28a006 --- /dev/null +++ b/src/AirspaceManagement/AirspaceAdvisoryProvider.cc @@ -0,0 +1,15 @@ +/**************************************************************************** + * + * (c) 2017 QGROUNDCONTROL PROJECT + * + * QGroundControl is licensed according to the terms in the file + * COPYING.md in the root of the source code directory. + * + ****************************************************************************/ + +#include "AirspaceAdvisoryProvider.h" + +AirspaceAdvisoryProvider::AirspaceAdvisoryProvider(QObject *parent) + : QObject(parent) +{ +} diff --git a/src/AirspaceManagement/AirspaceAdvisoryProvider.h b/src/AirspaceManagement/AirspaceAdvisoryProvider.h new file mode 100644 index 000000000..1a25c194b --- /dev/null +++ b/src/AirspaceManagement/AirspaceAdvisoryProvider.h @@ -0,0 +1,39 @@ +/**************************************************************************** + * + * (c) 2017 QGROUNDCONTROL PROJECT + * + * QGroundControl is licensed according to the terms in the file + * COPYING.md in the root of the source code directory. + * + ****************************************************************************/ + +#pragma once + +/** + * @file AirspaceAdvisoryProvider.h + * Weather information provided by the Airspace Managemement + */ + +#include +#include + +class AirspaceAdvisoryProvider : public QObject +{ + Q_OBJECT +public: + AirspaceAdvisoryProvider (QObject *parent = nullptr); + virtual ~AirspaceAdvisoryProvider () {} + + Q_PROPERTY(bool valid READ valid NOTIFY advisoryChanged) + + virtual bool valid () = 0; ///< Current data is valid + + /** + * Set region of interest that should be queried. When finished, the advisoryChanged() signal will be emmited. + * @param center Center coordinate for ROI + */ + virtual void setROI (const QGeoCoordinate& center, double radiusMeters) = 0; + +signals: + void advisoryChanged (); +}; diff --git a/src/AirspaceManagement/AirspaceController.cc b/src/AirspaceManagement/AirspaceController.cc index faa4d4824..fe8230453 100644 --- a/src/AirspaceManagement/AirspaceController.cc +++ b/src/AirspaceManagement/AirspaceController.cc @@ -10,6 +10,7 @@ #include "AirspaceController.h" #include "AirspaceManager.h" #include "AirspaceWeatherInfoProvider.h" +#include "AirspaceAdvisoryProvider.h" #include "QGCApplication.h" #include "QGCQGeoCoordinate.h" @@ -50,3 +51,15 @@ AirspaceController::weatherInfo() { return _manager->weatherInfo(); } + +AirspaceAdvisoryProvider* +AirspaceController::advisories() +{ + return _manager->advisories(); +} + +AirspaceRulesetsProvider* +AirspaceController::rules() +{ + return _manager->rules(); +} diff --git a/src/AirspaceManagement/AirspaceController.h b/src/AirspaceManagement/AirspaceController.h index 3391cd35f..a892f20a3 100644 --- a/src/AirspaceManagement/AirspaceController.h +++ b/src/AirspaceManagement/AirspaceController.h @@ -15,6 +15,8 @@ class AirspaceManager; class QmlObjectListModel; class AirspaceWeatherInfoProvider; +class AirspaceAdvisoryProvider; +class AirspaceRulesetsProvider; class AirspaceController : public QObject { @@ -27,6 +29,8 @@ public: Q_PROPERTY(QmlObjectListModel* circles READ circles CONSTANT) ///< List of AirspaceCircularRestriction objects Q_PROPERTY(QString providerName READ providerName CONSTANT) Q_PROPERTY(AirspaceWeatherInfoProvider* weatherInfo READ weatherInfo CONSTANT) + Q_PROPERTY(AirspaceAdvisoryProvider* advisories READ advisories CONSTANT) + Q_PROPERTY(AirspaceRulesetsProvider* rules READ rules CONSTANT) Q_INVOKABLE void setROI (QGeoCoordinate center, double radius); @@ -34,6 +38,8 @@ public: QmlObjectListModel* circles (); QString providerName(); AirspaceWeatherInfoProvider* weatherInfo (); + AirspaceAdvisoryProvider* advisories (); + AirspaceRulesetsProvider* rules (); private: AirspaceManager* _manager; diff --git a/src/AirspaceManagement/AirspaceManager.cc b/src/AirspaceManagement/AirspaceManager.cc index 96c8e0671..3b9a5c0c0 100644 --- a/src/AirspaceManagement/AirspaceManager.cc +++ b/src/AirspaceManagement/AirspaceManager.cc @@ -10,6 +10,7 @@ #include "AirspaceManager.h" #include "AirspaceWeatherInfoProvider.h" +#include "AirspaceAdvisoryProvider.h" #include "AirspaceRestriction.h" #include "AirspaceRestrictionProvider.h" #include "AirspaceRulesetsProvider.h" @@ -30,16 +31,25 @@ AirspaceManager::AirspaceManager(QGCApplication* app, QGCToolbox* toolbox) qmlRegisterUncreatableType ("QGroundControl", 1, 0, "AirspaceAuthorization", "Reference only"); qmlRegisterUncreatableType ("QGroundControl.Vehicle", 1, 0, "AirspaceController", "Reference only"); qmlRegisterUncreatableType ("QGroundControl.Vehicle", 1, 0, "AirspaceWeatherInfoProvider","Reference only"); + qmlRegisterUncreatableType ("QGroundControl.Vehicle", 1, 0, "AirspaceAdvisoryProvider", "Reference only"); + qmlRegisterUncreatableType ("QGroundControl.Vehicle", 1, 0, "AirspaceRule", "Reference only"); + qmlRegisterUncreatableType ("QGroundControl.Vehicle", 1, 0, "AirspaceRulesetsProvider", "Reference only"); } AirspaceManager::~AirspaceManager() { - if (_restrictionsProvider) { - delete _restrictionsProvider; + if(_advisories) { + delete _advisories; + } + if(_weatherProvider) { + delete _weatherProvider; } if(_rulesetsProvider) { delete _rulesetsProvider; } + if (_restrictionsProvider) { + delete _restrictionsProvider; + } _polygonRestrictions.clearAndDeleteContents(); _circleRestrictions.clearAndDeleteContents(); } @@ -52,11 +62,9 @@ void AirspaceManager::setToolbox(QGCToolbox* toolbox) if (_restrictionsProvider) { connect(_restrictionsProvider, &AirspaceRestrictionProvider::requestDone, this, &AirspaceManager::_restrictionsUpdated); } - _rulesetsProvider = instantiateRulesetsProvider(); - if (_rulesetsProvider) { - connect(_rulesetsProvider, &AirspaceRulesetsProvider::requestDone, this, &AirspaceManager::_rulessetsUpdated); - } - _weatherProvider = instatiateAirspaceWeatherInfoProvider(); + _rulesetsProvider = instantiateRulesetsProvider(); + _weatherProvider = instatiateAirspaceWeatherInfoProvider(); + _advisories = instatiateAirspaceAdvisoryProvider(); } void AirspaceManager::setROI(const QGeoCoordinate& center, double radiusMeters) @@ -68,15 +76,20 @@ void AirspaceManager::setROI(const QGeoCoordinate& center, double radiusMeters) void AirspaceManager::_updateToROI() { + /* if (_restrictionsProvider) { _restrictionsProvider->setROI(_roiCenter, _roiRadius); } if(_rulesetsProvider) { _rulesetsProvider->setROI(_roiCenter); } + */ if(_weatherProvider) { _weatherProvider->setROI(_roiCenter); } + if (_advisories) { + _advisories->setROI(_roiCenter, _roiRadius); + } } void AirspaceManager::_restrictionsUpdated(bool success) diff --git a/src/AirspaceManagement/AirspaceManager.h b/src/AirspaceManagement/AirspaceManager.h index 91ce2d805..fe12bec82 100644 --- a/src/AirspaceManagement/AirspaceManager.h +++ b/src/AirspaceManagement/AirspaceManager.h @@ -39,6 +39,7 @@ class AirspaceWeatherInfoProvider; class AirspaceRestrictionProvider; class AirspaceRulesetsProvider; class AirspaceVehicleManager; +class AirspaceAdvisoryProvider; Q_DECLARE_LOGGING_CATEGORY(AirspaceManagementLog) @@ -72,6 +73,12 @@ public: * Factory method to create an AirspaceRulesetsProvider object */ virtual AirspaceWeatherInfoProvider* instatiateAirspaceWeatherInfoProvider () = 0; + + /** + * Factory method to create an AirspaceAdvisoryProvider object + */ + virtual AirspaceAdvisoryProvider* instatiateAirspaceAdvisoryProvider () = 0; + /** * Set the ROI for airspace information (restrictions shown in UI) * @param center Center coordinate for ROI @@ -82,6 +89,8 @@ public: QmlObjectListModel* polygonRestrictions () { return &_polygonRestrictions; } QmlObjectListModel* circularRestrictions () { return &_circleRestrictions; } AirspaceWeatherInfoProvider* weatherInfo () { return _weatherProvider; } + AirspaceAdvisoryProvider* advisories () { return _advisories; } + AirspaceRulesetsProvider* rules () { return _rulesetsProvider; } void setToolbox(QGCToolbox* toolbox) override; @@ -102,6 +111,7 @@ private: AirspaceRestrictionProvider* _restrictionsProvider = nullptr; ///< Restrictions that are shown in the UI AirspaceRulesetsProvider* _rulesetsProvider = nullptr; ///< Restrictions that are shown in the UI AirspaceWeatherInfoProvider* _weatherProvider = nullptr; ///< Weather info that is shown in the UI + AirspaceAdvisoryProvider* _advisories = nullptr; ///< Advisory info that is shown in the UI QmlObjectListModel _polygonRestrictions; ///< current polygon restrictions QmlObjectListModel _circleRestrictions; ///< current circle restrictions diff --git a/src/AirspaceManagement/AirspaceRulesetsProvider.cc b/src/AirspaceManagement/AirspaceRulesetsProvider.cc index d6ec2ede6..5795ac297 100644 --- a/src/AirspaceManagement/AirspaceRulesetsProvider.cc +++ b/src/AirspaceManagement/AirspaceRulesetsProvider.cc @@ -9,6 +9,11 @@ #include "AirspaceRulesetsProvider.h" +AirspaceRule::AirspaceRule(QObject* parent) + : QObject(parent) +{ +} + AirspaceRulesetsProvider::AirspaceRulesetsProvider(QObject *parent) : QObject(parent) { diff --git a/src/AirspaceManagement/AirspaceRulesetsProvider.h b/src/AirspaceManagement/AirspaceRulesetsProvider.h index 49a0aa3f3..3d5aac357 100644 --- a/src/AirspaceManagement/AirspaceRulesetsProvider.h +++ b/src/AirspaceManagement/AirspaceRulesetsProvider.h @@ -15,20 +15,49 @@ * Base class that queries for airspace rulesets */ +#include "QmlObjectListModel.h" + #include #include +//----------------------------------------------------------------------------- +class AirspaceRule : public QObject +{ + Q_OBJECT +public: + AirspaceRule(QObject* parent = NULL); + + Q_PROPERTY(QString id READ id CONSTANT) + Q_PROPERTY(QString name READ name CONSTANT) + Q_PROPERTY(QString description READ description CONSTANT) + Q_PROPERTY(bool isDefault READ isDefault CONSTANT) + + virtual QString id () = 0; + virtual QString description () = 0; + virtual bool isDefault () = 0; + virtual QString name () = 0; +}; + +//----------------------------------------------------------------------------- class AirspaceRulesetsProvider : public QObject { Q_OBJECT public: - AirspaceRulesetsProvider (QObject* parent = NULL); - ~AirspaceRulesetsProvider () = default; + AirspaceRulesetsProvider (QObject* parent = NULL); + ~AirspaceRulesetsProvider () = default; + + Q_PROPERTY(bool valid READ valid NOTIFY rulesChanged) + Q_PROPERTY(QmlObjectListModel* rules READ rules NOTIFY rulesChanged) + + virtual bool valid () = 0; ///< Current ruleset is valid + virtual QmlObjectListModel* rules () = 0; ///< List of AirspaceRule + /** - * Set region of interest that should be queried. When finished, the requestDone() signal will be emmited. + * Set region of interest that should be queried. When finished, the rulesChanged() signal will be emmited. * @param center Center coordinate for ROI */ - virtual void setROI (const QGeoCoordinate& center) = 0; + virtual void setROI (const QGeoCoordinate& center) = 0; + signals: - void requestDone (bool success); + void rulesChanged (); }; -- 2.22.0