Commit d09847fc authored by Gus Grubba's avatar Gus Grubba Committed by Beat Küng

Make AirMapController as part of a Vehicle rather than a creatable QML...

Make AirMapController as part of a Vehicle rather than a creatable QML instance. This is ultimately linked to a vehicle and not the view. Eventually a lot of the code currently in AirMapManager will have to come here as well so the data persists with a vehicle. AirMapManager should only handle the global aspects.
Added a temporary indicator right below the toolbar. It's only visible if a permission (of any kind) exists. I need to understand better how this works before coming up with a more permanent solution.
Restored toolbar to its original state (brand logo and whatnot)
parent 06cf7dfa
...@@ -614,4 +614,50 @@ QGCView { ...@@ -614,4 +614,50 @@ QGCView {
visible: false 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
}
} }
...@@ -58,7 +58,9 @@ FlightMap { ...@@ -58,7 +58,9 @@ FlightMap {
// Track last known map position and zoom from Fly view in settings // Track last known map position and zoom from Fly view in settings
onZoomLevelChanged: QGroundControl.flightMapZoom = zoomLevel onZoomLevelChanged: QGroundControl.flightMapZoom = zoomLevel
onCenterChanged: { onCenterChanged: {
airMapController.setROI(center, 5000) if(_activeVehicle) {
_activeVehicle.airMapController.setROI(center, 5000)
}
QGroundControl.flightMapPosition = center QGroundControl.flightMapPosition = center
} }
...@@ -328,14 +330,8 @@ FlightMap { ...@@ -328,14 +330,8 @@ FlightMap {
} }
// AirMap overlap support // AirMap overlap support
AirMapController {
id: airMapController
}
MapItemView { MapItemView {
model: airMapController.circles model: _activeVehicle ? _activeVehicle.airMapController.circles : []
delegate: MapCircle { delegate: MapCircle {
center: object.center center: object.center
radius: object.radius radius: object.radius
...@@ -346,8 +342,7 @@ FlightMap { ...@@ -346,8 +342,7 @@ FlightMap {
} }
MapItemView { MapItemView {
model: airMapController.polygons model: _activeVehicle ? _activeVehicle.airMapController.polygons : []
delegate: MapPolygon { delegate: MapPolygon {
border.color: "white" border.color: "white"
color: "yellow" color: "yellow"
......
...@@ -361,6 +361,7 @@ void QGCApplication::_initCommon(void) ...@@ -361,6 +361,7 @@ void QGCApplication::_initCommon(void)
qmlRegisterUncreatableType<ParameterManager> ("QGroundControl.Vehicle", 1, 0, "ParameterManager", "Reference only"); qmlRegisterUncreatableType<ParameterManager> ("QGroundControl.Vehicle", 1, 0, "ParameterManager", "Reference only");
qmlRegisterUncreatableType<QGCCameraManager> ("QGroundControl.Vehicle", 1, 0, "QGCCameraManager", "Reference only"); qmlRegisterUncreatableType<QGCCameraManager> ("QGroundControl.Vehicle", 1, 0, "QGCCameraManager", "Reference only");
qmlRegisterUncreatableType<QGCCameraControl> ("QGroundControl.Vehicle", 1, 0, "QGCCameraControl", "Reference only"); qmlRegisterUncreatableType<QGCCameraControl> ("QGroundControl.Vehicle", 1, 0, "QGCCameraControl", "Reference only");
qmlRegisterUncreatableType<AirMapController> ("QGroundControl.Vehicle", 1, 0, "AirMapController", "Reference only");
qmlRegisterUncreatableType<JoystickManager> ("QGroundControl.JoystickManager", 1, 0, "JoystickManager", "Reference only"); qmlRegisterUncreatableType<JoystickManager> ("QGroundControl.JoystickManager", 1, 0, "JoystickManager", "Reference only");
qmlRegisterUncreatableType<Joystick> ("QGroundControl.JoystickManager", 1, 0, "Joystick", "Reference only"); qmlRegisterUncreatableType<Joystick> ("QGroundControl.JoystickManager", 1, 0, "Joystick", "Reference only");
qmlRegisterUncreatableType<QGCPositionManager> ("QGroundControl.QGCPositionManager", 1, 0, "QGCPositionManager", "Reference only"); qmlRegisterUncreatableType<QGCPositionManager> ("QGroundControl.QGCPositionManager", 1, 0, "QGCPositionManager", "Reference only");
...@@ -380,7 +381,6 @@ void QGCApplication::_initCommon(void) ...@@ -380,7 +381,6 @@ void QGCApplication::_initCommon(void)
qmlRegisterType<JoystickConfigController> ("QGroundControl.Controllers", 1, 0, "JoystickConfigController"); qmlRegisterType<JoystickConfigController> ("QGroundControl.Controllers", 1, 0, "JoystickConfigController");
qmlRegisterType<LogDownloadController> ("QGroundControl.Controllers", 1, 0, "LogDownloadController"); qmlRegisterType<LogDownloadController> ("QGroundControl.Controllers", 1, 0, "LogDownloadController");
qmlRegisterType<SyslinkComponentController> ("QGroundControl.Controllers", 1, 0, "SyslinkComponentController"); qmlRegisterType<SyslinkComponentController> ("QGroundControl.Controllers", 1, 0, "SyslinkComponentController");
qmlRegisterType<AirMapController> ("QGroundControl.Controllers", 1, 0, "AirMapController");
#ifndef __mobile__ #ifndef __mobile__
qmlRegisterType<ViewWidgetController> ("QGroundControl.Controllers", 1, 0, "ViewWidgetController"); qmlRegisterType<ViewWidgetController> ("QGroundControl.Controllers", 1, 0, "ViewWidgetController");
qmlRegisterType<CustomCommandWidgetController> ("QGroundControl.Controllers", 1, 0, "CustomCommandWidgetController"); qmlRegisterType<CustomCommandWidgetController> ("QGroundControl.Controllers", 1, 0, "CustomCommandWidgetController");
......
...@@ -33,6 +33,7 @@ ...@@ -33,6 +33,7 @@
#include "QGCCorePlugin.h" #include "QGCCorePlugin.h"
#include "ADSBVehicle.h" #include "ADSBVehicle.h"
#include "QGCCameraManager.h" #include "QGCCameraManager.h"
#include "AirMapController.h"
QGC_LOGGING_CATEGORY(VehicleLog, "VehicleLog") QGC_LOGGING_CATEGORY(VehicleLog, "VehicleLog")
...@@ -131,6 +132,7 @@ Vehicle::Vehicle(LinkInterface* link, ...@@ -131,6 +132,7 @@ Vehicle::Vehicle(LinkInterface* link,
, _rallyPointManager(NULL) , _rallyPointManager(NULL)
, _rallyPointManagerInitialRequestSent(false) , _rallyPointManagerInitialRequestSent(false)
, _parameterManager(NULL) , _parameterManager(NULL)
, _airMapController(NULL)
, _armed(false) , _armed(false)
, _base_mode(0) , _base_mode(0)
, _custom_mode(0) , _custom_mode(0)
...@@ -249,6 +251,7 @@ Vehicle::Vehicle(LinkInterface* link, ...@@ -249,6 +251,7 @@ Vehicle::Vehicle(LinkInterface* link,
_cameras = _firmwarePlugin->createCameraManager(this); _cameras = _firmwarePlugin->createCameraManager(this);
emit dynamicCamerasChanged(); emit dynamicCamerasChanged();
_airMapController = new AirMapController(this);
connect(qgcApp()->toolbox()->airMapManager(), &AirMapManager::trafficUpdate, this, &Vehicle::_trafficUpdate); connect(qgcApp()->toolbox()->airMapManager(), &AirMapManager::trafficUpdate, this, &Vehicle::_trafficUpdate);
} }
...@@ -308,6 +311,7 @@ Vehicle::Vehicle(MAV_AUTOPILOT firmwareType, ...@@ -308,6 +311,7 @@ Vehicle::Vehicle(MAV_AUTOPILOT firmwareType,
, _rallyPointManager(NULL) , _rallyPointManager(NULL)
, _rallyPointManagerInitialRequestSent(false) , _rallyPointManagerInitialRequestSent(false)
, _parameterManager(NULL) , _parameterManager(NULL)
, _airMapController(NULL)
, _armed(false) , _armed(false)
, _base_mode(0) , _base_mode(0)
, _custom_mode(0) , _custom_mode(0)
......
...@@ -35,6 +35,7 @@ class UASMessage; ...@@ -35,6 +35,7 @@ class UASMessage;
class SettingsManager; class SettingsManager;
class ADSBVehicle; class ADSBVehicle;
class QGCCameraManager; class QGCCameraManager;
class AirMapController;
Q_DECLARE_LOGGING_CATEGORY(VehicleLog) Q_DECLARE_LOGGING_CATEGORY(VehicleLog)
...@@ -320,6 +321,7 @@ public: ...@@ -320,6 +321,7 @@ public:
Q_PROPERTY(QVariantList staticCameraList READ staticCameraList CONSTANT) Q_PROPERTY(QVariantList staticCameraList READ staticCameraList CONSTANT)
Q_PROPERTY(QGCCameraManager* dynamicCameras READ dynamicCameras NOTIFY dynamicCamerasChanged) Q_PROPERTY(QGCCameraManager* dynamicCameras READ dynamicCameras NOTIFY dynamicCamerasChanged)
Q_PROPERTY(QString hobbsMeter READ hobbsMeter NOTIFY hobbsMeterChanged) Q_PROPERTY(QString hobbsMeter READ hobbsMeter NOTIFY hobbsMeterChanged)
Q_PROPERTY(AirMapController* airMapController READ airMapController CONSTANT)
// Vehicle state used for guided control // Vehicle state used for guided control
Q_PROPERTY(bool flying READ flying NOTIFY flyingChanged) ///< Vehicle is flying Q_PROPERTY(bool flying READ flying NOTIFY flyingChanged) ///< Vehicle is flying
...@@ -535,6 +537,8 @@ public: ...@@ -535,6 +537,8 @@ public:
QmlObjectListModel* cameraTriggerPoints(void) { return &_cameraTriggerPoints; } QmlObjectListModel* cameraTriggerPoints(void) { return &_cameraTriggerPoints; }
QmlObjectListModel* adsbVehicles(void) { return &_adsbVehicles; } QmlObjectListModel* adsbVehicles(void) { return &_adsbVehicles; }
AirMapController* airMapController() { return _airMapController; }
int flowImageIndex() { return _flowImageIndex; } int flowImageIndex() { return _flowImageIndex; }
//-- Mavlink Logging //-- Mavlink Logging
...@@ -992,6 +996,8 @@ private: ...@@ -992,6 +996,8 @@ private:
ParameterManager* _parameterManager; ParameterManager* _parameterManager;
AirMapController* _airMapController;
bool _armed; ///< true: vehicle is armed bool _armed; ///< true: vehicle is armed
uint8_t _base_mode; ///< base_mode from HEARTBEAT uint8_t _base_mode; ///< base_mode from HEARTBEAT
uint32_t _custom_mode; ///< custom_mode from HEARTBEAT uint32_t _custom_mode; ///< custom_mode from HEARTBEAT
......
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