Commit 066699f3 authored by Gus Grubba's avatar Gus Grubba

Removed AirspaceController and moved its interface into AirspaceManager

AirspaceManager is now exposed by QGroundControlQmlGlobal instead of Vehicle (available all the time)
parent 6cee3dfc
......@@ -1081,7 +1081,6 @@ contains (DEFINES, QGC_AIRMAP_ENABLED) {
HEADERS += \
src/AirspaceManagement/AirspaceAdvisoryProvider.h \
src/AirspaceManagement/AirspaceAuthorization.h \
src/AirspaceManagement/AirspaceController.h \
src/AirspaceManagement/AirspaceManager.h \
src/AirspaceManagement/AirspaceRestriction.h \
src/AirspaceManagement/AirspaceRestrictionProvider.h \
......@@ -1091,7 +1090,6 @@ contains (DEFINES, QGC_AIRMAP_ENABLED) {
SOURCES += \
src/AirspaceManagement/AirspaceAdvisoryProvider.cc \
src/AirspaceManagement/AirspaceController.cc \
src/AirspaceManagement/AirspaceManager.cc \
src/AirspaceManagement/AirspaceRestriction.cc \
src/AirspaceManagement/AirspaceRestrictionProvider.cc \
......
......@@ -30,11 +30,12 @@ using namespace airmap;
QGC_LOGGING_CATEGORY(AirMapManagerLog, "AirMapManagerLog")
//-----------------------------------------------------------------------------
AirMapManager::AirMapManager(QGCApplication* app, QGCToolbox* toolbox)
: AirspaceManager(app, toolbox)
{
_logger = std::make_shared<qt::Logger>();
qt::register_types(); // TODO: still needed?s
qt::register_types(); // TODO: still needed?
_logger->logging_category().setEnabled(QtDebugMsg, false);
_logger->logging_category().setEnabled(QtInfoMsg, false);
_logger->logging_category().setEnabled(QtWarningMsg, true);
......@@ -42,6 +43,7 @@ AirMapManager::AirMapManager(QGCApplication* app, QGCToolbox* toolbox)
connect(&_shared, &AirMapSharedState::error, this, &AirMapManager::_error);
}
//-----------------------------------------------------------------------------
AirMapManager::~AirMapManager()
{
if (_shared.client()) {
......@@ -49,6 +51,7 @@ AirMapManager::~AirMapManager()
}
}
//-----------------------------------------------------------------------------
void
AirMapManager::setToolbox(QGCToolbox* toolbox)
{
......@@ -61,6 +64,7 @@ AirMapManager::setToolbox(QGCToolbox* toolbox)
_settingsChanged();
}
//-----------------------------------------------------------------------------
void
AirMapManager::_error(const QString& what, const QString& airmapdMessage, const QString& airmapdDetails)
{
......@@ -68,6 +72,7 @@ AirMapManager::_error(const QString& what, const QString& airmapdMessage, const
qgcApp()->showMessage(QString("AirMap Error: %1. %2").arg(what).arg(airmapdMessage));
}
//-----------------------------------------------------------------------------
void
AirMapManager::_settingsChanged()
{
......@@ -80,7 +85,7 @@ AirMapManager::_settingsChanged()
settings.userName = ap->userName()->rawValueString();
settings.password = ap->password()->rawValueString();
_shared.setSettings(settings);
// need to re-create the client if the API key changed
//-- Need to re-create the client if the API key changed
if (_shared.client() && apiKeyChanged) {
delete _shared.client();
_shared.setClient(nullptr);
......@@ -104,6 +109,7 @@ AirMapManager::_settingsChanged()
}
}
//-----------------------------------------------------------------------------
AirspaceVehicleManager*
AirMapManager::instantiateVehicle(const Vehicle& vehicle)
{
......@@ -112,32 +118,36 @@ AirMapManager::instantiateVehicle(const Vehicle& vehicle)
return manager;
}
//-----------------------------------------------------------------------------
AirspaceRulesetsProvider*
AirMapManager::instantiateRulesetsProvider()
AirMapManager::_instantiateRulesetsProvider()
{
AirMapRulesetsManager* rulesetsManager = new AirMapRulesetsManager(_shared);
connect(rulesetsManager, &AirMapRulesetsManager::error, this, &AirMapManager::_error);
return rulesetsManager;
}
//-----------------------------------------------------------------------------
AirspaceWeatherInfoProvider*
AirMapManager::instatiateAirspaceWeatherInfoProvider()
AirMapManager::_instatiateAirspaceWeatherInfoProvider()
{
AirMapWeatherInfoManager* weatherInfo = new AirMapWeatherInfoManager(_shared);
connect(weatherInfo, &AirMapWeatherInfoManager::error, this, &AirMapManager::_error);
return weatherInfo;
}
//-----------------------------------------------------------------------------
AirspaceAdvisoryProvider*
AirMapManager::instatiateAirspaceAdvisoryProvider()
AirMapManager::_instatiateAirspaceAdvisoryProvider()
{
AirMapAdvisoryManager* advisories = new AirMapAdvisoryManager(_shared);
connect(advisories, &AirMapAdvisoryManager::error, this, &AirMapManager::_error);
return advisories;
}
//-----------------------------------------------------------------------------
AirspaceRestrictionProvider*
AirMapManager::instantiateAirspaceRestrictionProvider()
AirMapManager::_instantiateAirspaceRestrictionProvider()
{
AirMapRestrictionManager* airspaces = new AirMapRestrictionManager(_shared);
connect(airspaces, &AirMapRestrictionManager::error, this, &AirMapManager::_error);
......
......@@ -43,13 +43,14 @@ public:
void setToolbox (QGCToolbox* toolbox) override;
QString providerName () const override { return QString("AirMap"); }
AirspaceVehicleManager* instantiateVehicle (const Vehicle& vehicle) override;
AirspaceRulesetsProvider* instantiateRulesetsProvider () override;
AirspaceWeatherInfoProvider* instatiateAirspaceWeatherInfoProvider () override;
AirspaceAdvisoryProvider* instatiateAirspaceAdvisoryProvider () override;
AirspaceRestrictionProvider* instantiateAirspaceRestrictionProvider () override;
QString name () const override { return "AirMap"; }
protected:
AirspaceRulesetsProvider* _instantiateRulesetsProvider () override;
AirspaceWeatherInfoProvider* _instatiateAirspaceWeatherInfoProvider () override;
AirspaceAdvisoryProvider* _instatiateAirspaceAdvisoryProvider () override;
AirspaceRestrictionProvider* _instantiateAirspaceRestrictionProvider () override;
private slots:
void _error (const QString& what, const QString& airmapdMessage, const QString& airmapdDetails);
......
This diff is collapsed.
......@@ -5,21 +5,21 @@ import QtQuick.Dialogs 1.2
import QtQml 2.2
import QGroundControl 1.0
import QGroundControl.ScreenTools 1.0
import QGroundControl.Airmap 1.0
import QGroundControl.Airspace 1.0
import QGroundControl.Controls 1.0
import QGroundControl.Palette 1.0
import QGroundControl.Airmap 1.0
import QGroundControl.ScreenTools 1.0
import QGroundControl.SettingsManager 1.0
Item {
height: _valid ? weatherRow.height : 0
width: _valid ? weatherRow.width : 0
property color contentColor: "#ffffff"
property var iconHeight: ScreenTools.defaultFontPixelWidth * 4
property bool _valid: _activeVehicle && _activeVehicle.airspaceController.weatherInfo.valid
property var _activeVehicle: QGroundControl.multiVehicleManager.activeVehicle
property var iconHeight: ScreenTools.defaultFontPixelHeight * 2
property bool _valid: QGroundControl.airspaceManager.weatherInfo.valid
property bool _celcius: QGroundControl.settingsManager.unitsSettings.temperatureUnits.rawValue === UnitsSettings.TemperatureUnitsCelsius
property int _tempC: _valid ? _activeVehicle.airspaceController.weatherInfo.temperature : 0
property int _tempC: _valid ? QGroundControl.airspaceManager.weatherInfo.temperature : 0
property string _tempS: (_celcius ? _tempC : _tempC * 1.8 + 32).toFixed(0) + (_celcius ? "°C" : "°F")
Row {
id: weatherRow
......@@ -28,7 +28,7 @@ Item {
width: height
height: iconHeight
sourceSize.height: height
source: _valid ? _activeVehicle.airspaceController.weatherInfo.icon : ""
source: _valid ? QGroundControl.airspaceManager.weatherInfo.icon : ""
color: contentColor
visible: _valid
anchors.verticalCenter: parent.verticalCenter
......
......@@ -36,7 +36,7 @@
<file alias="mostly_cloudy_night.svg">images/weather-icons/mostly_cloudy_night.svg</file>
<file alias="mostly_sunny.svg">images/weather-icons/mostly_sunny.svg</file>
<file alias="partly_cloudy_day.svg">images/weather-icons/partly_cloudy_day.svg</file>
<file alias="partyly_cloudy_night.svg">images/weather-icons/partyly_cloudy_night.svg</file>
<file alias="partly_cloudy_night.svg">images/weather-icons/partly_cloudy_night.svg</file>
<file alias="rain.svg">images/weather-icons/rain.svg</file>
<file alias="rain_snow.svg">images/weather-icons/rain_snow.svg</file>
<file alias="scattered_snow_showers_day.svg">images/weather-icons/scattered_snow_showers_day.svg</file>
......
/****************************************************************************
*
* (c) 2009-2016 QGROUNDCONTROL PROJECT <http://www.qgroundcontrol.org>
*
* QGroundControl is licensed according to the terms in the file
* COPYING.md in the root of the source code directory.
*
****************************************************************************/
#include "AirspaceController.h"
#include "AirspaceManager.h"
#include "AirspaceWeatherInfoProvider.h"
#include "AirspaceAdvisoryProvider.h"
#include "QGCApplication.h"
#include "QGCQGeoCoordinate.h"
#include "QmlObjectListModel.h"
AirspaceController::AirspaceController(QObject* parent)
: QObject(parent)
, _manager(qgcApp()->toolbox()->airspaceManager())
, _airspaceVisible(false)
{
}
void
AirspaceController::setROI(QGeoCoordinate center, double radius)
{
_manager->setROI(center, radius);
}
QString
AirspaceController::providerName()
{
return _manager->name();
}
AirspaceWeatherInfoProvider*
AirspaceController::weatherInfo()
{
return _manager->weatherInfo();
}
AirspaceAdvisoryProvider*
AirspaceController::advisories()
{
return _manager->advisories();
}
AirspaceRulesetsProvider*
AirspaceController::ruleSets()
{
return _manager->ruleSets();
}
AirspaceRestrictionProvider*
AirspaceController::airspaces()
{
return _manager->airspaces();
}
/****************************************************************************
*
* (c) 2009-2016 QGROUNDCONTROL PROJECT <http://www.qgroundcontrol.org>
*
* QGroundControl is licensed according to the terms in the file
* COPYING.md in the root of the source code directory.
*
****************************************************************************/
#pragma once
#include <QObject>
#include <QGeoCoordinate>
class AirspaceManager;
class QmlObjectListModel;
class AirspaceWeatherInfoProvider;
class AirspaceAdvisoryProvider;
class AirspaceRulesetsProvider;
class AirspaceRestrictionProvider;
class AirspaceController : public QObject
{
Q_OBJECT
public:
AirspaceController(QObject* parent = NULL);
~AirspaceController() = default;
Q_PROPERTY(QString providerName READ providerName CONSTANT)
Q_PROPERTY(AirspaceWeatherInfoProvider* weatherInfo READ weatherInfo CONSTANT)
Q_PROPERTY(AirspaceAdvisoryProvider* advisories READ advisories CONSTANT)
Q_PROPERTY(AirspaceRulesetsProvider* ruleSets READ ruleSets CONSTANT)
Q_PROPERTY(AirspaceRestrictionProvider* airspaces READ airspaces CONSTANT)
Q_PROPERTY(bool airspaceVisible READ airspaceVisible WRITE setairspaceVisible NOTIFY airspaceVisibleChanged)
Q_INVOKABLE void setROI (QGeoCoordinate center, double radius);
QString providerName ();
AirspaceWeatherInfoProvider* weatherInfo ();
AirspaceAdvisoryProvider* advisories ();
AirspaceRulesetsProvider* ruleSets ();
AirspaceRestrictionProvider* airspaces ();
bool airspaceVisible () { return _airspaceVisible; }
void setairspaceVisible (bool set) { _airspaceVisible = set; emit airspaceVisibleChanged(); }
signals:
void airspaceVisibleChanged ();
private:
AirspaceManager* _manager;
bool _airspaceVisible;
};
......@@ -15,7 +15,6 @@
#include "AirspaceRulesetsProvider.h"
#include "AirspaceRestrictionProvider.h"
#include "AirspaceVehicleManager.h"
#include "AirspaceController.h"
#include "Vehicle.h"
#include "QGCApplication.h"
......@@ -24,20 +23,20 @@ QGC_LOGGING_CATEGORY(AirspaceManagementLog, "AirspaceManagementLog")
AirspaceManager::AirspaceManager(QGCApplication* app, QGCToolbox* toolbox)
: QGCTool(app, toolbox)
, _airspaceVisible(false)
{
_roiUpdateTimer.setInterval(2000);
_roiUpdateTimer.setSingleShot(true);
connect(&_roiUpdateTimer, &QTimer::timeout, this, &AirspaceManager::_updateToROI);
//-- TODO: Move these away from QGroundControl and into their own group (Airspace)
qmlRegisterUncreatableType<AirspaceAuthorization> ("QGroundControl", 1, 0, "AirspaceAuthorization", "Reference only");
qmlRegisterUncreatableType<AirspaceController> ("QGroundControl.Vehicle", 1, 0, "AirspaceController", "Reference only");
qmlRegisterUncreatableType<AirspaceWeatherInfoProvider> ("QGroundControl.Vehicle", 1, 0, "AirspaceWeatherInfoProvider", "Reference only");
qmlRegisterUncreatableType<AirspaceAdvisoryProvider> ("QGroundControl.Vehicle", 1, 0, "AirspaceAdvisoryProvider", "Reference only");
qmlRegisterUncreatableType<AirspaceRuleFeature> ("QGroundControl.Vehicle", 1, 0, "AirspaceRuleFeature", "Reference only");
qmlRegisterUncreatableType<AirspaceRule> ("QGroundControl.Vehicle", 1, 0, "AirspaceRule", "Reference only");
qmlRegisterUncreatableType<AirspaceRuleSet> ("QGroundControl.Vehicle", 1, 0, "AirspaceRuleSet", "Reference only");
qmlRegisterUncreatableType<AirspaceRulesetsProvider> ("QGroundControl.Vehicle", 1, 0, "AirspaceRulesetsProvider", "Reference only");
qmlRegisterUncreatableType<AirspaceRestrictionProvider> ("QGroundControl.Vehicle", 1, 0, "AirspaceRestrictionProvider", "Reference only");
qmlRegisterUncreatableType<AirspaceAdvisoryProvider> ("QGroundControl.Airspace", 1, 0, "AirspaceAdvisoryProvider", "Reference only");
qmlRegisterUncreatableType<AirspaceAuthorization> ("QGroundControl.Airspace", 1, 0, "AirspaceAuthorization", "Reference only");
qmlRegisterUncreatableType<AirspaceManager> ("QGroundControl.Airspace", 1, 0, "AirspaceManager", "Reference only");
qmlRegisterUncreatableType<AirspaceRestrictionProvider> ("QGroundControl.Airspace", 1, 0, "AirspaceRestrictionProvider", "Reference only");
qmlRegisterUncreatableType<AirspaceRule> ("QGroundControl.Airspace", 1, 0, "AirspaceRule", "Reference only");
qmlRegisterUncreatableType<AirspaceRuleFeature> ("QGroundControl.Airspace", 1, 0, "AirspaceRuleFeature", "Reference only");
qmlRegisterUncreatableType<AirspaceRuleSet> ("QGroundControl.Airspace", 1, 0, "AirspaceRuleSet", "Reference only");
qmlRegisterUncreatableType<AirspaceRulesetsProvider> ("QGroundControl.Airspace", 1, 0, "AirspaceRulesetsProvider", "Reference only");
qmlRegisterUncreatableType<AirspaceWeatherInfoProvider> ("QGroundControl.Airspace", 1, 0, "AirspaceWeatherInfoProvider", "Reference only");
}
AirspaceManager::~AirspaceManager()
......@@ -60,13 +59,18 @@ void AirspaceManager::setToolbox(QGCToolbox* toolbox)
{
QGCTool::setToolbox(toolbox);
// We should not call virtual methods in the constructor, so we instantiate the restriction provider here
_ruleSetsProvider = instantiateRulesetsProvider();
_weatherProvider = instatiateAirspaceWeatherInfoProvider();
_advisories = instatiateAirspaceAdvisoryProvider();
_airspaces = instantiateAirspaceRestrictionProvider();
_ruleSetsProvider = _instantiateRulesetsProvider();
_weatherProvider = _instatiateAirspaceWeatherInfoProvider();
_advisories = _instatiateAirspaceAdvisoryProvider();
_airspaces = _instantiateAirspaceRestrictionProvider();
}
void AirspaceManager::setROI(const QGeoCoordinate& center, double radiusMeters)
void AirspaceManager::setROI(QGeoCoordinate center, double radiusMeters)
{
_setROI(center, radiusMeters);
}
void AirspaceManager::_setROI(const QGeoCoordinate& center, double radiusMeters)
{
_roiCenter = center;
_roiRadius = radiusMeters;
......
......@@ -54,59 +54,74 @@ public:
AirspaceManager(QGCApplication* app, QGCToolbox* toolbox);
virtual ~AirspaceManager();
Q_PROPERTY(QString providerName READ providerName CONSTANT)
Q_PROPERTY(AirspaceWeatherInfoProvider* weatherInfo READ weatherInfo CONSTANT)
Q_PROPERTY(AirspaceAdvisoryProvider* advisories READ advisories CONSTANT)
Q_PROPERTY(AirspaceRulesetsProvider* ruleSets READ ruleSets CONSTANT)
Q_PROPERTY(AirspaceRestrictionProvider* airspaces READ airspaces CONSTANT)
Q_PROPERTY(bool airspaceVisible READ airspaceVisible WRITE setAirspaceVisible NOTIFY airspaceVisibleChanged)
Q_INVOKABLE void setROI (QGeoCoordinate center, double radius);
AirspaceWeatherInfoProvider* weatherInfo () { return _weatherProvider; }
AirspaceAdvisoryProvider* advisories () { return _advisories; }
AirspaceRulesetsProvider* ruleSets () { return _ruleSetsProvider; }
AirspaceRestrictionProvider* airspaces () { return _airspaces; }
void setToolbox(QGCToolbox* toolbox) override;
virtual QString providerName () const = 0; ///< Name of the airspace management provider (used in the UI)
virtual bool airspaceVisible () { return _airspaceVisible; }
virtual void setAirspaceVisible (bool set) { _airspaceVisible = set; emit airspaceVisibleChanged(); }
/**
* Factory method to create an AirspaceVehicleManager object
*/
virtual AirspaceVehicleManager* instantiateVehicle (const Vehicle& vehicle) = 0;
/**
* Factory method to create an AirspaceRulesetsProvider object
*/
virtual AirspaceRulesetsProvider* instantiateRulesetsProvider () = 0;
signals:
void airspaceVisibleChanged ();
protected:
/**
* Factory method to create an AirspaceRulesetsProvider object
* Set the ROI for airspace information (restrictions shown in UI)
* @param center Center coordinate for ROI
* @param radiusMeters Radius in meters around center which is of interest
*/
virtual AirspaceWeatherInfoProvider* instatiateAirspaceWeatherInfoProvider () = 0;
virtual void _setROI (const QGeoCoordinate& center, double radiusMeters);
/**
* Factory method to create an AirspaceAdvisoryProvider object
* Factory method to create an AirspaceRulesetsProvider object
*/
virtual AirspaceAdvisoryProvider* instatiateAirspaceAdvisoryProvider () = 0;
virtual AirspaceRulesetsProvider* _instantiateRulesetsProvider () = 0;
/**
* Factory method to create an AirspaceRestrictionProvider object
* Factory method to create an AirspaceRulesetsProvider object
*/
virtual AirspaceRestrictionProvider* instantiateAirspaceRestrictionProvider () = 0;
virtual AirspaceWeatherInfoProvider* _instatiateAirspaceWeatherInfoProvider () = 0;
/**
* Set the ROI for airspace information (restrictions shown in UI)
* @param center Center coordinate for ROI
* @param radiusMeters Radius in meters around center which is of interest
* Factory method to create an AirspaceAdvisoryProvider object
*/
void setROI (const QGeoCoordinate& center, double radiusMeters);
AirspaceWeatherInfoProvider* weatherInfo () { return _weatherProvider; }
AirspaceAdvisoryProvider* advisories () { return _advisories; }
AirspaceRulesetsProvider* ruleSets () { return _ruleSetsProvider; }
AirspaceRestrictionProvider* airspaces () { return _airspaces; }
void setToolbox(QGCToolbox* toolbox) override;
virtual AirspaceAdvisoryProvider* _instatiateAirspaceAdvisoryProvider () = 0;
/**
* Name of the airspace management provider (used in the UI)
* Factory method to create an AirspaceRestrictionProvider object
*/
virtual QString name () const = 0;
private:
void _updateToROI ();
virtual AirspaceRestrictionProvider* _instantiateAirspaceRestrictionProvider () = 0;
protected:
bool _airspaceVisible;
AirspaceRulesetsProvider* _ruleSetsProvider = nullptr; ///< Rulesets 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
AirspaceRestrictionProvider* _airspaces = nullptr; ///< Airspace info that is shown in the UI
QTimer _roiUpdateTimer;
QGeoCoordinate _roiCenter;
double _roiRadius;
private:
void _updateToROI ();
};
......@@ -19,14 +19,15 @@ import QtQuick.Layouts 1.2
import QtQuick.Window 2.2
import QGroundControl 1.0
import QGroundControl.Airspace 1.0
import QGroundControl.Controllers 1.0
import QGroundControl.Controls 1.0
import QGroundControl.FactSystem 1.0
import QGroundControl.FlightDisplay 1.0
import QGroundControl.FlightMap 1.0
import QGroundControl.ScreenTools 1.0
import QGroundControl.Controls 1.0
import QGroundControl.Palette 1.0
import QGroundControl.ScreenTools 1.0
import QGroundControl.Vehicle 1.0
import QGroundControl.Controllers 1.0
import QGroundControl.FactSystem 1.0
/// Flight Display View
QGCView {
......@@ -670,7 +671,7 @@ QGCView {
}
}
property var flightPermit: (QGroundControl.airmapSupported && _activeVehicle) ? _activeVehicle.flightPermitStatus : null
property var providerName: _activeVehicle ? _activeVehicle.airspaceController.providerName : ""
property var providerName: QGroundControl.airspaceManager.providerName
}
}
......@@ -15,13 +15,14 @@ import QtPositioning 5.3
import QtQuick.Dialogs 1.2
import QGroundControl 1.0
import QGroundControl.Airspace 1.0
import QGroundControl.Controllers 1.0
import QGroundControl.Controls 1.0
import QGroundControl.FlightDisplay 1.0
import QGroundControl.FlightMap 1.0
import QGroundControl.ScreenTools 1.0
import QGroundControl.Controls 1.0
import QGroundControl.Palette 1.0
import QGroundControl.ScreenTools 1.0
import QGroundControl.Vehicle 1.0
import QGroundControl.Controllers 1.0
FlightMap {
id: flightMap
......@@ -51,7 +52,7 @@ FlightMap {
property var _activeVehicleCoordinate: _activeVehicle ? _activeVehicle.coordinate : QtPositioning.coordinate()
property var _gotoHereCoordinate: QtPositioning.coordinate()
property real _toolButtonTopMargin: parent.height - ScreenTools.availableHeight + (ScreenTools.defaultFontPixelHeight / 2)
property bool _airspaceManagement: QGroundControl.airmapSupported && _activeVehicle
property bool _airspaceEnabled: QGroundControl.airmapSupported ? QGroundControl.settingsManager.airMapSettings.enableAirMap.rawValue : false
property bool _disableVehicleTracking: false
property bool _keepVehicleCentered: _mainIsMap ? false : true
......@@ -59,8 +60,8 @@ FlightMap {
// Track last known map position and zoom from Fly view in settings
onZoomLevelChanged: QGroundControl.flightMapZoom = zoomLevel
onCenterChanged: {
if(_activeVehicle && QGroundControl.airmapSupported) {
_activeVehicle.airspaceController.setROI(center, 5000)
if(_airspaceEnabled) {
QGroundControl.airspaceManager.setROI(center, 1000)
}
QGroundControl.flightMapPosition = center
}
......@@ -331,7 +332,7 @@ FlightMap {
// Airspace overlap support
MapItemView {
model: _airspaceManagement && _activeVehicle.airspaceController.airspaceVisible ? _activeVehicle.airspaceController.airspaces.circles : []
model: _airspaceEnabled && QGroundControl.airspaceManager.airspaceVisible ? QGroundControl.airspaceManager.airspaces.circles : []
delegate: MapCircle {
center: object.center
radius: object.radius
......@@ -341,7 +342,7 @@ FlightMap {
}
MapItemView {
model: _airspaceManagement && _activeVehicle.airspaceController.airspaceVisible ? _activeVehicle.airspaceController.airspaces.polygons : []
model: _airspaceEnabled && QGroundControl.airspaceManager.airspaceVisible ? QGroundControl.airspaceManager.airspaces.polygons : []
delegate: MapPolygon {
path: object.polygon
color: Qt.rgba(0.94, 0.87, 0, 0.15)
......
......@@ -21,6 +21,7 @@ import QGroundControl.Controls 1.0
import QGroundControl.Palette 1.0
import QGroundControl.Vehicle 1.0
import QGroundControl.FlightMap 1.0
import QGroundControl.Airspace 1.0
import QGroundControl.Airmap 1.0
Item {
......@@ -29,12 +30,12 @@ Item {
property var qgcView
property bool useLightColors
property var missionController
property bool showValues: _activeVehicle ? !_activeVehicle.airspaceController.airspaceVisible : true
property bool showValues: QGroundControl.airspaceManager.airspaceVisible
property var _activeVehicle: QGroundControl.multiVehicleManager.activeVehicle
property bool _isSatellite: _mainIsMap ? (_flightMap ? _flightMap.isSatelliteMap : true) : true
property bool _lightWidgetBorders: _isSatellite
property bool _enableAirMap: QGroundControl.airmapSupported ? QGroundControl.settingsManager.airMapSettings.enableAirMap.rawValue : false
property bool _airspaceEnabled: QGroundControl.airmapSupported ? QGroundControl.settingsManager.airMapSettings.enableAirMap.rawValue : false
readonly property real _margins: ScreenTools.defaultFontPixelHeight * 0.5
......@@ -80,11 +81,9 @@ Item {
}
Connections {
target: _activeVehicle ? _activeVehicle.airspaceController : null
target: QGroundControl.airspaceManager
onAirspaceVisibleChanged: {
if(_activeVehicle) {
widgetRoot.showValues = !_activeVehicle.airspaceController.airspaceVisible
}
widgetRoot.showValues = !QGroundControl.airspaceManager.airspaceVisible
}
}
......@@ -140,7 +139,7 @@ Item {
AirspaceControl {
id: airspaceControl
width: getPreferredInstrumentWidth()
visible: _enableAirMap
visible: _airspaceEnabled
anchors.margins: ScreenTools.defaultFontPixelHeight * 0.5
}
//-------------------------------------------------------
......
......@@ -25,6 +25,7 @@ import QGroundControl.FactControls 1.0
import QGroundControl.Palette 1.0
import QGroundControl.Mavlink 1.0
import QGroundControl.Controllers 1.0
import QGroundControl.Airspace 1.0
import QGroundControl.Airmap 1.0
/// Mission Editor
......@@ -46,7 +47,7 @@ QGCView {
readonly property var _defaultVehicleCoordinate: QtPositioning.coordinate(37.803784, -122.462276)
readonly property bool _waypointsOnlyMode: QGroundControl.corePlugin.options.missionWaypointsOnly
property bool _enableAirMap: QGroundControl.airmapSupported ? QGroundControl.settingsManager.airMapSettings.enableAirMap.rawValue : false
property bool _airspaceEnabled: QGroundControl.airmapSupported ? QGroundControl.settingsManager.airMapSettings.enableAirMap.rawValue : false
property var _planMasterController: masterController
property var _missionController: _planMasterController.missionController
property var _geoFenceController: _planMasterController.geoFenceController
......@@ -59,7 +60,6 @@ QGCView {
property real _toolbarHeight: _qgcView.height - ScreenTools.availableHeight
property int _editingLayer: _layerMission
property int _toolStripBottom: toolStrip.height + toolStrip.y
property bool _airspaceManagement: QGroundControl.airmapSupported && _activeVehicle
readonly property int _layerMission: 1
readonly property int _layerGeoFence: 2
......@@ -96,12 +96,10 @@ QGCView {
planMasterController: _planMasterController
}
on_EnableAirMapChanged: {
on_AirspaceEnabledChanged: {
if(QGroundControl.airmapSupported) {
if(!_activeVehicle) {
planControlColapsed = false
} else if(_enableAirMap) {
planControlColapsed = _activeVehicle.airspaceController.airspaceVisible
if(_airspaceEnabled) {
planControlColapsed = QGroundControl.airspaceManager.airspaceVisible
} else {
planControlColapsed = false
}
......@@ -167,9 +165,9 @@ QGCView {
}
Connections {
target: _activeVehicle ? _activeVehicle.airspaceController : null
target: QGroundControl.airspaceManager
onAirspaceVisibleChanged: {
planControlColapsed = _activeVehicle.airspaceController.airspaceVisible
planControlColapsed = QGroundControl.airspaceManager.airspaceVisible
}
}
......@@ -350,8 +348,8 @@ QGCView {
QGCMapPalette { id: mapPal; lightColors: editorMap.isSatelliteMap }
onCenterChanged: {
if(_activeVehicle && QGroundControl.airmapSupported) {
_activeVehicle.airspaceController.setROI(center, 5000)
if(_airspaceEnabled) {
QGroundControl.airspaceManager.setROI(center, 5000)
}
}
......@@ -439,7 +437,7 @@ QGCView {
// Airspace overlap support
MapItemView {
model: _airspaceManagement && _activeVehicle.airspaceController.airspaceVisible ? _activeVehicle.airspaceController.airspaces.circles : []
model: _airspaceEnabled && QGroundControl.airspaceManager.airspaceVisible ? QGroundControl.airspaceManager.airspaces.circles : []
delegate: MapCircle {
center: object.center
radius: object.radius
......@@ -449,7 +447,7 @@ QGCView {
}
MapItemView {
model: _airspaceManagement && _activeVehicle.airspaceController.airspaceVisible ? _activeVehicle.airspaceController.airspaces.polygons : []
model: _airspaceEnabled && QGroundControl.airspaceManager.airspaceVisible ? QGroundControl.airspaceManager.airspaces.polygons : []
delegate: MapPolygon {
path: object.polygon
color: Qt.rgba(0.94, 0.87, 0, 0.1)
......@@ -565,7 +563,7 @@ QGCView {
AirspaceControl {
id: airspaceControl
width: parent.width
visible: _enableAirMap
visible: _airspaceEnabled
showColapse: true
}
//-------------------------------------------------------
......@@ -575,7 +573,7 @@ QGCView {
height: planControlColapsed ? colapsedRow.height + ScreenTools.defaultFontPixelHeight : 0
color: qgcPal.missionItemEditor
radius: _radius
visible: planControlColapsed && _enableAirMap
visible: planControlColapsed && _airspaceEnabled
Row {
id: colapsedRow
spacing: ScreenTools.defaultFontPixelWidth
......@@ -611,9 +609,7 @@ QGCView {
anchors.fill: parent
enabled: QGroundControl.airmapSupported
onClicked: {
if(_activeVehicle) {
_activeVehicle.airspaceController.airspaceVisible = false
}
QGroundControl.airspaceManager.airspaceVisible = false
}
}
}
......@@ -622,10 +618,10 @@ QGCView {
Rectangle {
id: planExpanded
width: parent.width
height: (!planControlColapsed || !_enableAirMap) ? expandedCol.height + ScreenTools.defaultFontPixelHeight : 0
height: (!planControlColapsed || !_airspaceEnabled) ? expandedCol.height + ScreenTools.defaultFontPixelHeight : 0
color: qgcPal.missionItemEditor
radius: _radius
visible: !planControlColapsed || !_enableAirMap
visible: !planControlColapsed || !_airspaceEnabled
Item {
height: expandedCol.height
anchors.left: parent.left
......
......@@ -40,6 +40,7 @@ QGroundControlQmlGlobal::QGroundControlQmlGlobal(QGCApplication* app, QGCToolbox
, _corePlugin(NULL)
, _firmwarePluginManager(NULL)
, _settingsManager(NULL)
, _airspaceManager(NULL)
, _skipSetupPage(false)
{
// We clear the parent on this object since we run into shutdown problems caused by hybrid qml app. Instead we let it leak on shutdown.
......@@ -76,6 +77,7 @@ void QGroundControlQmlGlobal::setToolbox(QGCToolbox* toolbox)
_corePlugin = toolbox->corePlugin();
_firmwarePluginManager = toolbox->firmwarePluginManager();
_settingsManager = toolbox->settingsManager();
_airspaceManager = toolbox->airspaceManager();
#ifndef __mobile__
GPSManager *gpsManager = toolbox->gpsManager();
......
......@@ -22,6 +22,7 @@
#include "SimulatedPosition.h"
#include "QGCLoggingCategory.h"
#include "AppSettings.h"
#include "AirspaceManager.h"
#ifndef __mobile__
#include "GPS/GPSManager.h"
#endif /* __mobile__ */
......@@ -53,6 +54,7 @@ public:
Q_PROPERTY(QGCCorePlugin* corePlugin READ corePlugin CONSTANT)
Q_PROPERTY(SettingsManager* settingsManager READ settingsManager CONSTANT)
Q_PROPERTY(FactGroup* gpsRtk READ gpsRtkFactGroup CONSTANT)
Q_PROPERTY(AirspaceManager* airspaceManager READ airspaceManager CONSTANT)
Q_PROPERTY(bool airmapSupported READ airmapSupported CONSTANT)
Q_PROPERTY(int supportedFirmwareCount READ supportedFirmwareCount CONSTANT)
......@@ -143,6 +145,7 @@ public:
QGCCorePlugin* corePlugin () { return _corePlugin; }
SettingsManager* settingsManager () { return _settingsManager; }
FactGroup* gpsRtkFactGroup () { return &_gpsRtkFactGroup; }
AirspaceManager* airspaceManager () { return _airspaceManager; }
static QGeoCoordinate flightMapPosition () { return _coord; }
static double flightMapZoom () { return _zoom; }
......@@ -208,6 +211,7 @@ private:
FirmwarePluginManager* _firmwarePluginManager;
SettingsManager* _settingsManager;
GPSRTKFactGroup _gpsRtkFactGroup;
AirspaceManager* _airspaceManager;
bool _skipSetupPage;
......
......@@ -38,9 +38,6 @@
#include "QGCCameraManager.h"
#include "VideoReceiver.h"
#include "VideoManager.h"
#if defined(QGC_AIRMAP_ENABLED)
#include "AirspaceController.h"
#endif
QGC_LOGGING_CATEGORY(VehicleLog, "VehicleLog")
#define UPDATE_TIMER 50
......@@ -142,7 +139,6 @@ Vehicle::Vehicle(LinkInterface* link,
, _rallyPointManagerInitialRequestSent(false)
, _parameterManager(NULL)
#if defined(QGC_AIRMAP_ENABLED)
, _airspaceController(NULL)
, _airspaceVehicleManager(NULL)
#endif
, _armed(false)
......@@ -276,18 +272,6 @@ Vehicle::Vehicle(LinkInterface* link,
connect(&_adsbTimer, &QTimer::timeout, this, &Vehicle::_adsbTimerTimeout);
_adsbTimer.setSingleShot(false);
_adsbTimer.start(1000);
#if defined(QGC_AIRMAP_ENABLED)
_airspaceController = new AirspaceController(this);
AirspaceManager* airspaceManager = _toolbox->airspaceManager();
if (airspaceManager) {
_airspaceVehicleManager = airspaceManager->instantiateVehicle(*this);
if (_airspaceVehicleManager) {
connect(_airspaceVehicleManager, &AirspaceVehicleManager::trafficUpdate, this, &Vehicle::_trafficUpdate);
connect(_airspaceVehicleManager, &AirspaceVehicleManager::flightPermitStatusChanged, this, &Vehicle::flightPermitStatusChanged);
}
}
#endif
}
// Disconnected Vehicle for offline editing
......@@ -349,7 +333,6 @@ Vehicle::Vehicle(MAV_AUTOPILOT firmwareType,
, _rallyPointManagerInitialRequestSent(false)
, _parameterManager(NULL)
#if defined(QGC_AIRMAP_ENABLED)
, _airspaceController(NULL)
, _airspaceVehicleManager(NULL)
#endif
, _armed(false)
......@@ -470,6 +453,18 @@ void Vehicle::_commonInit(void)
_flightDistanceFact.setRawValue(0);
_flightTimeFact.setRawValue(0);
//-- Airspace Management
#if defined(QGC_AIRMAP_ENABLED)
AirspaceManager* airspaceManager = _toolbox->airspaceManager();
if (airspaceManager) {
_airspaceVehicleManager = airspaceManager->instantiateVehicle(*this);
if (_airspaceVehicleManager) {
connect(_airspaceVehicleManager, &AirspaceVehicleManager::trafficUpdate, this, &Vehicle::_trafficUpdate);
connect(_airspaceVehicleManager, &AirspaceVehicleManager::flightPermitStatusChanged, this, &Vehicle::flightPermitStatusChanged);
}
}
#endif
}
Vehicle::~Vehicle()
......
......@@ -39,9 +39,6 @@ class UASMessage;
class SettingsManager;
class ADSBVehicle;
class QGCCameraManager;
#if defined(QGC_AIRMAP_ENABLED)
class AirspaceController;
#endif
Q_DECLARE_LOGGING_CATEGORY(VehicleLog)
......@@ -362,7 +359,6 @@ public:
Q_PROPERTY(bool highLatencyLink READ highLatencyLink NOTIFY highLatencyLinkChanged)
#if defined(QGC_AIRMAP_ENABLED)
Q_PROPERTY(AirspaceAuthorization::PermitStatus flightPermitStatus READ flightPermitStatus NOTIFY flightPermitStatusChanged) ///< state of flight permission
Q_PROPERTY(AirspaceController* airspaceController READ airspaceController CONSTANT)
#endif
// Vehicle state used for guided control
Q_PROPERTY(bool flying READ flying NOTIFY flyingChanged) ///< Vehicle is flying
......@@ -582,9 +578,6 @@ public:
QmlObjectListModel* cameraTriggerPoints(void) { return &_cameraTriggerPoints; }
QmlObjectListModel* adsbVehicles(void) { return &_adsbVehicles; }
#if defined(QGC_AIRMAP_ENABLED)
AirspaceController* airspaceController() { return _airspaceController; }
#endif
int flowImageIndex() { return _flowImageIndex; }
//-- Mavlink Logging
......@@ -1068,7 +1061,6 @@ private:
ParameterManager* _parameterManager;
#if defined(QGC_AIRMAP_ENABLED)
AirspaceController* _airspaceController;
AirspaceVehicleManager* _airspaceVehicleManager;
#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