diff --git a/src/FlightDisplay/FlightDisplayView.qml b/src/FlightDisplay/FlightDisplayView.qml index 3c87dc13aa576040dca443faee06d60d178dd8a3..b0066941605734ae42b264acee62d5dcb15c2b7b 100644 --- a/src/FlightDisplay/FlightDisplayView.qml +++ b/src/FlightDisplay/FlightDisplayView.qml @@ -614,4 +614,50 @@ QGCView { visible: false } } + + //-- AirMap Indicator + Rectangle { + id: airMapIndicator + width: airMapRow.width + (ScreenTools.defaultFontPixelWidth * 3) + height: airMapRow.height * 1.25 + color: qgcPal.globalTheme === QGCPalette.Light ? Qt.rgba(1,1,1,0.95) : Qt.rgba(0,0,0,0.75) + visible: _mainIsMap && flightPermit && flightPermit !== AirspaceAuthorization.PermitUnknown && !messageArea.visible && !criticalMmessageArea.visible + radius: 3 + border.width: 1 + border.color: qgcPal.globalTheme === QGCPalette.Light ? Qt.rgba(0,0,0,0.35) : Qt.rgba(1,1,1,0.35) + anchors.top: parent.top + anchors.topMargin: ScreenTools.toolbarHeight + (ScreenTools.defaultFontPixelHeight * 0.25) + anchors.horizontalCenter: parent.horizontalCenter + Row { + id: airMapRow + spacing: ScreenTools.defaultFontPixelWidth + anchors.centerIn: parent + QGCLabel { text: qsTr("AirMap:"); anchors.verticalCenter: parent.verticalCenter; } + QGCLabel { + text: { + if(airMapIndicator.flightPermit) { + if(airMapIndicator.flightPermit === AirspaceAuthorization.PermitPending) + return qsTr("Approval Pending") + if(airMapIndicator.flightPermit === AirspaceAuthorization.PermitAccepted) + return qsTr("Flight Approved") + if(airMapIndicator.flightPermit === AirspaceAuthorization.PermitRejected) + return qsTr("Flight Denied") + } + return "" + } + color: { + if(airMapIndicator.flightPermit) { + if(airMapIndicator.flightPermit === AirspaceAuthorization.PermitPending) + return qgcPal.colorOrange + if(airMapIndicator.flightPermit === AirspaceAuthorization.PermitAccepted) + return qgcPal.colorGreen + } + return qgcPal.colorRed + } + anchors.verticalCenter: parent.verticalCenter; + } + } + property var flightPermit: _activeVehicle ? _activeVehicle.airMapController.flightPermitStatus : null + } + } diff --git a/src/FlightDisplay/FlightDisplayViewMap.qml b/src/FlightDisplay/FlightDisplayViewMap.qml index 6419b4cad30c00a57b090ff80aee3df490d63951..f289648090f4f0f42bf8c5714461ae48045b17f3 100644 --- a/src/FlightDisplay/FlightDisplayViewMap.qml +++ b/src/FlightDisplay/FlightDisplayViewMap.qml @@ -58,7 +58,9 @@ FlightMap { // Track last known map position and zoom from Fly view in settings onZoomLevelChanged: QGroundControl.flightMapZoom = zoomLevel onCenterChanged: { - airMapController.setROI(center, 5000) + if(_activeVehicle) { + _activeVehicle.airMapController.setROI(center, 5000) + } QGroundControl.flightMapPosition = center } @@ -328,14 +330,8 @@ FlightMap { } // AirMap overlap support - - AirMapController { - id: airMapController - } - MapItemView { - model: airMapController.circles - + model: _activeVehicle ? _activeVehicle.airMapController.circles : [] delegate: MapCircle { center: object.center radius: object.radius @@ -346,8 +342,7 @@ FlightMap { } MapItemView { - model: airMapController.polygons - + model: _activeVehicle ? _activeVehicle.airMapController.polygons : [] delegate: MapPolygon { border.color: "white" color: "yellow" diff --git a/src/QGCApplication.cc b/src/QGCApplication.cc index 0822645ca528427a2b2bf2d54556cd47d7284b2b..9f31e124ee945e0527591680ff267378908b6105 100644 --- a/src/QGCApplication.cc +++ b/src/QGCApplication.cc @@ -361,6 +361,7 @@ void QGCApplication::_initCommon(void) qmlRegisterUncreatableType ("QGroundControl.Vehicle", 1, 0, "ParameterManager", "Reference only"); qmlRegisterUncreatableType ("QGroundControl.Vehicle", 1, 0, "QGCCameraManager", "Reference only"); qmlRegisterUncreatableType ("QGroundControl.Vehicle", 1, 0, "QGCCameraControl", "Reference only"); + qmlRegisterUncreatableType ("QGroundControl.Vehicle", 1, 0, "AirMapController", "Reference only"); qmlRegisterUncreatableType ("QGroundControl.JoystickManager", 1, 0, "JoystickManager", "Reference only"); qmlRegisterUncreatableType ("QGroundControl.JoystickManager", 1, 0, "Joystick", "Reference only"); qmlRegisterUncreatableType ("QGroundControl.QGCPositionManager", 1, 0, "QGCPositionManager", "Reference only"); @@ -380,7 +381,6 @@ void QGCApplication::_initCommon(void) qmlRegisterType ("QGroundControl.Controllers", 1, 0, "JoystickConfigController"); qmlRegisterType ("QGroundControl.Controllers", 1, 0, "LogDownloadController"); qmlRegisterType ("QGroundControl.Controllers", 1, 0, "SyslinkComponentController"); - qmlRegisterType ("QGroundControl.Controllers", 1, 0, "AirMapController"); #ifndef __mobile__ qmlRegisterType ("QGroundControl.Controllers", 1, 0, "ViewWidgetController"); qmlRegisterType ("QGroundControl.Controllers", 1, 0, "CustomCommandWidgetController"); diff --git a/src/Vehicle/Vehicle.cc b/src/Vehicle/Vehicle.cc index 84e03a7a39a8f1ed39092abb5061403096e92da3..99a946534239294f8081c34176d7318b29bcf581 100644 --- a/src/Vehicle/Vehicle.cc +++ b/src/Vehicle/Vehicle.cc @@ -33,6 +33,7 @@ #include "QGCCorePlugin.h" #include "ADSBVehicle.h" #include "QGCCameraManager.h" +#include "AirMapController.h" QGC_LOGGING_CATEGORY(VehicleLog, "VehicleLog") @@ -131,6 +132,7 @@ Vehicle::Vehicle(LinkInterface* link, , _rallyPointManager(NULL) , _rallyPointManagerInitialRequestSent(false) , _parameterManager(NULL) + , _airMapController(NULL) , _armed(false) , _base_mode(0) , _custom_mode(0) @@ -249,6 +251,7 @@ Vehicle::Vehicle(LinkInterface* link, _cameras = _firmwarePlugin->createCameraManager(this); emit dynamicCamerasChanged(); + _airMapController = new AirMapController(this); connect(qgcApp()->toolbox()->airMapManager(), &AirMapManager::trafficUpdate, this, &Vehicle::_trafficUpdate); } @@ -308,6 +311,7 @@ Vehicle::Vehicle(MAV_AUTOPILOT firmwareType, , _rallyPointManager(NULL) , _rallyPointManagerInitialRequestSent(false) , _parameterManager(NULL) + , _airMapController(NULL) , _armed(false) , _base_mode(0) , _custom_mode(0) diff --git a/src/Vehicle/Vehicle.h b/src/Vehicle/Vehicle.h index f7362fcda885d96392ddfffa6e032aba4d7d8d5a..448a0c422ae7f72de5eb63498f94ed1f8417601f 100644 --- a/src/Vehicle/Vehicle.h +++ b/src/Vehicle/Vehicle.h @@ -35,6 +35,7 @@ class UASMessage; class SettingsManager; class ADSBVehicle; class QGCCameraManager; +class AirMapController; Q_DECLARE_LOGGING_CATEGORY(VehicleLog) @@ -320,6 +321,7 @@ public: Q_PROPERTY(QVariantList staticCameraList READ staticCameraList CONSTANT) Q_PROPERTY(QGCCameraManager* dynamicCameras READ dynamicCameras NOTIFY dynamicCamerasChanged) Q_PROPERTY(QString hobbsMeter READ hobbsMeter NOTIFY hobbsMeterChanged) + Q_PROPERTY(AirMapController* airMapController READ airMapController CONSTANT) // Vehicle state used for guided control Q_PROPERTY(bool flying READ flying NOTIFY flyingChanged) ///< Vehicle is flying @@ -535,6 +537,8 @@ public: QmlObjectListModel* cameraTriggerPoints(void) { return &_cameraTriggerPoints; } QmlObjectListModel* adsbVehicles(void) { return &_adsbVehicles; } + AirMapController* airMapController() { return _airMapController; } + int flowImageIndex() { return _flowImageIndex; } //-- Mavlink Logging @@ -990,7 +994,9 @@ private: RallyPointManager* _rallyPointManager; bool _rallyPointManagerInitialRequestSent; - ParameterManager* _parameterManager; + ParameterManager* _parameterManager; + + AirMapController* _airMapController; bool _armed; ///< true: vehicle is armed uint8_t _base_mode; ///< base_mode from HEARTBEAT