diff --git a/src/AutoPilotPlugins/APM/APMAirframeComponentSummary.qml b/src/AutoPilotPlugins/APM/APMAirframeComponentSummary.qml index e53930ff29544b970e9972794c73b188d8767541..3e8f49b427e4a79e3804e49cb29c25c7b44037c9 100644 --- a/src/AutoPilotPlugins/APM/APMAirframeComponentSummary.qml +++ b/src/AutoPilotPlugins/APM/APMAirframeComponentSummary.qml @@ -33,7 +33,7 @@ Item { VehicleSummaryRow { labelText: qsTr("Firmware Version") - valueText: activeVehicle.firmwareMajorVersion == -1 ? qsTr("Unknown") : activeVehicle.firmwareMajorVersion + "." + activeVehicle.firmwareMinorVersion + "." + activeVehicle.firmwarePatchVersion + activeVehicle.firmwareVersionTypeString + valueText: globals.activeVehicle.firmwareMajorVersion == -1 ? qsTr("Unknown") : globals.activeVehicle.firmwareMajorVersion + "." + globals.activeVehicle.firmwareMinorVersion + "." + globals.activeVehicle.firmwarePatchVersion + globals.activeVehicle.firmwareVersionTypeString } } } diff --git a/src/AutoPilotPlugins/APM/APMCameraSubComponent.qml b/src/AutoPilotPlugins/APM/APMCameraSubComponent.qml index 005d37d10e99cba35d4b657cf6a5d1a34772d853..2ba21c449b2e33bfd1b54da6f3ab5ca2751db58d 100644 --- a/src/AutoPilotPlugins/APM/APMCameraSubComponent.qml +++ b/src/AutoPilotPlugins/APM/APMCameraSubComponent.qml @@ -35,7 +35,7 @@ SetupPage { QGCPalette { id: palette; colorGroupEnabled: true } - property bool _oldFW: !(activeVehicle.firmwareMajorVersion > 3 || activeVehicle.firmwareMinorVersion > 5 || activeVehicle.firmwarePatchVersion >= 2) + property bool _oldFW: !(globals.activeVehicle.firmwareMajorVersion > 3 || globals.activeVehicle.firmwareMinorVersion > 5 || globals.activeVehicle.firmwarePatchVersion >= 2) property Fact _mountRetractX: controller.getParameterFact(-1, "MNT_RETRACT_X") property Fact _mountRetractY: controller.getParameterFact(-1, "MNT_RETRACT_Y") diff --git a/src/AutoPilotPlugins/APM/APMSafetyComponentSub.qml b/src/AutoPilotPlugins/APM/APMSafetyComponentSub.qml index 6a926d5239b23fee3e8184165ae35450d17207ab..2a61cd96ab5432b7bdf7d60b717ffa768d5e4436 100644 --- a/src/AutoPilotPlugins/APM/APMSafetyComponentSub.qml +++ b/src/AutoPilotPlugins/APM/APMSafetyComponentSub.qml @@ -35,7 +35,7 @@ SetupPage { QGCPalette { id: ggcPal; colorGroupEnabled: true } - property bool _firmware34: activeVehicle.versionCompare(3, 5, 0) < 0 + property bool _firmware34: globals.activeVehicle.versionCompare(3, 5, 0) < 0 // Enable/Action parameters property Fact _failsafeBatteryEnable: controller.getParameterFact(-1, "r.BATT_FS_LOW_ACT") diff --git a/src/AutoPilotPlugins/APM/APMSafetyComponentSummarySub.qml b/src/AutoPilotPlugins/APM/APMSafetyComponentSummarySub.qml index 23a5350ae2bb56693005f5abdb0ce6ce3454fa2c..82896194d577b70654b1a4f71729c72f2a4ead7c 100644 --- a/src/AutoPilotPlugins/APM/APMSafetyComponentSummarySub.qml +++ b/src/AutoPilotPlugins/APM/APMSafetyComponentSummarySub.qml @@ -10,7 +10,7 @@ import QGroundControl.Palette 1.0 Item { anchors.fill: parent - property bool _firmware34: activeVehicle.versionCompare(3, 5, 0) < 0 + property bool _firmware34: globals.activeVehicle.versionCompare(3, 5, 0) < 0 FactPanelController { id: controller; } diff --git a/src/AutoPilotPlugins/APM/APMSensorsComponent.qml b/src/AutoPilotPlugins/APM/APMSensorsComponent.qml index 82a1ad6e2f1f64729027d101da63fba27acc9c5b..55dd6905fb67487ee92f8b080bc47178fa9f3c64 100644 --- a/src/AutoPilotPlugins/APM/APMSensorsComponent.qml +++ b/src/AutoPilotPlugins/APM/APMSensorsComponent.qml @@ -178,7 +178,7 @@ SetupPage { Component.onCompleted: { var usingUDP = controller.usingUDPLink() - var isSub = QGroundControl.multiVehicleManager.activeVehicle.sub; + var isSub = globals.activeVehicle.sub; if (usingUDP && !isSub) { mainWindow.showMessageDialog(qsTr("Sensor Calibration"), qsTr("Performing sensor calibration over a WiFi connection can be unreliable. If you run into problems try using a direct USB connection instead.")) } @@ -562,9 +562,9 @@ SetupPage { wrapMode: Text.WordWrap text: _helpText - readonly property string _altText: activeVehicle.sub ? qsTr("depth") : qsTr("altitude") + readonly property string _altText: globals.activeVehicle.sub ? qsTr("depth") : qsTr("altitude") readonly property string _helpText: qsTr("Pressure calibration will set the %1 to zero at the current pressure reading. %2").arg(_altText).arg(_helpTextFW) - readonly property string _helpTextFW: activeVehicle.fixedWing ? qsTr("To calibrate the airspeed sensor shield it from the wind. Do not touch the sensor or obstruct any holes during the calibration.") : "" + readonly property string _helpTextFW: globals.activeVehicle.fixedWing ? qsTr("To calibrate the airspeed sensor shield it from the wind. Do not touch the sensor or obstruct any holes during the calibration.") : "" } } // QGCViewDialog } // Component - calibratePressureDialogComponent @@ -644,7 +644,7 @@ SetupPage { QGCButton { width: _buttonWidth text: qsTr("Gyro") - visible: activeVehicle && (activeVehicle.multiRotor | activeVehicle.rover) + visible: globals.activeVehicle && (globals.activeVehicle.multiRotor | globals.activeVehicle.rover) onClicked: mainWindow.showComponentDialog(calibrateGyroDialogComponent, qsTr("Calibrate Gyro"), mainWindow.showDialogDefaultWidth, StandardButton.Cancel | StandardButton.Ok) } @@ -653,13 +653,13 @@ SetupPage { text: _calibratePressureText onClicked: mainWindow.showComponentDialog(calibratePressureDialogComponent, _calibratePressureText, mainWindow.showDialogDefaultWidth, StandardButton.Cancel | StandardButton.Ok) - readonly property string _calibratePressureText: activeVehicle.fixedWing ? qsTr("Baro/Airspeed") : qsTr("Pressure") + readonly property string _calibratePressureText: globals.activeVehicle.fixedWing ? qsTr("Baro/Airspeed") : qsTr("Pressure") } QGCButton { width: _buttonWidth text: qsTr("CompassMot") - visible: activeVehicle ? activeVehicle.supportsMotorInterference : false + visible: globals.activeVehicle ? globals.activeVehicle.supportsMotorInterference : false onClicked: mainWindow.showComponentDialog(compassMotDialogComponent, qsTr("CompassMot - Compass Motor Interference Calibration"), mainWindow.showDialogFullWidth, StandardButton.Cancel | StandardButton.Ok) } diff --git a/src/AutoPilotPlugins/APM/APMSubFrameComponent.qml b/src/AutoPilotPlugins/APM/APMSubFrameComponent.qml index 1e663ad057fdb61805a6bce978ab935f8f815835..2059a5e1fc295dfbe9b4d4a8084f1e3d9d5c0fca 100644 --- a/src/AutoPilotPlugins/APM/APMSubFrameComponent.qml +++ b/src/AutoPilotPlugins/APM/APMSubFrameComponent.qml @@ -24,7 +24,7 @@ SetupPage { id: subFramePage pageComponent: subFramePageComponent - property bool _oldFW: activeVehicle.versionCompare(3 ,5 ,2) < 0 + property bool _oldFW: globals.activeVehicle.versionCompare(3 ,5 ,2) < 0 APMAirframeComponentController { id: controller; } diff --git a/src/AutoPilotPlugins/APM/APMSubFrameComponentSummary.qml b/src/AutoPilotPlugins/APM/APMSubFrameComponentSummary.qml index b04f8903337a11db4068d143c22c0d1c07939bce..f62a3faf0c2f417d8aefac76945c3178100281d0 100644 --- a/src/AutoPilotPlugins/APM/APMSubFrameComponentSummary.qml +++ b/src/AutoPilotPlugins/APM/APMSubFrameComponentSummary.qml @@ -47,12 +47,12 @@ Item { VehicleSummaryRow { labelText: qsTr("Firmware Version") - valueText: activeVehicle.firmwareMajorVersion == -1 ? qsTr("Unknown") : activeVehicle.firmwareMajorVersion + "." + activeVehicle.firmwareMinorVersion + "." + activeVehicle.firmwarePatchVersion + " " + activeVehicle.firmwareVersionTypeString + valueText: globals.activeVehicle.firmwareMajorVersion == -1 ? qsTr("Unknown") : globals.activeVehicle.firmwareMajorVersion + "." + globals.activeVehicle.firmwareMinorVersion + "." + globals.activeVehicle.firmwarePatchVersion + " " + globals.activeVehicle.firmwareVersionTypeString } VehicleSummaryRow { labelText: qsTr("Git Revision") - valueText: activeVehicle.gitHash == -1 ? qsTr("Unknown") : activeVehicle.gitHash + valueText: globals.activeVehicle.gitHash == -1 ? qsTr("Unknown") : globals.activeVehicle.gitHash } } } diff --git a/src/AutoPilotPlugins/APM/APMTuningComponentSub.qml b/src/AutoPilotPlugins/APM/APMTuningComponentSub.qml index c238b97132c8f459f89964cdd3e3a3f86d888f29..8a93944244861b3a6165c59838449d2abbd594d8 100644 --- a/src/AutoPilotPlugins/APM/APMTuningComponentSub.qml +++ b/src/AutoPilotPlugins/APM/APMTuningComponentSub.qml @@ -157,7 +157,7 @@ SetupPage { anchors.right: parent.right anchors.top: parent.top - sourceComponent: activeVehicle.versionCompare(3, 6, 0) <= 0 ? velColumnUpTo36 :velColumn40 + sourceComponent: globals.activeVehicle.versionCompare(3, 6, 0) <= 0 ? velColumnUpTo36 :velColumn40 } } // Rectangle - VEL parameters @@ -224,7 +224,7 @@ SetupPage { anchors.right: parent.right anchors.top: parent.top - sourceComponent: activeVehicle.versionCompare(3, 6, 0) < 0 ? wpnavColumn35 : wpnavColumn36 + sourceComponent: globals.activeVehicle.versionCompare(3, 6, 0) < 0 ? wpnavColumn35 : wpnavColumn36 } } // Rectangle - WPNAV parameters } // Column diff --git a/src/AutoPilotPlugins/Common/RadioComponent.qml b/src/AutoPilotPlugins/Common/RadioComponent.qml index f49e46c92daa0ba513d8416467c5356a69f280f2..4f1f39d24f20fbaa01a68097db7daf808a924904 100644 --- a/src/AutoPilotPlugins/Common/RadioComponent.qml +++ b/src/AutoPilotPlugins/Common/RadioComponent.qml @@ -160,7 +160,7 @@ SetupPage { // Center point Rectangle { anchors.horizontalCenter: parent.horizontalCenter - width: defaultTextWidth / 2 + width: globals.defaultTextWidth / 2 height: parent.height color: qgcPal.window } @@ -210,10 +210,10 @@ SetupPage { Item { width: parent.width - height: defaultTextHeight * 2 + height: globals.defaultTextHeight * 2 QGCLabel { id: rollLabel - width: defaultTextWidth * 10 + width: globals.defaultTextWidth * 10 text: qsTr("Roll") } @@ -221,11 +221,10 @@ SetupPage { id: rollLoader anchors.left: rollLabel.right anchors.right: parent.right - height: defaultTextHeight + height: globals.defaultTextHeight width: 100 sourceComponent: channelMonitorDisplayComponent - property real defaultTextWidth: defaultTextWidth property bool mapped: controller.rollChannelMapped property bool reversed: controller.rollChannelReversed } @@ -239,11 +238,11 @@ SetupPage { Item { width: parent.width - height: defaultTextHeight * 2 + height: globals.defaultTextHeight * 2 QGCLabel { id: pitchLabel - width: defaultTextWidth * 10 + width: globals.defaultTextWidth * 10 text: qsTr("Pitch") } @@ -251,11 +250,10 @@ SetupPage { id: pitchLoader anchors.left: pitchLabel.right anchors.right: parent.right - height: defaultTextHeight + height: globals.defaultTextHeight width: 100 sourceComponent: channelMonitorDisplayComponent - property real defaultTextWidth: defaultTextWidth property bool mapped: controller.pitchChannelMapped property bool reversed: controller.pitchChannelReversed } @@ -269,11 +267,11 @@ SetupPage { Item { width: parent.width - height: defaultTextHeight * 2 + height: globals.defaultTextHeight * 2 QGCLabel { id: yawLabel - width: defaultTextWidth * 10 + width: globals.defaultTextWidth * 10 text: qsTr("Yaw") } @@ -281,11 +279,10 @@ SetupPage { id: yawLoader anchors.left: yawLabel.right anchors.right: parent.right - height: defaultTextHeight + height: globals.defaultTextHeight width: 100 sourceComponent: channelMonitorDisplayComponent - property real defaultTextWidth: defaultTextWidth property bool mapped: controller.yawChannelMapped property bool reversed: controller.yawChannelReversed } @@ -299,11 +296,11 @@ SetupPage { Item { width: parent.width - height: defaultTextHeight * 2 + height: globals.defaultTextHeight * 2 QGCLabel { id: throttleLabel - width: defaultTextWidth * 10 + width: globals.defaultTextWidth * 10 text: qsTr("Throttle") } @@ -311,11 +308,10 @@ SetupPage { id: throttleLoader anchors.left: throttleLabel.right anchors.right: parent.right - height: defaultTextHeight + height: globals.defaultTextHeight width: 100 sourceComponent: channelMonitorDisplayComponent - property real defaultTextWidth: defaultTextWidth property bool mapped: controller.throttleChannelMapped property bool reversed: controller.throttleChannelReversed } diff --git a/src/AutoPilotPlugins/Common/SetupPage.qml b/src/AutoPilotPlugins/Common/SetupPage.qml index 4a3b1a8c1522b8b1a5b0b25b7270c700681cd504..cf3a7209a829146644fc8276937fa2cc40254a51 100644 --- a/src/AutoPilotPlugins/Common/SetupPage.qml +++ b/src/AutoPilotPlugins/Common/SetupPage.qml @@ -33,9 +33,9 @@ Item { property bool showAdvanced: false property alias advanced: advancedCheckBox.checked - property bool _vehicleIsRover: activeVehicle ? activeVehicle.rover : false - property bool _vehicleArmed: activeVehicle ? activeVehicle.armed : false - property bool _vehicleFlying: activeVehicle ? activeVehicle.flying : false + property bool _vehicleIsRover: globals.activeVehicle ? globals.activeVehicle.rover : false + property bool _vehicleArmed: globals.activeVehicle ? globals.activeVehicle.armed : false + property bool _vehicleFlying: globals.activeVehicle ? globals.activeVehicle.flying : false property bool _disableDueToArmed: vehicleComponent ? (!vehicleComponent.allowSetupWhileArmed && _vehicleArmed) : false // FIXME: The _vehicleIsRover checkl is a hack to work around https://github.com/PX4/Firmware/issues/10969 property bool _disableDueToFlying: vehicleComponent ? (!_vehicleIsRover && !vehicleComponent.allowSetupWhileFlying && _vehicleFlying) : false diff --git a/src/AutoPilotPlugins/PX4/AirframeComponentSummary.qml b/src/AutoPilotPlugins/PX4/AirframeComponentSummary.qml index 79396bea6df79a51f85450fe84ee77a6106df134..195ca843a71d42bb75fe18d27708b57e7ca8255a 100644 --- a/src/AutoPilotPlugins/PX4/AirframeComponentSummary.qml +++ b/src/AutoPilotPlugins/PX4/AirframeComponentSummary.qml @@ -34,12 +34,12 @@ Item { VehicleSummaryRow { labelText: qsTr("Firmware Version") - valueText: activeVehicle.firmwareMajorVersion === -1 ? qsTr("Unknown") : activeVehicle.firmwareMajorVersion + "." + activeVehicle.firmwareMinorVersion + "." + activeVehicle.firmwarePatchVersion + activeVehicle.firmwareVersionTypeString + valueText: globals.activeVehicle.firmwareMajorVersion === -1 ? qsTr("Unknown") : globals.activeVehicle.firmwareMajorVersion + "." + globals.activeVehicle.firmwareMinorVersion + "." + globals.activeVehicle.firmwarePatchVersion + globals.activeVehicle.firmwareVersionTypeString } VehicleSummaryRow { - visible: activeVehicle.firmwareCustomMajorVersion !== -1 + visible: globals.activeVehicle.firmwareCustomMajorVersion !== -1 labelText: qsTr("Custom Fw. Ver.") - valueText: activeVehicle.firmwareCustomMajorVersion + "." + activeVehicle.firmwareCustomMinorVersion + "." + activeVehicle.firmwareCustomPatchVersion + valueText: globals.activeVehicle.firmwareCustomMajorVersion + "." + globals.activeVehicle.firmwareCustomMinorVersion + "." + globals.activeVehicle.firmwareCustomPatchVersion } } } diff --git a/src/FlightDisplay/FlightDisplayViewVideo.qml b/src/FlightDisplay/FlightDisplayViewVideo.qml index 037550e2da83c7f12cf54199b128f3885127037f..c2e6980e37c307df414e2eb4289b89a537604abc 100644 --- a/src/FlightDisplay/FlightDisplayViewVideo.qml +++ b/src/FlightDisplay/FlightDisplayViewVideo.qml @@ -28,8 +28,8 @@ Item { property double _ar: QGroundControl.videoManager.aspectRatio property bool _showGrid: QGroundControl.settingsManager.videoSettings.gridLines.rawValue > 0 - property var _dynamicCameras: activeVehicle ? activeVehicle.cameraManager : null - property bool _connected: activeVehicle ? !activeVehicle.connectionLost : false + property var _dynamicCameras: globals.activeVehicle ? globals.activeVehicle.cameraManager : null + property bool _connected: globals.activeVehicle ? !globals.activeVehicle.connectionLost : false property int _curCameraIndex: _dynamicCameras ? _dynamicCameras.currentCamera : 0 property bool _isCamera: _dynamicCameras ? _dynamicCameras.cameras.count > 0 : false property var _camera: _isCamera ? _dynamicCameras.cameras.get(_curCameraIndex) : null diff --git a/src/FlightDisplay/FlyViewMap.qml b/src/FlightDisplay/FlyViewMap.qml index f3e79932cac3d214957d25a906376b71f4d032e8..ac662452993592a213f25e5bbb33abd7acc6905a 100644 --- a/src/FlightDisplay/FlyViewMap.qml +++ b/src/FlightDisplay/FlyViewMap.qml @@ -43,10 +43,11 @@ FlightMap { property bool pipMode: false // true: map is shown in a small pip mode property var toolInsets // Insets for the center viewport area + property var _activeVehicle: QGroundControl.multiVehicleManager.activeVehicle property var _planMasterController: planMasterController property var _geoFenceController: planMasterController.geoFenceController property var _rallyPointController: planMasterController.rallyPointController - property var _activeVehicleCoordinate: activeVehicle ? activeVehicle.coordinate : QtPositioning.coordinate() + property var _activeVehicleCoordinate: _activeVehicle ? _activeVehicle.coordinate : QtPositioning.coordinate() property real _toolButtonTopMargin: parent.height - mainWindow.height + (ScreenTools.defaultFontPixelHeight / 2) property bool _airspaceEnabled: QGroundControl.airmapSupported ? (QGroundControl.settingsManager.airMapSettings.enableAirMap.rawValue && QGroundControl.airspaceManager.connected): false property var _flyViewSettings: QGroundControl.settingsManager.flyViewSettings @@ -231,11 +232,11 @@ FlightMap { Connections { target: QGroundControl.multiVehicleManager - onActiveVehicleChanged: trajectoryPolyline.path = activeVehicle ? activeVehicle.trajectoryPoints.list() : [] + onActiveVehicleChanged: trajectoryPolyline.path = _activeVehicle ? _activeVehicle.trajectoryPoints.list() : [] } Connections { - target: activeVehicle ? activeVehicle.trajectoryPoints : null + target: _activeVehicle ? _activeVehicle.trajectoryPoints : null onPointAdded: trajectoryPolyline.addCoordinate(coordinate) onUpdateLastPoint: trajectoryPolyline.replaceCoordinate(trajectoryPolyline.pathLength() - 1, coordinate) onPointsCleared: trajectoryPolyline.path = [] @@ -318,7 +319,7 @@ FlightMap { myGeoFenceController: _geoFenceController interactive: false planView: false - homePosition: activeVehicle && activeVehicle.homePosition.isValid ? activeVehicle.homePosition : QtPositioning.coordinate() + homePosition: _activeVehicle && _activeVehicle.homePosition.isValid ? _activeVehicle.homePosition : QtPositioning.coordinate() } // Rally points on map @@ -341,7 +342,7 @@ FlightMap { // Camera trigger points MapItemView { - model: activeVehicle ? activeVehicle.cameraTriggerPoints : 0 + model: _activeVehicle ? _activeVehicle.cameraTriggerPoints : 0 delegate: CameraTriggerIndicator { coordinate: object.coordinate @@ -362,7 +363,7 @@ FlightMap { label: qsTr("Go here", "Go to location waypoint") } - property bool inGotoFlightMode: activeVehicle ? activeVehicle.flightMode === activeVehicle.gotoFlightMode : false + property bool inGotoFlightMode: _activeVehicle ? _activeVehicle.flightMode === _activeVehicle.gotoFlightMode : false onInGotoFlightModeChanged: { if (!inGotoFlightMode && gotoLocationItem.visible) { @@ -372,7 +373,7 @@ FlightMap { } Connections { - target: mainWindow + target: QGroundControl.multiVehicleManager onActiveVehicleChanged: { if (!activeVehicle) { gotoLocationItem.visible = false @@ -410,7 +411,7 @@ FlightMap { readonly property real defaultRadius: 30 Connections { - target: mainWindow + target: QGroundControl.multiVehicleManager onActiveVehicleChanged: { if (!activeVehicle) { orbitMapCircle.visible = false @@ -441,7 +442,7 @@ FlightMap { return _mapCircle.radius.rawValue } - Component.onCompleted: mainWindow.guidedControllerFlyView.orbitMapCircle = orbitMapCircle + Component.onCompleted: globals.guidedControllerFlyView.orbitMapCircle = orbitMapCircle QGCMapCircle { id: _mapCircle @@ -455,7 +456,7 @@ FlightMap { // ROI Location visuals MapQuickItem { id: roiLocationItem - visible: activeVehicle && activeVehicle.isROIEnabled + visible: _activeVehicle && _activeVehicle.isROIEnabled z: QGroundControl.zOrderMapItems anchorPoint.x: sourceItem.anchorPointX anchorPoint.y: sourceItem.anchorPointY @@ -484,15 +485,15 @@ FlightMap { QGCMapCircleVisuals { id: orbitTelemetryCircle mapControl: parent - mapCircle: activeVehicle ? activeVehicle.orbitMapCircle : null - visible: activeVehicle ? activeVehicle.orbitActive : false + mapCircle: _activeVehicle ? _activeVehicle.orbitMapCircle : null + visible: _activeVehicle ? _activeVehicle.orbitActive : false } MapQuickItem { id: orbitCenterIndicator anchorPoint.x: sourceItem.anchorPointX anchorPoint.y: sourceItem.anchorPointY - coordinate: activeVehicle ? activeVehicle.orbitMapCircle.center : QtPositioning.coordinate() + coordinate: _activeVehicle ? _activeVehicle.orbitMapCircle.center : QtPositioning.coordinate() visible: orbitTelemetryCircle.visible sourceItem: MissionItemIndexLabel { @@ -511,35 +512,35 @@ FlightMap { property var coord QGCMenuItem { text: qsTr("Go to location") - visible: mainWindow.guidedControllerFlyView.showGotoLocation + visible: globals.guidedControllerFlyView.showGotoLocation onTriggered: { gotoLocationItem.show(clickMenu.coord) - mainWindow.guidedControllerFlyView.confirmAction(mainWindow.guidedControllerFlyView.actionGoto, clickMenu.coord, gotoLocationItem) + globals.guidedControllerFlyView.confirmAction(globals.guidedControllerFlyView.actionGoto, clickMenu.coord, gotoLocationItem) } } QGCMenuItem { text: qsTr("Orbit at location") - visible: mainWindow.guidedControllerFlyView.showOrbit + visible: globals.guidedControllerFlyView.showOrbit onTriggered: { orbitMapCircle.show(clickMenu.coord) - mainWindow.guidedControllerFlyView.confirmAction(mainWindow.guidedControllerFlyView.actionOrbit, clickMenu.coord, orbitMapCircle) + globals.guidedControllerFlyView.confirmAction(globals.guidedControllerFlyView.actionOrbit, clickMenu.coord, orbitMapCircle) } } QGCMenuItem { text: qsTr("ROI at location") - visible: mainWindow.guidedControllerFlyView.showROI + visible: globals.guidedControllerFlyView.showROI onTriggered: { roiLocationItem.show(clickMenu.coord) - mainWindow.guidedControllerFlyView.confirmAction(mainWindow.guidedControllerFlyView.actionROI, clickMenu.coord, roiLocationItem) + globals.guidedControllerFlyView.confirmAction(globals.guidedControllerFlyView.actionROI, clickMenu.coord, roiLocationItem) } } } onClicked: { - if (!mainWindow.guidedControllerFlyView.guidedUIVisible && (mainWindow.guidedControllerFlyView.showGotoLocation || mainWindow.guidedControllerFlyView.showOrbit || mainWindow.guidedControllerFlyView.showROI)) { + if (!globals.guidedControllerFlyView.guidedUIVisible && (globals.guidedControllerFlyView.showGotoLocation || globals.guidedControllerFlyView.showOrbit || globals.guidedControllerFlyView.showROI)) { orbitMapCircle.hide() gotoLocationItem.hide() var clickCoord = _root.toCoordinate(Qt.point(mouse.x, mouse.y), false /* clipToViewPort */) diff --git a/src/FlightDisplay/FlyViewMissionCompleteDialog.qml b/src/FlightDisplay/FlyViewMissionCompleteDialog.qml index 1fad8755d716a55f1be285969f395b3e358626d0..5f4dca817892b5111c91be0daa41fa0ac86fc42c 100644 --- a/src/FlightDisplay/FlyViewMissionCompleteDialog.qml +++ b/src/FlightDisplay/FlyViewMissionCompleteDialog.qml @@ -108,15 +108,15 @@ Item { ColumnLayout { Layout.fillWidth: true spacing: ScreenTools.defaultFontPixelHeight - visible: !_activeVehicle.connectionLost && mainWindow.guidedControllerFlyView.showResumeMission + visible: !_activeVehicle.connectionLost && globals.guidedControllerFlyView.showResumeMission QGCButton { Layout.fillWidth: true Layout.alignment: Qt.AlignHCenter - text: qsTr("Resume Mission From Waypoint %1").arg(mainWindow.guidedControllerFlyView._resumeMissionIndex) + text: qsTr("Resume Mission From Waypoint %1").arg(globals.guidedControllerFlyView._resumeMissionIndex) onClicked: { - mainWindow.guidedControllerFlyView.executeAction(mainWindow.guidedControllerFlyView.actionResumeMission, null, null) + globals.guidedControllerFlyView.executeAction(globals.guidedControllerFlyView.actionResumeMission, null, null) hideDialog() } } @@ -133,7 +133,7 @@ Item { wrapMode: Text.WordWrap color: qgcPal.warningText text: qsTr("If you are changing batteries for Resume Mission do not disconnect from the vehicle.") - visible: mainWindow.guidedControllerFlyView.showResumeMission + visible: globals.guidedControllerFlyView.showResumeMission } } } diff --git a/src/FlightDisplay/FlyViewWidgetLayer.qml b/src/FlightDisplay/FlyViewWidgetLayer.qml index 8541583b9af4130d248900dfd0826db0340bc358..811578a1917d25bd3b084d4eab77861332b9bb44 100644 --- a/src/FlightDisplay/FlyViewWidgetLayer.qml +++ b/src/FlightDisplay/FlyViewWidgetLayer.qml @@ -39,11 +39,11 @@ Item { property var mapControl property var _activeVehicle: QGroundControl.multiVehicleManager.activeVehicle - property var _planMasterController: mainWindow.planMasterControllerFlyView + property var _planMasterController: globals.planMasterControllerFlyView property var _missionController: _planMasterController.missionController property var _geoFenceController: _planMasterController.geoFenceController property var _rallyPointController: _planMasterController.rallyPointController - property var _guidedController: mainWindow.guidedControllerFlyView + property var _guidedController: globals.guidedControllerFlyView property real _margins: ScreenTools.defaultFontPixelWidth / 2 property real _toolsMargin: ScreenTools.defaultFontPixelWidth * 0.75 property rect _centerViewport: Qt.rect(0, 0, width, height) @@ -156,12 +156,12 @@ Item { z: QGroundControl.zOrderTopMost + 1 width: parent.width - (_pipOverlay.width / 2) height: Math.min(parent.height * 0.25, ScreenTools.defaultFontPixelWidth * 16) - visible: _virtualJoystickEnabled && !QGroundControl.videoManager.fullScreen && !(activeVehicle ? activeVehicle.highLatencyLink : false) + visible: _virtualJoystickEnabled && !QGroundControl.videoManager.fullScreen && !(_activeVehicle ? _activeVehicle.highLatencyLink : false) anchors.bottom: parent.bottom anchors.bottomMargin: parentToolInsets.leftEdgeBottomInset + ScreenTools.defaultFontPixelHeight * 2 anchors.horizontalCenter: parent.horizontalCenter source: "qrc:/qml/VirtualJoystick.qml" - active: _virtualJoystickEnabled && !(activeVehicle ? activeVehicle.highLatencyLink : false) + active: _virtualJoystickEnabled && !(_activeVehicle ? _activeVehicle.highLatencyLink : false) property bool autoCenterThrottle: QGroundControl.settingsManager.appSettings.virtualJoystickAutoCenterThrottle.rawValue diff --git a/src/FlightDisplay/GuidedActionsController.qml b/src/FlightDisplay/GuidedActionsController.qml index 0efe31631c9e64f1622e793b8d5ca1c8751bc6a1..41252a37015adeab1627250891f97666435b5b10 100644 --- a/src/FlightDisplay/GuidedActionsController.qml +++ b/src/FlightDisplay/GuidedActionsController.qml @@ -101,21 +101,22 @@ Item { readonly property int actionActionList: 23 readonly property int actionForceArm: 24 + property var _activeVehicle: QGroundControl.multiVehicleManager.activeVehicle property bool _useChecklist: QGroundControl.settingsManager.appSettings.useChecklist.rawValue && QGroundControl.corePlugin.options.preFlightChecklistUrl.toString().length property bool _enforceChecklist: _useChecklist && QGroundControl.settingsManager.appSettings.enforceChecklist.rawValue - property bool _canArm: activeVehicle ? (_useChecklist ? (_enforceChecklist ? activeVehicle.checkListState === Vehicle.CheckListPassed : true) : true) : false + property bool _canArm: _activeVehicle ? (_useChecklist ? (_enforceChecklist ? _activeVehicle.checkListState === Vehicle.CheckListPassed : true) : true) : false property bool showEmergenyStop: _guidedActionsEnabled && !_hideEmergenyStop && _vehicleArmed && _vehicleFlying property bool showArm: _guidedActionsEnabled && !_vehicleArmed && _canArm property bool showForceArm: _guidedActionsEnabled && !_vehicleArmed property bool showDisarm: _guidedActionsEnabled && _vehicleArmed && !_vehicleFlying - property bool showRTL: _guidedActionsEnabled && _vehicleArmed && activeVehicle.guidedModeSupported && _vehicleFlying && !_vehicleInRTLMode - property bool showTakeoff: _guidedActionsEnabled && activeVehicle.takeoffVehicleSupported && !_vehicleFlying && _canArm - property bool showLand: _guidedActionsEnabled && activeVehicle.guidedModeSupported && _vehicleArmed && !activeVehicle.fixedWing && !_vehicleInLandMode + property bool showRTL: _guidedActionsEnabled && _vehicleArmed && _activeVehicle.guidedModeSupported && _vehicleFlying && !_vehicleInRTLMode + property bool showTakeoff: _guidedActionsEnabled && _activeVehicle.takeoffVehicleSupported && !_vehicleFlying && _canArm + property bool showLand: _guidedActionsEnabled && _activeVehicle.guidedModeSupported && _vehicleArmed && !_activeVehicle.fixedWing && !_vehicleInLandMode property bool showStartMission: _guidedActionsEnabled && _missionAvailable && !_missionActive && !_vehicleFlying && _canArm property bool showContinueMission: _guidedActionsEnabled && _missionAvailable && !_missionActive && _vehicleArmed && _vehicleFlying && (_currentMissionIndex < _missionItemCount - 1) - property bool showPause: _guidedActionsEnabled && _vehicleArmed && activeVehicle.pauseVehicleSupported && _vehicleFlying && !_vehiclePaused && !_fixedWingOnApproach - property bool showChangeAlt: _guidedActionsEnabled && _vehicleFlying && activeVehicle.guidedModeSupported && _vehicleArmed && !_missionActive + property bool showPause: _guidedActionsEnabled && _vehicleArmed && _activeVehicle.pauseVehicleSupported && _vehicleFlying && !_vehiclePaused && !_fixedWingOnApproach + property bool showChangeAlt: _guidedActionsEnabled && _vehicleFlying && _activeVehicle.guidedModeSupported && _vehicleArmed && !_missionActive property bool showOrbit: _guidedActionsEnabled && _vehicleFlying && __orbitSupported && !_missionActive property bool showROI: _guidedActionsEnabled && _vehicleFlying && __roiSupported && !_missionActive property bool showLandAbort: _guidedActionsEnabled && _vehicleFlying && _fixedWingOnApproach @@ -123,19 +124,19 @@ Item { property bool showActionList: _guidedActionsEnabled && (showStartMission || showResumeMission || showChangeAlt || showLandAbort) // Note: The '_missionItemCount - 2' is a hack to not trigger resume mission when a mission ends with an RTL item - property bool showResumeMission: activeVehicle && !_vehicleArmed && _vehicleWasFlying && _missionAvailable && _resumeMissionIndex > 0 && (_resumeMissionIndex < _missionItemCount - 2) + property bool showResumeMission: _activeVehicle && !_vehicleArmed && _vehicleWasFlying && _missionAvailable && _resumeMissionIndex > 0 && (_resumeMissionIndex < _missionItemCount - 2) property bool guidedUIVisible: confirmDialog.visible || actionList.visible property var _corePlugin: QGroundControl.corePlugin property var _corePluginOptions: QGroundControl.corePlugin.options - property bool _guidedActionsEnabled: (!ScreenTools.isDebug && _corePluginOptions.guidedActionsRequireRCRSSI && activeVehicle) ? _rcRSSIAvailable : activeVehicle - property string _flightMode: activeVehicle ? activeVehicle.flightMode : "" + property bool _guidedActionsEnabled: (!ScreenTools.isDebug && _corePluginOptions.guidedActionsRequireRCRSSI && _activeVehicle) ? _rcRSSIAvailable : _activeVehicle + property string _flightMode: _activeVehicle ? _activeVehicle.flightMode : "" property bool _missionAvailable: missionController.containsItems - property bool _missionActive: activeVehicle ? _vehicleArmed && (_vehicleInLandMode || _vehicleInRTLMode || _vehicleInMissionMode) : false - property bool _vehicleArmed: activeVehicle ? activeVehicle.armed : false - property bool _vehicleFlying: activeVehicle ? activeVehicle.flying : false - property bool _vehicleLanding: activeVehicle ? activeVehicle.landing : false + property bool _missionActive: _activeVehicle ? _vehicleArmed && (_vehicleInLandMode || _vehicleInRTLMode || _vehicleInMissionMode) : false + property bool _vehicleArmed: _activeVehicle ? _activeVehicle.armed : false + property bool _vehicleFlying: _activeVehicle ? _activeVehicle.flying : false + property bool _vehicleLanding: _activeVehicle ? _activeVehicle.landing : false property bool _vehiclePaused: false property bool _vehicleInMissionMode: false property bool _vehicleInRTLMode: false @@ -147,28 +148,23 @@ Item { property bool _hideOrbit: !_corePluginOptions.flyView.guidedBarShowOrbit property bool _hideROI: !_corePluginOptions.flyView.guidedBarShowROI property bool _vehicleWasFlying: false - property bool _rcRSSIAvailable: activeVehicle ? activeVehicle.rcRSSI > 0 && activeVehicle.rcRSSI <= 100 : false - property bool _fixedWingOnApproach: activeVehicle ? activeVehicle.fixedWing && _vehicleLanding : false + property bool _rcRSSIAvailable: _activeVehicle ? _activeVehicle.rcRSSI > 0 && _activeVehicle.rcRSSI <= 100 : false + property bool _fixedWingOnApproach: _activeVehicle ? _activeVehicle.fixedWing && _vehicleLanding : false // You can turn on log output for GuidedActionsController by turning on GuidedActionsControllerLog category - property bool __guidedModeSupported: activeVehicle ? activeVehicle.guidedModeSupported : false - property bool __pauseVehicleSupported: activeVehicle ? activeVehicle.pauseVehicleSupported : false - property bool __roiSupported: activeVehicle ? !_hideROI && activeVehicle.roiModeSupported : false - property bool __orbitSupported: activeVehicle ? !_hideOrbit && activeVehicle.orbitModeSupported : false + property bool __guidedModeSupported: _activeVehicle ? _activeVehicle.guidedModeSupported : false + property bool __pauseVehicleSupported: _activeVehicle ? _activeVehicle.pauseVehicleSupported : false + property bool __roiSupported: _activeVehicle ? !_hideROI && _activeVehicle.roiModeSupported : false + property bool __orbitSupported: _activeVehicle ? !_hideOrbit && _activeVehicle.orbitModeSupported : false property bool __flightMode: _flightMode function _outputState() { if (_corePlugin.guidedActionsControllerLogging()) { - console.log(qsTr("activeVehicle(%1) _vehicleArmed(%2) guidedModeSupported(%3) _vehicleFlying(%4) _vehicleWasFlying(%5) _vehicleInRTLMode(%6) pauseVehicleSupported(%7) _vehiclePaused(%8) _flightMode(%9) _missionItemCount(%10) roiSupported(%11) orbitSupported(%12) _missionActive(%13) _hideROI(%14) _hideOrbit(%15)").arg(activeVehicle ? 1 : 0).arg(_vehicleArmed ? 1 : 0).arg(__guidedModeSupported ? 1 : 0).arg(_vehicleFlying ? 1 : 0).arg(_vehicleWasFlying ? 1 : 0).arg(_vehicleInRTLMode ? 1 : 0).arg(__pauseVehicleSupported ? 1 : 0).arg(_vehiclePaused ? 1 : 0).arg(_flightMode).arg(_missionItemCount).arg(__roiSupported).arg(__orbitSupported).arg(_missionActive).arg(_hideROI).arg(_hideOrbit)) + console.log(qsTr("_activeVehicle(%1) _vehicleArmed(%2) guidedModeSupported(%3) _vehicleFlying(%4) _vehicleWasFlying(%5) _vehicleInRTLMode(%6) pauseVehicleSupported(%7) _vehiclePaused(%8) _flightMode(%9) _missionItemCount(%10) roiSupported(%11) orbitSupported(%12) _missionActive(%13) _hideROI(%14) _hideOrbit(%15)").arg(_activeVehicle ? 1 : 0).arg(_vehicleArmed ? 1 : 0).arg(__guidedModeSupported ? 1 : 0).arg(_vehicleFlying ? 1 : 0).arg(_vehicleWasFlying ? 1 : 0).arg(_vehicleInRTLMode ? 1 : 0).arg(__pauseVehicleSupported ? 1 : 0).arg(_vehiclePaused ? 1 : 0).arg(_flightMode).arg(_missionItemCount).arg(__roiSupported).arg(__orbitSupported).arg(_missionActive).arg(_hideROI).arg(_hideOrbit)) } } - Connections { - target: mainWindow - onActiveVehicleChanged: { - _outputState() - } - } + on_ActiveVehicleChanged: _outputState() Component.onCompleted: _outputState() on_VehicleArmedChanged: _outputState() @@ -264,10 +260,10 @@ Item { property var _actionData on_FlightModeChanged: { - _vehiclePaused = activeVehicle ? _flightMode === activeVehicle.pauseFlightMode : false - _vehicleInRTLMode = activeVehicle ? _flightMode === activeVehicle.rtlFlightMode || _flightMode === activeVehicle.smartRTLFlightMode : false - _vehicleInLandMode = activeVehicle ? _flightMode === activeVehicle.landFlightMode : false - _vehicleInMissionMode = activeVehicle ? _flightMode === activeVehicle.missionFlightMode : false // Must be last to get correct signalling for showStartMission popups + _vehiclePaused = _activeVehicle ? _flightMode === _activeVehicle.pauseFlightMode : false + _vehicleInRTLMode = _activeVehicle ? _flightMode === _activeVehicle.rtlFlightMode || _flightMode === _activeVehicle.smartRTLFlightMode : false + _vehicleInLandMode = _activeVehicle ? _flightMode === _activeVehicle.landFlightMode : false + _vehicleInMissionMode = _activeVehicle ? _flightMode === _activeVehicle.missionFlightMode : false // Must be last to get correct signalling for showStartMission popups } Connections { @@ -392,7 +388,7 @@ Item { case actionRTL: confirmDialog.title = rtlTitle confirmDialog.message = rtlMessage - if (activeVehicle.supportsSmartRTL) { + if (_activeVehicle.supportsSmartRTL) { confirmDialog.optionText = qsTr("Smart RTL") confirmDialog.optionChecked = false } @@ -469,13 +465,13 @@ Item { var rgVehicle; switch (actionCode) { case actionRTL: - activeVehicle.guidedModeRTL(optionChecked) + _activeVehicle.guidedModeRTL(optionChecked) break case actionLand: - activeVehicle.guidedModeLand() + _activeVehicle.guidedModeLand() break case actionTakeoff: - activeVehicle.guidedModeTakeoff(actionAltitudeChange) + _activeVehicle.guidedModeTakeoff(actionAltitudeChange) break case actionResumeMission: case actionResumeMissionUploadFail: @@ -483,7 +479,7 @@ Item { break case actionStartMission: case actionContinueMission: - activeVehicle.startMission() + _activeVehicle.startMission() break case actionMVStartMission: rgVehicle = QGroundControl.multiVehicleManager.vehicles @@ -492,35 +488,35 @@ Item { } break case actionArm: - activeVehicle.armed = true + _activeVehicle.armed = true break case actionForceArm: - activeVehicle.forceArm() + _activeVehicle.forceArm() break case actionDisarm: - activeVehicle.armed = false + _activeVehicle.armed = false break case actionEmergencyStop: - activeVehicle.emergencyStop() + _activeVehicle.emergencyStop() break case actionChangeAlt: - activeVehicle.guidedModeChangeAltitude(actionAltitudeChange) + _activeVehicle.guidedModeChangeAltitude(actionAltitudeChange) break case actionGoto: - activeVehicle.guidedModeGotoLocation(actionData) + _activeVehicle.guidedModeGotoLocation(actionData) break case actionSetWaypoint: - activeVehicle.setCurrentMissionSequence(actionData) + _activeVehicle.setCurrentMissionSequence(actionData) break case actionOrbit: - activeVehicle.guidedModeOrbit(orbitMapCircle.center, orbitMapCircle.radius() * (orbitMapCircle.clockwiseRotation ? 1 : -1), activeVehicle.altitudeAMSL.rawValue + actionAltitudeChange) + _activeVehicle.guidedModeOrbit(orbitMapCircle.center, orbitMapCircle.radius() * (orbitMapCircle.clockwiseRotation ? 1 : -1), _activeVehicle.altitudeAMSL.rawValue + actionAltitudeChange) break case actionLandAbort: - activeVehicle.abortLanding(50) // hardcoded value for climbOutAltitude that is currently ignored + _activeVehicle.abortLanding(50) // hardcoded value for climbOutAltitude that is currently ignored break case actionPause: - activeVehicle.pauseVehicle() - activeVehicle.guidedModeChangeAltitude(actionAltitudeChange) + _activeVehicle.pauseVehicle() + _activeVehicle.guidedModeChangeAltitude(actionAltitudeChange) break case actionMVPause: rgVehicle = QGroundControl.multiVehicleManager.vehicles @@ -529,13 +525,13 @@ Item { } break case actionVtolTransitionToFwdFlight: - activeVehicle.vtolInFwdFlight = true + _activeVehicle.vtolInFwdFlight = true break case actionVtolTransitionToMRFlight: - activeVehicle.vtolInFwdFlight = false + _activeVehicle.vtolInFwdFlight = false break case actionROI: - activeVehicle.guidedModeROI(actionData) + _activeVehicle.guidedModeROI(actionData) break default: console.warn(qsTr("Internal error: unknown actionCode"), actionCode) diff --git a/src/FlightDisplay/GuidedAltitudeSlider.qml b/src/FlightDisplay/GuidedAltitudeSlider.qml index 8444e4f07fcb205783476023fb82f61eada9eb36..39e4bd8794375ec67f84d7e13f84fc8bba5a2b94 100644 --- a/src/FlightDisplay/GuidedAltitudeSlider.qml +++ b/src/FlightDisplay/GuidedAltitudeSlider.qml @@ -21,12 +21,13 @@ Rectangle { readonly property real _maxAlt: 121.92 // 400 feet readonly property real _minAlt: 3 + property var _activeVehicle: QGroundControl.multiVehicleManager.activeVehicle property var _flyViewSettings: QGroundControl.settingsManager.flyViewSettings - property real _vehicleAltitude: activeVehicle ? activeVehicle.altitudeRelative.rawValue : 0 - property bool _fixedWing: activeVehicle ? activeVehicle.fixedWing : false + property real _vehicleAltitude: _activeVehicle ? _activeVehicle.altitudeRelative.rawValue : 0 + property bool _fixedWing: _activeVehicle ? _activeVehicle.fixedWing : false property real _sliderMaxAlt: _flyViewSettings ? _flyViewSettings.guidedMaximumAltitude.rawValue : 0 property real _sliderMinAlt: _flyViewSettings ? _flyViewSettings.guidedMinimumAltitude.rawValue : 0 - property bool _flying: activeVehicle ? activeVehicle.flying : false + property bool _flying: _activeVehicle ? _activeVehicle.flying : false function reset() { altSlider.value = 0 @@ -77,7 +78,7 @@ Rectangle { property string newAltitudeAppUnits: QGroundControl.unitsConversion.metersToAppSettingsHorizontalDistanceUnits(newAltitudeMeters).toFixed(1) function setToMinimumTakeoff() { - altSlider.value = Math.pow(activeVehicle.minimumTakeoffAltitude() / altGainRange, 1.0/3.0) + altSlider.value = Math.pow(_activeVehicle.minimumTakeoffAltitude() / altGainRange, 1.0/3.0) } } } diff --git a/src/FlightDisplay/GuidedToolStripAction.qml b/src/FlightDisplay/GuidedToolStripAction.qml index 2de4b300d0733feede23556a7e324fa89065d39c..9cf2a28b7cd826190a783a49ff4fd6afc4e99814 100644 --- a/src/FlightDisplay/GuidedToolStripAction.qml +++ b/src/FlightDisplay/GuidedToolStripAction.qml @@ -13,7 +13,7 @@ ToolStripAction { property int actionID property string message - property var _guidedController: mainWindow.guidedControllerFlyView + property var _guidedController: globals.guidedControllerFlyView onTriggered: { _guidedController.closeAll() diff --git a/src/FlightDisplay/MultiVehicleList.qml b/src/FlightDisplay/MultiVehicleList.qml index e1fa05fbafb91379416d3e819dd3b10cfda947d7..a1f78de3b819c40ee68e1e0bbe6cc8bb05a82f62 100644 --- a/src/FlightDisplay/MultiVehicleList.qml +++ b/src/FlightDisplay/MultiVehicleList.qml @@ -23,7 +23,7 @@ Item { property real _widgetHeight: ScreenTools.defaultFontPixelHeight * 3 property color _textColor: "black" property real _rectOpacity: 0.8 - property var _guidedController: mainWindow.guidedControllerFlyView + property var _guidedController: globals.guidedControllerFlyView QGCPalette { id: qgcPal } diff --git a/src/FlightDisplay/PreFlightBatteryCheck.qml b/src/FlightDisplay/PreFlightBatteryCheck.qml index 30736be6632d929187cbdc259c83fb21601585fc..48ce81222ebd2fbfe5d4480e7ccbc869a59a6e22 100644 --- a/src/FlightDisplay/PreFlightBatteryCheck.qml +++ b/src/FlightDisplay/PreFlightBatteryCheck.qml @@ -25,7 +25,7 @@ PreFlightCheckButton { property int failurePercent: 40 property bool allowFailurePercentOverride: false - property var _batteryValue: activeVehicle ? activeVehicle.battery.percentRemaining.value : 0 + property var _batteryValue: globals.activeVehicle ? globals.activeVehicle.battery.percentRemaining.value : 0 property var _batPercentRemaining: isNaN(_batteryValue) ? 0 : _batteryValue property bool _batLow: _batPercentRemaining < failurePercent } diff --git a/src/FlightDisplay/PreFlightCheckList.qml b/src/FlightDisplay/PreFlightCheckList.qml index 98121447ee315d9b1784bb648f0dcdc765a363ec..96bd38385bfe2794052c89a5d5a3fed9ff9cf476 100644 --- a/src/FlightDisplay/PreFlightCheckList.qml +++ b/src/FlightDisplay/PreFlightCheckList.qml @@ -19,7 +19,7 @@ import QGroundControl.Vehicle 1.0 Rectangle { width: mainColumn.width + ScreenTools.defaultFontPixelWidth * 3 - height: Math.min(mainWindow.availableHeight - (_verticalMargin * 2), mainColumn.height + ScreenTools.defaultFontPixelHeight) + height: Math.min(mainWindow.height - (_verticalMargin * 2), mainColumn.height + ScreenTools.defaultFontPixelHeight) color: qgcPal.windowShade radius: 3 @@ -31,7 +31,7 @@ Rectangle { } property bool allChecksPassed: false - property var vehicleCopy: activeVehicle + property var vehicleCopy: globals.activeVehicle onVehicleCopyChanged: { checkListRepeater.model.reset() @@ -39,9 +39,9 @@ Rectangle { onAllChecksPassedChanged: { if (allChecksPassed) { - activeVehicle.checkListState = Vehicle.CheckListPassed + globals.activeVehicle.checkListState = Vehicle.CheckListPassed } else { - activeVehicle.checkListState = Vehicle.CheckListFailed + globals.activeVehicle.checkListState = Vehicle.CheckListFailed } } @@ -71,7 +71,7 @@ Rectangle { //-- Pick a checklist model that matches the current airframe type (if any) function _updateModel() { - var vehicle = activeVehicle + var vehicle = globals.activeVehicle if (!vehicle) { vehicle = QGroundControl.multiVehicleManager.offlineEditingVehicle } @@ -97,7 +97,7 @@ Rectangle { } onVisibleChanged: { - if(activeVehicle) { + if(globals.activeVehicle) { if(visible) { _updateModel() } diff --git a/src/FlightDisplay/PreFlightGPSCheck.qml b/src/FlightDisplay/PreFlightGPSCheck.qml index 4b7a8f5ca113d6e2d5b2ed19de63d6379a4acd9f..b1499a64cd6ad2ba426a9b018676d78d3baf29de 100644 --- a/src/FlightDisplay/PreFlightGPSCheck.qml +++ b/src/FlightDisplay/PreFlightGPSCheck.qml @@ -24,8 +24,8 @@ PreFlightCheckButton { property bool allowOverrideSatCount: false ///< true: sat count above failureSatCount reguired to pass, false: user can click past satCount <= failureSetCount property int failureSatCount: -1 ///< -1 indicates no sat count check - property bool _3dLock: activeVehicle ? activeVehicle.gps.lock.rawValue >= 3 : false - property int _satCount: activeVehicle ? activeVehicle.gps.count.rawValue : 0 + property bool _3dLock: globals.activeVehicle ? globals.activeVehicle.gps.lock.rawValue >= 3 : false + property int _satCount: globals.activeVehicle ? globals.activeVehicle.gps.count.rawValue : 0 property bool _3dLockFailure: !_3dLock property bool _satCountFailure: failureSatCount !== -1 && _satCount <= failureSatCount property string _satCountFailureText: allowOverrideSatCount ? qsTr("Warning - Sat count below %1.").arg(failureSatCount + 1) : qsTr("Waiting for sat count above %1.").arg(failureSatCount) diff --git a/src/FlightDisplay/PreFlightRCCheck.qml b/src/FlightDisplay/PreFlightRCCheck.qml index acac3a74dbbf9392e6667816d6feb2d28f6b9191..b9c1b338be2be4a5d4f86883f744f5851d65187d 100644 --- a/src/FlightDisplay/PreFlightRCCheck.qml +++ b/src/FlightDisplay/PreFlightRCCheck.qml @@ -19,5 +19,5 @@ PreFlightCheckButton { telemetryTextFailure: qsTr("No signal or invalid autopilot-RC config. Check RC and console.") telemetryFailure: _unhealthySensors & Vehicle.SysStatusSensorRCReceiver - property int _unhealthySensors: activeVehicle ? activeVehicle.sensorsUnhealthyBits : 0 + property int _unhealthySensors: globals.activeVehicle ? globals.activeVehicle.sensorsUnhealthyBits : 0 } diff --git a/src/FlightDisplay/PreFlightSensorsHealthCheck.qml b/src/FlightDisplay/PreFlightSensorsHealthCheck.qml index e5e4a2a37886890c4ed13b8b0cd9b32226b88533..ba50b88529e1ca774be11befdb5303ab28d9daf2 100644 --- a/src/FlightDisplay/PreFlightSensorsHealthCheck.qml +++ b/src/FlightDisplay/PreFlightSensorsHealthCheck.qml @@ -17,7 +17,7 @@ PreFlightCheckButton { name: qsTr("Sensors") telemetryFailure: _unhealthySensors & _allCheckedSensors - property int _unhealthySensors: activeVehicle ? activeVehicle.sensorsUnhealthyBits : 1 + property int _unhealthySensors: globals.activeVehicle ? globals.activeVehicle.sensorsUnhealthyBits : 1 property int _allCheckedSensors: Vehicle.SysStatusSensor3dMag | Vehicle.SysStatusSensor3dAccel | Vehicle.SysStatusSensor3dGyro | diff --git a/src/FlightDisplay/VirtualJoystick.qml b/src/FlightDisplay/VirtualJoystick.qml index 8ae010b41d3ed36fc5530cd30323116d4aae5bd3..f8037549b3c660b0c91e56124a19f0d8c81337ac 100644 --- a/src/FlightDisplay/VirtualJoystick.qml +++ b/src/FlightDisplay/VirtualJoystick.qml @@ -27,8 +27,8 @@ Item { running: QGroundControl.settingsManager.appSettings.virtualJoystick.value && activeVehicle repeat: true onTriggered: { - if (activeVehicle) { - activeVehicle.virtualTabletJoystickValue(rightStick.xAxis, rightStick.yAxis, leftStick.xAxis, leftStick.yAxis) + if (_activeVehicle) { + _activeVehicle.virtualTabletJoystickValue(rightStick.xAxis, rightStick.yAxis, leftStick.xAxis, leftStick.yAxis) } } } diff --git a/src/FlightMap/FlightMap.qml b/src/FlightMap/FlightMap.qml index 50407081439cf53e7ca013d38d92e0be161a6f3b..bddb56bc6a34318e85116294cc58d6ff3aa7b440 100644 --- a/src/FlightMap/FlightMap.qml +++ b/src/FlightMap/FlightMap.qml @@ -45,7 +45,8 @@ Map { readonly property real maxZoomLevel: 20 - property var activeVehicleCoordinate: activeVehicle ? activeVehicle.coordinate : QtPositioning.coordinate() + property var _activeVehicle: QGroundControl.multiVehicleManager.activeVehicle + property var _activeVehicleCoordinate: _activeVehicle ? _activeVehicle.coordinate : QtPositioning.coordinate() function setVisibleRegion(region) { // TODO: Is this still necessary with Qt 5.11? @@ -57,9 +58,9 @@ Map { } function _possiblyCenterToVehiclePosition() { - if (!firstVehiclePositionReceived && allowVehicleLocationCenter && activeVehicleCoordinate.isValid) { + if (!firstVehiclePositionReceived && allowVehicleLocationCenter && _activeVehicleCoordinate.isValid) { firstVehiclePositionReceived = true - center = activeVehicleCoordinate + center = _activeVehicleCoordinate zoomLevel = QGroundControl.flightMapInitialZoom } } @@ -81,8 +82,8 @@ Map { if (gcsPosition.isValid && allowGCSLocationCenter && !firstGCSPositionReceived && !firstVehiclePositionReceived) { firstGCSPositionReceived = true //-- Only center on gsc if we have no vehicle (and we are supposed to do so) - var activeVehicleCoordinate = activeVehicle ? activeVehicle.coordinate : QtPositioning.coordinate() - if(QGroundControl.settingsManager.flyViewSettings.keepMapCenteredOnVehicle.rawValue || !activeVehicleCoordinate.isValid) + var _activeVehicleCoordinate = _activeVehicle ? _activeVehicle.coordinate : QtPositioning.coordinate() + if(QGroundControl.settingsManager.flyViewSettings.keepMapCenteredOnVehicle.rawValue || !_activeVehicleCoordinate.isValid) center = gcsPosition } } @@ -99,7 +100,7 @@ Map { } } - onActiveVehicleCoordinateChanged: _possiblyCenterToVehiclePosition() + on_ActiveVehicleCoordinateChanged: _possiblyCenterToVehiclePosition() Component.onCompleted: { updateActiveMapType() diff --git a/src/FlightMap/MapItems/PlanMapItems.qml b/src/FlightMap/MapItems/PlanMapItems.qml index b652fba2b4d3aec194afad9d247c1dafd0c15c96..9910559d94ed34419382e5414eb870ea224ecaed 100644 --- a/src/FlightMap/MapItems/PlanMapItems.qml +++ b/src/FlightMap/MapItems/PlanMapItems.qml @@ -30,7 +30,7 @@ Item { property var _missionController: masterController.missionController property var _geoFenceController: masterController.geoFenceController property var _rallyPointController: masterController.rallyPointController - property var _guidedController: mainWindow.guidedControllerFlyView + property var _guidedController: globals.guidedControllerFlyView property var _missionLineViewComponent property bool _isActiveVehicle: vehicle.active diff --git a/src/FlightMap/Widgets/CenterMapDropButton.qml b/src/FlightMap/Widgets/CenterMapDropButton.qml index 66d24ef207f9cf1a99f9f32dff5f75647b603512..eaeb86a838b4ac1528830614e80cf296cf024ff3 100644 --- a/src/FlightMap/Widgets/CenterMapDropButton.qml +++ b/src/FlightMap/Widgets/CenterMapDropButton.qml @@ -221,11 +221,11 @@ DropButton { QGCButton { text: qsTr("Vehicle") Layout.fillWidth: true - enabled: activeVehicle && activeVehicle.latitude != 0 && activeVehicle.longitude != 0 && !followVehicleCheckBox.checked + enabled: globals.activeVehicle && globals.activeVehicle.latitude != 0 && globals.activeVehicle.longitude != 0 && !followVehicleCheckBox.checked onClicked: { dropButton.hideDropDown() - map.center = activeVehicle.coordinate + map.center = globals.activeVehicle.coordinate } } diff --git a/src/FlightMap/Widgets/CenterMapDropPanel.qml b/src/FlightMap/Widgets/CenterMapDropPanel.qml index a151f76f94aeafcf378e00c9bd7d8b6dcfa1ce14..f3cf21d3f859e3b6edda8c3523e6737e095ea121 100644 --- a/src/FlightMap/Widgets/CenterMapDropPanel.qml +++ b/src/FlightMap/Widgets/CenterMapDropPanel.qml @@ -63,11 +63,11 @@ ColumnLayout { QGCButton { text: qsTr("Vehicle") Layout.fillWidth: true - enabled: activeVehicle && activeVehicle.coordinate.isValid + enabled: globals.activeVehicle && globals.activeVehicle.coordinate.isValid onClicked: { dropPanel.hide() - map.center = activeVehicle.coordinate + map.center = globals.activeVehicle.coordinate } } diff --git a/src/FlightMap/Widgets/QGCCompassWidget.qml b/src/FlightMap/Widgets/QGCCompassWidget.qml index 0fc4d0ac8253eb651de0581da78bc1a7606fa5df..f1f1a3846c76b977d28d8c62cedfce14bcc1824e 100644 --- a/src/FlightMap/Widgets/QGCCompassWidget.qml +++ b/src/FlightMap/Widgets/QGCCompassWidget.qml @@ -31,14 +31,15 @@ Item { property real size: _defaultSize property var vehicle: null - property real _defaultSize: ScreenTools.defaultFontPixelHeight * (10) - property real _sizeRatio: ScreenTools.isTinyScreen ? (size / _defaultSize) * 0.5 : size / _defaultSize - property int _fontSize: ScreenTools.defaultFontPointSize * _sizeRatio - property real _heading: vehicle ? vehicle.heading.rawValue : 0 - property real _headingToHome: vehicle ? vehicle.headingToHome.rawValue : 0 - property real _groundSpeed: vehicle ? vehicle.groundSpeed.rawValue : 0 - property real _headingToNextWP: vehicle ? vehicle.headingToNextWP.rawValue : 0 - property real _courseOverGround:activeVehicle ? activeVehicle.gps.courseOverGround.rawValue : 0 + property var _activeVehicle: QGroundControl.multiVehicleManager.activeVehicle + property real _defaultSize: ScreenTools.defaultFontPixelHeight * (10) + property real _sizeRatio: ScreenTools.isTinyScreen ? (size / _defaultSize) * 0.5 : size / _defaultSize + property int _fontSize: ScreenTools.defaultFontPointSize * _sizeRatio + property real _heading: vehicle ? vehicle.heading.rawValue : 0 + property real _headingToHome: vehicle ? vehicle.headingToHome.rawValue : 0 + property real _groundSpeed: vehicle ? vehicle.groundSpeed.rawValue : 0 + property real _headingToNextWP: vehicle ? vehicle.headingToNextWP.rawValue : 0 + property real _courseOverGround: _activeVehicle ? _activeVehicle.gps.courseOverGround.rawValue : 0 property bool usedByMultipleVehicleList: false diff --git a/src/FlightMap/Widgets/QGCInstrumentWidget.qml b/src/FlightMap/Widgets/QGCInstrumentWidget.qml index 76885eda4fd32dd99f7af727cac941d5a1b9975a..0c69160a20b2be286b29993abdfb7f7075f78dab 100644 --- a/src/FlightMap/Widgets/QGCInstrumentWidget.qml +++ b/src/FlightMap/Widgets/QGCInstrumentWidget.qml @@ -43,7 +43,7 @@ ColumnLayout { anchors.leftMargin: _topBottomMargin anchors.left: parent.left size: _innerRadius * 2 - vehicle: activeVehicle + vehicle: globals.activeVehicle anchors.verticalCenter: parent.verticalCenter } @@ -52,7 +52,7 @@ ColumnLayout { anchors.leftMargin: _spacing anchors.left: attitude.right size: _innerRadius * 2 - vehicle: activeVehicle + vehicle: globals.activeVehicle anchors.verticalCenter: parent.verticalCenter } } diff --git a/src/FlightMap/Widgets/QGCInstrumentWidgetAlternate.qml b/src/FlightMap/Widgets/QGCInstrumentWidgetAlternate.qml index bd551b9a7ab2404928ee4de85219999c55adb5b5..283a077f48e6c27082aec71d012f77fc7aca666d 100644 --- a/src/FlightMap/Widgets/QGCInstrumentWidgetAlternate.qml +++ b/src/FlightMap/Widgets/QGCInstrumentWidgetAlternate.qml @@ -44,7 +44,7 @@ Rectangle { anchors.margins : _margins anchors.top: parent.top size: _innerRadius * 2 - vehicle: activeVehicle + vehicle: globals.activeVehicle } QGCCompassWidget { @@ -53,6 +53,6 @@ Rectangle { anchors.margins: _margins anchors.top: attitude.bottom size: _innerRadius * 2 - vehicle: activeVehicle + vehicle: globals.activeVehicle } } diff --git a/src/PlanView/FWLandingPatternEditor.qml b/src/PlanView/FWLandingPatternEditor.qml index b5b1bb5f6600cc504984b9811e5c8e4305c985d9..6701183d4a447e7b47bf3509dcf2f0231e1dd533 100644 --- a/src/PlanView/FWLandingPatternEditor.qml +++ b/src/PlanView/FWLandingPatternEditor.qml @@ -97,8 +97,8 @@ Rectangle { QGCButton { text: _setToVehicleHeadingStr - visible: activeVehicle - onClicked: missionItem.landingHeading.rawValue = activeVehicle.heading.rawValue + visible: globals.activeVehicle + onClicked: missionItem.landingHeading.rawValue = globals.activeVehicle.heading.rawValue } } @@ -167,9 +167,9 @@ Rectangle { QGCButton { text: _setToVehicleLocationStr - visible: activeVehicle + visible: globals.activeVehicle Layout.columnSpan: 2 - onClicked: missionItem.landingCoordinate = activeVehicle.coordinate + onClicked: missionItem.landingCoordinate = globals.activeVehicle.coordinate } } } @@ -278,17 +278,17 @@ Rectangle { anchors.right: parent.right horizontalAlignment: Text.AlignHCenter text: qsTr("- or -") - visible: activeVehicle + visible: globals.activeVehicle } QGCButton { anchors.horizontalCenter: parent.horizontalCenter text: _setToVehicleLocationStr - visible: activeVehicle + visible: globals.activeVehicle onClicked: { - missionItem.landingCoordinate = activeVehicle.coordinate - missionItem.landingHeading.rawValue = activeVehicle.heading.rawValue + missionItem.landingCoordinate = globals.activeVehicle.coordinate + missionItem.landingHeading.rawValue = globals.activeVehicle.heading.rawValue missionItem.setLandingHeadingToTakeoffHeading() } } diff --git a/src/PlanView/PlanToolBarIndicators.qml b/src/PlanView/PlanToolBarIndicators.qml index 491aab2489afd7c885e7efce14c8f1634708a12b..571448b1ebd9aa72dade0ef3c5cff725ec0a1e7d 100644 --- a/src/PlanView/PlanToolBarIndicators.qml +++ b/src/PlanView/PlanToolBarIndicators.qml @@ -13,8 +13,8 @@ import QGroundControl.Palette 1.0 Item { width: missionStats.width + _margins - property var _planMasterController: mainWindow.planMasterControllerPlanView - property var _currentMissionItem: mainWindow.currentPlanMissionItem ///< Mission item to display status for + property var _planMasterController: globals.planMasterControllerPlanView + property var _currentMissionItem: globals.currentPlanMissionItem ///< Mission item to display status for property var missionItems: _controllerValid ? _planMasterController.missionController.visualItems : undefined property real missionDistance: _controllerValid ? _planMasterController.missionController.missionDistance : NaN diff --git a/src/PlanView/PlanView.qml b/src/PlanView/PlanView.qml index 620eb81fec5a24ce23962c04ffbfbf5cf468422d..141abedea08bdb683baa748d4e5ef874b98bdcaf 100644 --- a/src/PlanView/PlanView.qml +++ b/src/PlanView/PlanView.qml @@ -218,7 +218,7 @@ Item { Component.onCompleted: { _planMasterController.start() _missionController.setCurrentPlanViewSeqNum(0, true) - mainWindow.planMasterControllerPlanView = _planMasterController + globals.planMasterControllerPlanView = _planMasterController } onPromptForPlanUsageOnVehicleChange: { @@ -1040,7 +1040,7 @@ Item { id: unsavedChangedLabel Layout.fillWidth: true wrapMode: Text.WordWrap - text: activeVehicle ? + text: globals.activeVehicle ? qsTr("You have unsaved changes. You should upload to your vehicle, or save to a file.") : qsTr("You have unsaved changes.") visible: _planMasterController.dirty diff --git a/src/PlanView/VTOLLandingPatternEditor.qml b/src/PlanView/VTOLLandingPatternEditor.qml index 196fc2705f3b0962ff0aa347291ea46d3b4667fe..0d0927f4b7ad9380750f59611a2d5c245a107ebb 100644 --- a/src/PlanView/VTOLLandingPatternEditor.qml +++ b/src/PlanView/VTOLLandingPatternEditor.qml @@ -105,8 +105,8 @@ Rectangle { QGCButton { text: _setToVehicleHeadingStr - visible: activeVehicle - onClicked: missionItem.landingHeading.rawValue = activeVehicle.heading.rawValue + visible: globals.activeVehicle + onClicked: missionItem.landingHeading.rawValue = globals.activeVehicle.heading.rawValue } } @@ -154,9 +154,9 @@ Rectangle { QGCButton { text: _setToVehicleLocationStr - visible: activeVehicle + visible: globals.activeVehicle Layout.columnSpan: 2 - onClicked: missionItem.landingCoordinate = activeVehicle.coordinate + onClicked: missionItem.landingCoordinate = globals.activeVehicle.coordinate } } } @@ -265,17 +265,17 @@ Rectangle { anchors.right: parent.right horizontalAlignment: Text.AlignHCenter text: qsTr("- or -") - visible: activeVehicle + visible: globals.activeVehicle } QGCButton { anchors.horizontalCenter: parent.horizontalCenter text: _setToVehicleLocationStr - visible: activeVehicle + visible: globals.activeVehicle onClicked: { - missionItem.landingCoordinate = activeVehicle.coordinate - missionItem.landingHeading.rawValue = activeVehicle.heading.rawValue + missionItem.landingCoordinate = globals.activeVehicle.coordinate + missionItem.landingHeading.rawValue = globals.activeVehicle.heading.rawValue missionItem.setLandingHeadingToTakeoffHeading() } } diff --git a/src/QGCApplication.cc b/src/QGCApplication.cc index 7177376d48ec895c402cc16a05c7b698364fe14b..33904ea035d0839be7ab80603b1db3250d04fef3 100644 --- a/src/QGCApplication.cc +++ b/src/QGCApplication.cc @@ -783,7 +783,7 @@ QObject* QGCApplication::_rootQmlObject() return nullptr; } -void QGCApplication::showVehicleMessage(const QString& message) +void QGCApplication::showCriticalVehicleMessage(const QString& message) { // PreArm messages are handled by Vehicle and shown in Map if (message.startsWith(QStringLiteral("PreArm")) || message.startsWith(QStringLiteral("preflight"), Qt::CaseInsensitive)) { @@ -793,10 +793,10 @@ void QGCApplication::showVehicleMessage(const QString& message) if (rootQmlObject) { QVariant varReturn; QVariant varMessage = QVariant::fromValue(message); - QMetaObject::invokeMethod(_rootQmlObject(), "showVehicleMessage", Q_RETURN_ARG(QVariant, varReturn), Q_ARG(QVariant, varMessage)); + QMetaObject::invokeMethod(_rootQmlObject(), "showCriticalVehicleMessage", Q_RETURN_ARG(QVariant, varReturn), Q_ARG(QVariant, varMessage)); } else if (runningUnitTests()) { // Unit tests can run without UI - qDebug() << "QGCApplication::showVehicleMessage unittest" << message; + qDebug() << "QGCApplication::showCriticalVehicleMessage unittest" << message; } else { qWarning() << "Internal error"; } diff --git a/src/QGCApplication.h b/src/QGCApplication.h index f66f8b14970cd03da5588252bc9cfcdec87b07f8..4966687cb5fe78ed3d067abb40901780da623888 100644 --- a/src/QGCApplication.h +++ b/src/QGCApplication.h @@ -78,7 +78,7 @@ public: void reportMissingParameter(int componentId, const QString& name); /// Show non-modal vehicle message to the user - Q_SLOT void showVehicleMessage(const QString& message); + Q_SLOT void showCriticalVehicleMessage(const QString& message); /// Show modal application message to the user Q_SLOT void showAppMessage(const QString& message, const QString& title = QString()); diff --git a/src/QmlControls/LogReplayStatusBar.qml b/src/QmlControls/LogReplayStatusBar.qml index f341624faadabe0e157b1e3c9eb5abf6d1484231..ab56388675959e538c8cb01f58ec4dbde4c6e36a 100644 --- a/src/QmlControls/LogReplayStatusBar.qml +++ b/src/QmlControls/LogReplayStatusBar.qml @@ -15,7 +15,7 @@ Rectangle { property var _logReplayLink: null function pickLogFile() { - if (mainWindow.activeVehicle) { + if (globals.activeVehicle) { mainWindow.showMessageDialog(qsTr("Log Replay"), qsTr("You must close all connections prior to replaying a log.")) return } diff --git a/src/QmlControls/PIDTuning.qml b/src/QmlControls/PIDTuning.qml index 6aafb37244203faa7c07651633ff8cf807e1e24d..1de9b3c2bb471705c13c9c1e81724be1b7ef489b 100644 --- a/src/QmlControls/PIDTuning.qml +++ b/src/QmlControls/PIDTuning.qml @@ -27,18 +27,18 @@ RowLayout { property real _chartHeight: ScreenTools.defaultFontPixelHeight * 20 property real _margins: ScreenTools.defaultFontPixelHeight / 2 property string _currentTuneType: tuneList[0] - property real _roll: activeVehicle.roll.value - property real _rollSetpoint: activeVehicle.setpoint.roll.value - property real _rollRate: activeVehicle.rollRate.value - property real _rollRateSetpoint: activeVehicle.setpoint.rollRate.value - property real _pitch: activeVehicle.pitch.value - property real _pitchSetpoint: activeVehicle.setpoint.pitch.value - property real _pitchRate: activeVehicle.pitchRate.value - property real _pitchRateSetpoint: activeVehicle.setpoint.pitchRate.value - property real _yaw: activeVehicle.heading.value - property real _yawSetpoint: activeVehicle.setpoint.yaw.value - property real _yawRate: activeVehicle.yawRate.value - property real _yawRateSetpoint: activeVehicle.setpoint.yawRate.value + property real _roll: globals.activeVehicle.roll.value + property real _rollSetpoint: globals.activeVehicle.setpoint.roll.value + property real _rollRate: globals.activeVehicle.rollRate.value + property real _rollRateSetpoint: globals.activeVehicle.setpoint.rollRate.value + property real _pitch: globals.activeVehicle.pitch.value + property real _pitchSetpoint: globals.activeVehicle.setpoint.pitch.value + property real _pitchRate: globals.activeVehicle.pitchRate.value + property real _pitchRateSetpoint: globals.activeVehicle.setpoint.pitchRate.value + property real _yaw: globals.activeVehicle.heading.value + property real _yawSetpoint: globals.activeVehicle.setpoint.yaw.value + property real _yawRate: globals.activeVehicle.yawRate.value + property real _yawRateSetpoint: globals.activeVehicle.setpoint.yawRate.value property var _valueXAxis: valueXAxis property var _valueRateXAxis: valueRateXAxis property var _valueYAxis: valueYAxis @@ -142,11 +142,11 @@ RowLayout { } Component.onCompleted: { - activeVehicle.setPIDTuningTelemetryMode(true) + globals.activeVehicle.setPIDTuningTelemetryMode(true) saveTuningParamValues() } - Component.onDestruction: activeVehicle.setPIDTuningTelemetryMode(false) + Component.onDestruction: globals.activeVehicle.setPIDTuningTelemetryMode(false) on_CurrentTuneTypeChanged: { saveTuningParamValues() @@ -369,7 +369,7 @@ RowLayout { onClicked: { dataTimer.running = !dataTimer.running if (autoModeChange.checked) { - activeVehicle.flightMode = dataTimer.running ? "Stabilized" : activeVehicle.pauseFlightMode + globals.activeVehicle.flightMode = dataTimer.running ? "Stabilized" : globals.activeVehicle.pauseFlightMode } } } @@ -388,7 +388,7 @@ RowLayout { } QGCLabel { - text: qsTr("Switches to '%1' when you click Stop.").arg(activeVehicle.pauseFlightMode) + text: qsTr("Switches to '%1' when you click Stop.").arg(globals.activeVehicle.pauseFlightMode) font.pointSize: ScreenTools.smallFontPointSize } } diff --git a/src/QmlControls/ParameterEditor.qml b/src/QmlControls/ParameterEditor.qml index eb7c482f4f3c3954a131dfb1b94db3b364f3bc17..13ffcac57d17a6f2f0e75cee2ddecaf24a29aa0a 100644 --- a/src/QmlControls/ParameterEditor.qml +++ b/src/QmlControls/ParameterEditor.qml @@ -112,7 +112,7 @@ Item { } QGCMenuItem { text: qsTr("Reset to vehicle's configuration defaults") - visible: !activeVehicle.apmFirmware + visible: !_activeVehicle.apmFirmware onTriggered: mainWindow.showComponentDialog(resetToVehicleConfigurationConfirmComponent, qsTr("Reset All"), mainWindow.showDialogDefaultWidth, StandardButton.Cancel | StandardButton.Reset) } QGCMenuSeparator { } @@ -345,7 +345,7 @@ Item { QGCViewDialog { function accept() { - activeVehicle.rebootVehicle() + _activeVehicle.rebootVehicle() hideDialog() } diff --git a/src/QmlControls/ParameterEditorDialog.qml b/src/QmlControls/ParameterEditorDialog.qml index 4d5138114a68e433aa1604a2adc90d0c781f6d0c..171f195bd27fe5eae3496ee0d23a190a8283f602 100644 --- a/src/QmlControls/ParameterEditorDialog.qml +++ b/src/QmlControls/ParameterEditorDialog.qml @@ -101,7 +101,7 @@ QGCViewDialog { Column { id: _column - spacing: defaultTextHeight + spacing: globals.defaultTextHeight anchors.left: parent.left anchors.right: parent.right diff --git a/src/Vehicle/Vehicle.cc b/src/Vehicle/Vehicle.cc index dc56bd7afe64aa2ffb1ee70668f24990bdd75ff2..3423eae5e0363fa57479ac9faa0552a4f3dc0863 100644 --- a/src/Vehicle/Vehicle.cc +++ b/src/Vehicle/Vehicle.cc @@ -1959,7 +1959,7 @@ bool Vehicle::xConfigMotors() return _firmwarePlugin->multiRotorXConfig(this); } -QString Vehicle::formatedMessages() +QString Vehicle::formattedMessages() { QString messages; for(UASMessage* message: _toolbox->uasMessageHandler()->messages()) { @@ -1975,10 +1975,8 @@ void Vehicle::clearMessages() void Vehicle::_handletextMessageReceived(UASMessage* message) { - if(message) - { - _formatedMessage = message->getFormatedText(); - emit formatedMessageChanged(); + if (message) { + emit newFormattedMessage(message->getFormatedText()); } } diff --git a/src/Vehicle/Vehicle.h b/src/Vehicle/Vehicle.h index 2a95fa6bcc464d43b1f3fd6e43012f30d4c5c932..53105167a1ee2f661116de2f7be5633107592437 100644 --- a/src/Vehicle/Vehicle.h +++ b/src/Vehicle/Vehicle.h @@ -149,8 +149,7 @@ public: Q_PROPERTY(bool messageTypeError READ messageTypeError NOTIFY messageTypeChanged) Q_PROPERTY(int newMessageCount READ newMessageCount NOTIFY newMessageCountChanged) Q_PROPERTY(int messageCount READ messageCount NOTIFY messageCountChanged) - Q_PROPERTY(QString formatedMessages READ formatedMessages NOTIFY formatedMessagesChanged) - Q_PROPERTY(QString formatedMessage READ formatedMessage NOTIFY formatedMessageChanged) + Q_PROPERTY(QString formattedMessages READ formattedMessages NOTIFY formattedMessagesChanged) Q_PROPERTY(QString latestError READ latestError NOTIFY latestErrorChanged) Q_PROPERTY(bool joystickEnabled READ joystickEnabled WRITE setJoystickEnabled NOTIFY joystickEnabledChanged) Q_PROPERTY(bool active READ active WRITE setActive NOTIFY activeChanged) @@ -227,7 +226,7 @@ public: Q_PROPERTY(qreal gimbalPitch READ gimbalPitch NOTIFY gimbalPitchChanged) Q_PROPERTY(qreal gimbalYaw READ gimbalYaw NOTIFY gimbalYawChanged) Q_PROPERTY(bool gimbalData READ gimbalData NOTIFY gimbalDataChanged) - Q_PROPERTY(bool iARDURsROIEnabled READ isROIEnabled NOTIFY isROIEnabledChanged) + Q_PROPERTY(bool isROIEnabled READ isROIEnabled NOTIFY isROIEnabledChanged) Q_PROPERTY(CheckList checkListState READ checkListState WRITE setCheckListState NOTIFY checkListStateChanged) Q_PROPERTY(bool readyToFlyAvailable READ readyToFlyAvailable NOTIFY readyToFlyAvailableChanged) ///< true: readyToFly signalling is available on this vehicle Q_PROPERTY(bool readyToFly READ readyToFly NOTIFY readyToFlyChanged) @@ -506,8 +505,7 @@ public: bool messageTypeError () { return _currentMessageType == MessageError; } int newMessageCount () { return _currentMessageCount; } int messageCount () { return _messageCount; } - QString formatedMessages (); - QString formatedMessage () { return _formatedMessage; } + QString formattedMessages (); QString latestError () { return _latestError; } float latitude () { return static_cast(_coordinate.latitude()); } float longitude () { return static_cast(_coordinate.longitude()); } @@ -814,8 +812,8 @@ signals: void messageTypeChanged (); void newMessageCountChanged (); void messageCountChanged (); - void formatedMessagesChanged (); - void formatedMessageChanged (); + void formattedMessagesChanged (); + void newFormattedMessage (QString formattedMessage); void latestErrorChanged (); void longitudeChanged (); void currentConfigChanged (); @@ -1015,7 +1013,6 @@ private: MessageType_t _currentMessageType; QString _latestError; int _updateCount; - QString _formatedMessage; int _rcRSSI; double _rcRSSIstore; bool _autoDisconnect; ///< true: Automatically disconnect vehicle when last connection goes away or lost heartbeat diff --git a/src/VehicleSetup/FirmwareUpgrade.qml b/src/VehicleSetup/FirmwareUpgrade.qml index f602bd33bd587b55e291f28ef13850652a8c6e3b..17aaad10594215c59da670230462ee5d48012fa1 100644 --- a/src/VehicleSetup/FirmwareUpgrade.qml +++ b/src/VehicleSetup/FirmwareUpgrade.qml @@ -26,7 +26,7 @@ SetupPage { id: firmwarePage pageComponent: firmwarePageComponent pageName: qsTr("Firmware") - showAdvanced: activeVehicle && activeVehicle.apmFirmware + showAdvanced: globals.activeVehicle && globals.activeVehicle.apmFirmware Component { id: firmwarePageComponent @@ -97,7 +97,7 @@ SetupPage { property var activeVehicle: QGroundControl.multiVehicleManager.activeVehicle onActiveVehicleChanged: { - if (!activeVehicle) { + if (!globals.activeVehicle) { statusTextArea.append(plugInText) } } @@ -303,7 +303,7 @@ SetupPage { id: mainColumn anchors.left: parent.left anchors.right: parent.right - spacing: defaultTextHeight + spacing: globals.defaultTextHeight QGCLabel { width: parent.width @@ -511,7 +511,7 @@ SetupPage { id: flashBootloaderButton text: qsTr("Flash ChibiOS Bootloader") visible: firmwarePage.advanced - onClicked: activeVehicle.flashBootloader() + onClicked: globals.activeVehicle.flashBootloader() } TextArea { diff --git a/src/VehicleSetup/JoystickConfigAdvanced.qml b/src/VehicleSetup/JoystickConfigAdvanced.qml index a0e86d97802e5bf3ad82be7221e1a86b7969e318..833d62147e026bf6abf34e24a58efbd9c2fd7c3e 100644 --- a/src/VehicleSetup/JoystickConfigAdvanced.qml +++ b/src/VehicleSetup/JoystickConfigAdvanced.qml @@ -59,12 +59,12 @@ Item { //------------------------------------------------------------- QGCLabel { text: qsTr("Allow negative Thrust") - visible: activeVehicle.supportsNegativeThrust + visible: globals.activeVehicle.supportsNegativeThrust Layout.alignment: Qt.AlignVCenter } QGCCheckBox { - visible: activeVehicle.supportsNegativeThrust - enabled: _activeJoystick.negativeThrust = activeVehicle.supportsNegativeThrust + visible: globals.activeVehicle.supportsNegativeThrust + enabled: _activeJoystick.negativeThrust = globals.activeVehicle.supportsNegativeThrust checked: _activeJoystick ? _activeJoystick.negativeThrust : false onClicked: _activeJoystick.negativeThrust = checked } @@ -96,10 +96,10 @@ Item { } QGCCheckBox { id: advancedSettings - checked: activeVehicle.joystickMode !== 0 + checked: globals.activeVehicle.joystickMode !== 0 onClicked: { if (!checked) { - activeVehicle.joystickMode = 0 + globals.activeVehicle.joystickMode = 0 } } } @@ -171,7 +171,7 @@ Item { visible: advancedSettings.checked } QGCCheckBox { - checked: activeVehicle.joystickMode !== 0 + checked: globals.activeVehicle.joystickMode !== 0 enabled: advancedSettings.checked Component.onCompleted: { checked = _activeJoystick.circleCorrection diff --git a/src/VehicleSetup/JoystickConfigButtons.qml b/src/VehicleSetup/JoystickConfigButtons.qml index 10d6ad7aa240e71622092464991de57b075c2176..5eea2b51d9d6b4cf7fb8e71c07149a0c63680a3d 100644 --- a/src/VehicleSetup/JoystickConfigButtons.qml +++ b/src/VehicleSetup/JoystickConfigButtons.qml @@ -22,7 +22,7 @@ import QGroundControl.FactControls 1.0 Item { width: availableWidth - height: (activeVehicle.supportsJSButton ? buttonCol.height : flowColumn.height) + (ScreenTools.defaultFontPixelHeight * 2) + height: (globals.activeVehicle.supportsJSButton ? buttonCol.height : flowColumn.height) + (ScreenTools.defaultFontPixelHeight * 2) Connections { target: _activeJoystick onRawButtonPressedChanged: { @@ -48,7 +48,7 @@ Item { id: buttonFlow Layout.preferredWidth: parent.width spacing: ScreenTools.defaultFontPixelWidth - visible: !activeVehicle.supportsJSButton + visible: !globals.activeVehicle.supportsJSButton Repeater { id: buttonActionRepeater model: _activeJoystick ? Math.min(_activeJoystick.totalButtonCount, _maxButtons) : [] @@ -113,7 +113,7 @@ Item { Column { id: buttonCol width: parent.width - visible: activeVehicle.supportsJSButton + visible: globals.activeVehicle.supportsJSButton spacing: ScreenTools.defaultFontPixelHeight / 3 Row { spacing: ScreenTools.defaultFontPixelWidth @@ -137,7 +137,7 @@ Item { Row { spacing: ScreenTools.defaultFontPixelWidth - visible: activeVehicle.supportsJSButton + visible: globals.activeVehicle.supportsJSButton property bool pressed diff --git a/src/VehicleSetup/JoystickConfigGeneral.qml b/src/VehicleSetup/JoystickConfigGeneral.qml index eb60e785cdac571fffeefa6ae35a78d8d7eede8a..7d59724c63894e39a8270fbd7f8edfa90b41398f 100644 --- a/src/VehicleSetup/JoystickConfigGeneral.qml +++ b/src/VehicleSetup/JoystickConfigGeneral.qml @@ -42,21 +42,21 @@ Item { QGCCheckBox { id: enabledSwitch enabled: _activeJoystick ? _activeJoystick.calibrated : false - onClicked: activeVehicle.joystickEnabled = checked + onClicked: globals.activeVehicle.joystickEnabled = checked Component.onCompleted: { - checked = activeVehicle.joystickEnabled + checked = globals.activeVehicle.joystickEnabled } Connections { - target: activeVehicle + target: globals.activeVehicle onJoystickEnabledChanged: { - enabledSwitch.checked = activeVehicle.joystickEnabled + enabledSwitch.checked = globals.activeVehicle.joystickEnabled } } Connections { target: joystickManager onActiveJoystickChanged: { if(_activeJoystick) { - enabledSwitch.checked = Qt.binding(function() { return _activeJoystick.calibrated && activeVehicle.joystickEnabled }) + enabledSwitch.checked = Qt.binding(function() { return _activeJoystick.calibrated && globals.activeVehicle.joystickEnabled }) } } } @@ -148,7 +148,7 @@ Item { rowSpacing: ScreenTools.defaultFontPixelHeight anchors.centerIn: parent QGCLabel { - text: activeVehicle.sub ? qsTr("Lateral") : qsTr("Roll") + text: globals.activeVehicle.sub ? qsTr("Lateral") : qsTr("Roll") Layout.minimumWidth: ScreenTools.defaultFontPixelWidth * 12 } AxisMonitor { @@ -162,7 +162,7 @@ Item { QGCLabel { id: pitchLabel width: _attitudeLabelWidth - text: activeVehicle.sub ? qsTr("Forward") : qsTr("Pitch") + text: globals.activeVehicle.sub ? qsTr("Forward") : qsTr("Pitch") } AxisMonitor { id: pitchAxis diff --git a/src/VehicleSetup/PX4FlowSensor.qml b/src/VehicleSetup/PX4FlowSensor.qml index 8146e256cf30acdb8ced01a852f9957340fd4196..8cd3d22a9a4ba58f11b3546479154890ded3d6bb 100644 --- a/src/VehicleSetup/PX4FlowSensor.qml +++ b/src/VehicleSetup/PX4FlowSensor.qml @@ -24,7 +24,7 @@ Item { font.family: ScreenTools.demiboldFontFamily } Image { - source: activeVehicle ? "image://QGCImages/" + activeVehicle.id + "/" + activeVehicle.flowImageIndex : "" + source: globals.activeVehicle ? "image://QGCImages/" + globals.activeVehicle.id + "/" + globals.activeVehicle.flowImageIndex : "" width: parent.width * 0.5 height: width * 0.75 cache: false diff --git a/src/comm/MockLink.cc b/src/comm/MockLink.cc index 5786cadd100842e6422d4e9f53af7df9af51d2ab..9cb3bb446f40ac2da0697e08d6d6c3a98b15aa90 100644 --- a/src/comm/MockLink.cc +++ b/src/comm/MockLink.cc @@ -1252,7 +1252,7 @@ void MockLink::_sendStatusTextMessages(void) status->msg, 0, // Not a chunked sequence 0); // Not a chunked sequence - //respondWithMavlinkMessage(msg); + respondWithMavlinkMessage(msg); } _sendChunkedStatusText(1, false /* missingChunks */); diff --git a/src/uas/UASMessageHandler.cc b/src/uas/UASMessageHandler.cc index ddd9adcb891b9065990e7af1eb8f6e44447ab585..1ec3d9eb6006e855e790f776bf70be404de8e6cd 100644 --- a/src/uas/UASMessageHandler.cc +++ b/src/uas/UASMessageHandler.cc @@ -202,7 +202,7 @@ void UASMessageHandler::handleTextMessage(int, int compId, int severity, QString emit textMessageCountChanged(count); if (_showErrorsInToolbar && message->severityIsError()) { - _app->showVehicleMessage(message->getText()); + _app->showCriticalVehicleMessage(message->getText()); } } diff --git a/src/ui/MainRootWindow.qml b/src/ui/MainRootWindow.qml index a82ab3a5e17acfe9dbca0a6dbc73c7298d8a738f..23a8be6e120b0e6a5bb9dfad857d5deebbc5489a 100644 --- a/src/ui/MainRootWindow.qml +++ b/src/ui/MainRootWindow.qml @@ -75,19 +75,18 @@ ApplicationWindow { //------------------------------------------------------------------------- //-- Global Scope Variables - property var activeVehicle: QGroundControl.multiVehicleManager.activeVehicle - property string formatedMessage: activeVehicle ? activeVehicle.formatedMessage : "" - /// Indicates usable height between toolbar and footer - property real availableHeight: mainWindow.height - mainWindow.header.height - mainWindow.footer.height + QtObject { + id: globals - property var planMasterControllerPlanView: null - property var currentPlanMissionItem: planMasterControllerPlanView ? planMasterControllerPlanView.missionController.currentPlanViewItem : null - property var planMasterControllerFlyView: flightView.planController - property var guidedControllerFlyView: flightView.guidedController + readonly property var activeVehicle: QGroundControl.multiVehicleManager.activeVehicle + readonly property real defaultTextHeight: ScreenTools.defaultFontPixelHeight + readonly property real defaultTextWidth: ScreenTools.defaultFontPixelWidth + readonly property var planMasterControllerFlyView: flightView.planController + readonly property var guidedControllerFlyView: flightView.guidedController - readonly property string navButtonWidth: ScreenTools.defaultFontPixelWidth * 24 - readonly property real defaultTextHeight: ScreenTools.defaultFontPixelHeight - readonly property real defaultTextWidth: ScreenTools.defaultFontPixelWidth + property var planMasterControllerPlanView: null + property var currentPlanMissionItem: planMasterControllerPlanView ? planMasterControllerPlanView.missionController.currentPlanViewItem : null + } /// Default color palette used throughout the UI QGCPalette { id: qgcPal; colorGroupEnabled: true } @@ -265,7 +264,7 @@ ApplicationWindow { visible: false onYes: pendingParameterWritesCloseDialog.check() function check() { - if (planMasterControllerPlanView && planMasterControllerPlanView.dirty) { + if (globals.planMasterControllerPlanView && globals.planMasterControllerPlanView.dirty) { unsavedMissionCloseDialog.open() } else { pendingParameterWritesCloseDialog.check() @@ -534,132 +533,23 @@ ApplicationWindow { } //------------------------------------------------------------------------- - //-- Vehicle Messages - - function formatMessage(message) { - message = message.replace(new RegExp("<#E>", "g"), "color: " + qgcPal.warningText + "; font: " + (ScreenTools.defaultFontPointSize.toFixed(0) - 1) + "pt monospace;"); - message = message.replace(new RegExp("<#I>", "g"), "color: " + qgcPal.warningText + "; font: " + (ScreenTools.defaultFontPointSize.toFixed(0) - 1) + "pt monospace;"); - message = message.replace(new RegExp("<#N>", "g"), "color: " + qgcPal.text + "; font: " + (ScreenTools.defaultFontPointSize.toFixed(0) - 1) + "pt monospace;"); - return message; - } - - function showVehicleMessages() { - if(!vehicleMessageArea.visible) { - if(QGroundControl.multiVehicleManager.activeVehicleAvailable) { - messageText.text = formatMessage(activeVehicle.formatedMessages) - //-- Hack to scroll to last message - for (var i = 0; i < activeVehicle.messageCount; i++) - messageFlick.flick(0,-5000) - activeVehicle.resetMessages() - } else { - messageText.text = qsTr("No Messages") - } - vehicleMessageArea.open() - } - } + //-- Critical Vehicle Message Popup - onFormatedMessageChanged: { - if(vehicleMessageArea.visible) { - messageText.append(formatMessage(formatedMessage)) - //-- Hack to scroll down - messageFlick.flick(0,-500) - } - } + property var _vehicleMessageQueue: [] + property string _vehicleMessage: "" - Popup { - id: vehicleMessageArea - width: mainWindow.width * 0.666 - height: mainWindow.height * 0.666 - modal: true - focus: true - x: Math.round((mainWindow.width - width) * 0.5) - y: Math.round((mainWindow.height - height) * 0.5) - closePolicy: Popup.CloseOnEscape | Popup.CloseOnPressOutside - background: Rectangle { - anchors.fill: parent - color: qgcPal.window - border.color: qgcPal.text - radius: ScreenTools.defaultFontPixelHeight * 0.5 - } - QGCFlickable { - id: messageFlick - anchors.margins: ScreenTools.defaultFontPixelHeight - anchors.fill: parent - contentHeight: messageText.height - contentWidth: messageText.width - pixelAligned: true - clip: true - TextEdit { - id: messageText - readOnly: true - textFormat: TextEdit.RichText - color: qgcPal.text - } - } - //-- Dismiss Vehicle Messages - QGCColoredImage { - anchors.margins: ScreenTools.defaultFontPixelHeight * 0.5 - anchors.top: parent.top - anchors.right: parent.right - width: ScreenTools.isMobile ? ScreenTools.defaultFontPixelHeight * 1.5 : ScreenTools.defaultFontPixelHeight - height: width - sourceSize.height: width - source: "/res/XDelete.svg" - fillMode: Image.PreserveAspectFit - mipmap: true - smooth: true - color: qgcPal.text - MouseArea { - anchors.fill: parent - anchors.margins: ScreenTools.isMobile ? -ScreenTools.defaultFontPixelHeight : 0 - onClicked: { - vehicleMessageArea.close() - } - } - } - //-- Clear Messages - QGCColoredImage { - anchors.bottom: parent.bottom - anchors.right: parent.right - anchors.margins: ScreenTools.defaultFontPixelHeight * 0.5 - height: ScreenTools.isMobile ? ScreenTools.defaultFontPixelHeight * 1.5 : ScreenTools.defaultFontPixelHeight - width: height - sourceSize.height: height - source: "/res/TrashDelete.svg" - fillMode: Image.PreserveAspectFit - mipmap: true - smooth: true - color: qgcPal.text - MouseArea { - anchors.fill: parent - onClicked: { - if(QGroundControl.multiVehicleManager.activeVehicleAvailable) { - activeVehicle.clearMessages(); - vehicleMessageArea.close() - } - } - } - } - } - - //------------------------------------------------------------------------- - //-- System Messages - - property var _messageQueue: [] - property string _systemMessage: "" - - function showVehicleMessage(message) { - vehicleMessageArea.close() - if(systemMessageArea.visible || QGroundControl.videoManager.fullScreen) { - _messageQueue.push(message) + function showCriticalVehicleMessage(message) { + indicatorPopup.close() + if (criticalVehicleMessagePopup.visible || QGroundControl.videoManager.fullScreen) { + _vehicleMessageQueue.push(message) } else { - _systemMessage = message - systemMessageArea.open() + _vehicleMessage = message + criticalVehicleMessagePopup.open() } } Popup { - id: systemMessageArea + id: criticalVehicleMessagePopup y: ScreenTools.defaultFontPixelHeight x: Math.round((mainWindow.width - width) * 0.5) width: mainWindow.width * 0.55 @@ -677,39 +567,39 @@ ApplicationWindow { } onOpened: { - systemMessageText.text = mainWindow._systemMessage + criticalVehicleMessageText.text = mainWindow._vehicleMessage } onClosed: { //-- Are there messages in the waiting queue? - if(mainWindow._messageQueue.length) { - mainWindow._systemMessage = "" + if(mainWindow._vehicleMessageQueue.length) { + mainWindow._vehicleMessage = "" //-- Show all messages in queue - for (var i = 0; i < mainWindow._messageQueue.length; i++) { - var text = mainWindow._messageQueue[i] - if(i) mainWindow._systemMessage += "
" - mainWindow._systemMessage += text + for (var i = 0; i < mainWindow._vehicleMessageQueue.length; i++) { + var text = mainWindow._vehicleMessageQueue[i] + if(i) mainWindow._vehicleMessage += "
" + mainWindow._vehicleMessage += text } //-- Clear it - mainWindow._messageQueue = [] - systemMessageArea.open() + mainWindow._vehicleMessageQueue = [] + criticalVehicleMessagePopup.open() } else { - mainWindow._systemMessage = "" + mainWindow._vehicleMessage = "" } } Flickable { - id: systemMessageFlick + id: criticalVehicleMessageFlick anchors.margins: ScreenTools.defaultFontPixelHeight * 0.5 anchors.fill: parent - contentHeight: systemMessageText.height - contentWidth: systemMessageText.width + contentHeight: criticalVehicleMessageText.height + contentWidth: criticalVehicleMessageText.width boundsBehavior: Flickable.StopAtBounds pixelAligned: true clip: true TextEdit { - id: systemMessageText - width: systemMessageArea.width - systemMessageClose.width - (ScreenTools.defaultFontPixelHeight * 2) + id: criticalVehicleMessageText + width: criticalVehicleMessagePopup.width - criticalVehicleMessageClose.width - (ScreenTools.defaultFontPixelHeight * 2) anchors.centerIn: parent readOnly: true textFormat: TextEdit.RichText @@ -720,9 +610,9 @@ ApplicationWindow { } } - //-- Dismiss Critical Message + //-- Dismiss Vehicle Message QGCColoredImage { - id: systemMessageClose + id: criticalVehicleMessageClose anchors.margins: ScreenTools.defaultFontPixelHeight * 0.5 anchors.top: parent.top anchors.right: parent.right @@ -736,7 +626,7 @@ ApplicationWindow { anchors.fill: parent anchors.margins: -ScreenTools.defaultFontPixelHeight onClicked: { - systemMessageArea.close() + criticalVehicleMessagePopup.close() } } } @@ -751,12 +641,12 @@ ApplicationWindow { sourceSize.height: width source: "/res/ArrowDown.svg" fillMode: Image.PreserveAspectFit - visible: systemMessageText.lineCount > 5 + visible: criticalVehicleMessageText.lineCount > 5 color: qgcPal.alertText MouseArea { anchors.fill: parent onClicked: { - systemMessageFlick.flick(0,-500) + criticalVehicleMessageFlick.flick(0,-500) } } } diff --git a/src/ui/preferences/MavlinkSettings.qml b/src/ui/preferences/MavlinkSettings.qml index 0eb3e602c3bc16a598cd4f867d75d32ea1f3d28c..04d4bb2fbbcbd876e7654e205117bb02cb9c2b55 100644 --- a/src/ui/preferences/MavlinkSettings.qml +++ b/src/ui/preferences/MavlinkSettings.qml @@ -311,7 +311,7 @@ Rectangle { } QGCLabel { width: _valueWidth - text: activeVehicle ? activeVehicle.mavlinkSentCount : qsTr("Not Connected") + text: globals.activeVehicle ? globals.activeVehicle.mavlinkSentCount : qsTr("Not Connected") anchors.verticalCenter: parent.verticalCenter } } @@ -326,7 +326,7 @@ Rectangle { } QGCLabel { width: _valueWidth - text: activeVehicle ? activeVehicle.mavlinkReceivedCount : qsTr("Not Connected") + text: globals.activeVehicle ? globals.activeVehicle.mavlinkReceivedCount : qsTr("Not Connected") anchors.verticalCenter: parent.verticalCenter } } @@ -341,7 +341,7 @@ Rectangle { } QGCLabel { width: _valueWidth - text: activeVehicle ? activeVehicle.mavlinkLossCount : qsTr("Not Connected") + text: globals.activeVehicle ? globals.activeVehicle.mavlinkLossCount : qsTr("Not Connected") anchors.verticalCenter: parent.verticalCenter } } @@ -356,7 +356,7 @@ Rectangle { } QGCLabel { width: _valueWidth - text: activeVehicle ? activeVehicle.mavlinkLossPercent.toFixed(0) + '%' : qsTr("Not Connected") + text: globals.activeVehicle ? globals.activeVehicle.mavlinkLossPercent.toFixed(0) + '%' : qsTr("Not Connected") anchors.verticalCenter: parent.verticalCenter } } diff --git a/src/ui/toolbar/BatteryIndicator.qml b/src/ui/toolbar/BatteryIndicator.qml index f3e1aeb842d50e13d0c89ef46f534ad5a26128f1..9d68fc3c750545c12315118e221e70d2d7bf6f06 100644 --- a/src/ui/toolbar/BatteryIndicator.qml +++ b/src/ui/toolbar/BatteryIndicator.qml @@ -27,13 +27,15 @@ Item { property bool showIndicator: true + property var _activeVehicle: QGroundControl.multiVehicleManager.activeVehicle + Row { id: batteryIndicatorRow anchors.top: parent.top anchors.bottom: parent.bottom Repeater { - model: activeVehicle ? activeVehicle.batteries : 0 + model: _activeVehicle ? _activeVehicle.batteries : 0 Loader { anchors.top: parent.top @@ -149,7 +151,7 @@ Item { ColumnLayout { Repeater { - model: activeVehicle ? activeVehicle.batteries : 0 + model: _activeVehicle ? _activeVehicle.batteries : 0 ColumnLayout { spacing: 0 @@ -177,7 +179,7 @@ Item { ColumnLayout { Repeater { - model: activeVehicle ? activeVehicle.batteries : 0 + model: _activeVehicle ? _activeVehicle.batteries : 0 ColumnLayout { spacing: 0 diff --git a/src/ui/toolbar/GPSIndicator.qml b/src/ui/toolbar/GPSIndicator.qml index c0e1936bae54bfe5981b03236f17651711bd9100..881285c66ae84de817a530c2841f30b978da387e 100644 --- a/src/ui/toolbar/GPSIndicator.qml +++ b/src/ui/toolbar/GPSIndicator.qml @@ -26,6 +26,8 @@ Item { property bool showIndicator: true + property var _activeVehicle: QGroundControl.multiVehicleManager.activeVehicle + Component { id: gpsInfo @@ -45,29 +47,29 @@ Item { QGCLabel { id: gpsLabel - text: (activeVehicle && activeVehicle.gps.count.value >= 0) ? qsTr("GPS Status") : qsTr("GPS Data Unavailable") + text: (_activeVehicle && _activeVehicle.gps.count.value >= 0) ? qsTr("GPS Status") : qsTr("GPS Data Unavailable") font.family: ScreenTools.demiboldFontFamily anchors.horizontalCenter: parent.horizontalCenter } GridLayout { id: gpsGrid - visible: (activeVehicle && activeVehicle.gps.count.value >= 0) + visible: (_activeVehicle && _activeVehicle.gps.count.value >= 0) anchors.margins: ScreenTools.defaultFontPixelHeight columnSpacing: ScreenTools.defaultFontPixelWidth anchors.horizontalCenter: parent.horizontalCenter columns: 2 QGCLabel { text: qsTr("GPS Count:") } - QGCLabel { text: activeVehicle ? activeVehicle.gps.count.valueString : qsTr("N/A", "No data to display") } + QGCLabel { text: _activeVehicle ? _activeVehicle.gps.count.valueString : qsTr("N/A", "No data to display") } QGCLabel { text: qsTr("GPS Lock:") } - QGCLabel { text: activeVehicle ? activeVehicle.gps.lock.enumStringValue : qsTr("N/A", "No data to display") } + QGCLabel { text: _activeVehicle ? _activeVehicle.gps.lock.enumStringValue : qsTr("N/A", "No data to display") } QGCLabel { text: qsTr("HDOP:") } - QGCLabel { text: activeVehicle ? activeVehicle.gps.hdop.valueString : qsTr("--.--", "No data to display") } + QGCLabel { text: _activeVehicle ? _activeVehicle.gps.hdop.valueString : qsTr("--.--", "No data to display") } QGCLabel { text: qsTr("VDOP:") } - QGCLabel { text: activeVehicle ? activeVehicle.gps.vdop.valueString : qsTr("--.--", "No data to display") } + QGCLabel { text: _activeVehicle ? _activeVehicle.gps.vdop.valueString : qsTr("--.--", "No data to display") } QGCLabel { text: qsTr("Course Over Ground:") } - QGCLabel { text: activeVehicle ? activeVehicle.gps.courseOverGround.valueString : qsTr("--.--", "No data to display") } + QGCLabel { text: _activeVehicle ? _activeVehicle.gps.courseOverGround.valueString : qsTr("--.--", "No data to display") } } } } @@ -81,7 +83,7 @@ Item { source: "/qmlimages/Gps.svg" fillMode: Image.PreserveAspectFit sourceSize.height: height - opacity: (activeVehicle && activeVehicle.gps.count.value >= 0) ? 1 : 0.5 + opacity: (_activeVehicle && _activeVehicle.gps.count.value >= 0) ? 1 : 0.5 color: qgcPal.buttonText } @@ -93,16 +95,16 @@ Item { QGCLabel { anchors.horizontalCenter: hdopValue.horizontalCenter - visible: activeVehicle && !isNaN(activeVehicle.gps.hdop.value) + visible: _activeVehicle && !isNaN(_activeVehicle.gps.hdop.value) color: qgcPal.buttonText - text: activeVehicle ? activeVehicle.gps.count.valueString : "" + text: _activeVehicle ? _activeVehicle.gps.count.valueString : "" } QGCLabel { id: hdopValue - visible: activeVehicle && !isNaN(activeVehicle.gps.hdop.value) + visible: _activeVehicle && !isNaN(_activeVehicle.gps.hdop.value) color: qgcPal.buttonText - text: activeVehicle ? activeVehicle.gps.hdop.value.toFixed(1) : "" + text: _activeVehicle ? _activeVehicle.gps.hdop.value.toFixed(1) : "" } } diff --git a/src/ui/toolbar/JoystickIndicator.qml b/src/ui/toolbar/JoystickIndicator.qml index 8d0b096d30673c2746c6ced43d782895727d4418..469bc8e12ec48e2e99802c21c4cdf46fdc2f6324 100644 --- a/src/ui/toolbar/JoystickIndicator.qml +++ b/src/ui/toolbar/JoystickIndicator.qml @@ -22,7 +22,7 @@ Item { width: joystickRow.width * 1.1 anchors.top: parent.top anchors.bottom: parent.bottom - visible: activeVehicle ? activeVehicle.sub : false + visible: globals.activeVehicle ? globals.activeVehicle.sub : false Component { @@ -63,8 +63,8 @@ Item { } QGCLabel { text: qsTr("Enabled:") } QGCLabel { - text: activeVehicle && activeVehicle.joystickEnabled ? "Yes" : "No" - color: activeVehicle && activeVehicle.joystickEnabled ? qgcPal.buttonText : "red" + text: globals.activeVehicle && globals.activeVehicle.joystickEnabled ? "Yes" : "No" + color: globals.activeVehicle && globals.activeVehicle.joystickEnabled ? qgcPal.buttonText : "red" } } } @@ -84,7 +84,7 @@ Item { sourceSize.height: height source: "/qmlimages/Joystick.png" fillMode: Image.PreserveAspectFit - color: activeVehicle && activeVehicle.joystickEnabled && joystickManager.activeJoystick ? qgcPal.buttonText : "red" + color: globals.activeVehicle && globals.activeVehicle.joystickEnabled && joystickManager.activeJoystick ? qgcPal.buttonText : "red" } } diff --git a/src/ui/toolbar/LinkIndicator.qml b/src/ui/toolbar/LinkIndicator.qml index 1bf93c8d228e51d183f016f0091a4aa26122968c..0c8a1b182a5a3aceff487dc00a7919807d2960ed 100644 --- a/src/ui/toolbar/LinkIndicator.qml +++ b/src/ui/toolbar/LinkIndicator.qml @@ -27,9 +27,11 @@ Item { property bool showIndicator: false + property var _activeVehicle: QGroundControl.multiVehicleManager.activeVehicle + QGCLabel { id: priorityLinkSelector - text: activeVehicle ? activeVehicle.priorityLinkName : qsTr("N/A", "No data to display") + text: _activeVehicle ? _activeVehicle.priorityLinkName : qsTr("N/A", "No data to display") font.pointSize: ScreenTools.mediumFontPointSize color: qgcPal.buttonText anchors.verticalCenter: parent.verticalCenter @@ -39,12 +41,12 @@ Item { Component { id: linkSelectionMenuItemComponent QGCMenuItem { - onTriggered: activeVehicle.priorityLinkName = text + onTriggered: _activeVehicle.priorityLinkName = text } } property var linkSelectionMenuItems: [] function updatelinkSelectionMenu() { - if (activeVehicle) { + if (_activeVehicle) { // Remove old menu items var i for (i = 0; i < linkSelectionMenuItems.length; i++) { @@ -54,9 +56,9 @@ Item { // Add new items var has_hl = false; - var links = activeVehicle.links + var links = _activeVehicle.links for (i = 0; i < links.length; i++) { - var menuItem = linkSelectionMenuItemComponent.createObject(null, { "text": links[i].getName(), "enabled": links[i].link_active(activeVehicle.id)}) + var menuItem = linkSelectionMenuItemComponent.createObject(null, { "text": links[i].getName(), "enabled": links[i].link_active(_activeVehicle.id)}) linkSelectionMenuItems.push(menuItem) linkSelectionMenu.insertItem(i, menuItem) @@ -77,17 +79,17 @@ Item { } Connections { - target: activeVehicle - onLinksChanged: priorityLinkSelector.updatelinkSelectionMenu() + target: _activeVehicle + onLinksChanged: priorityLinkSelector.updatelinkSelectionMenu() } Connections { - target: activeVehicle + target: _activeVehicle onLinksPropertiesChanged: priorityLinkSelector.updatelinkSelectionMenu() } MouseArea { - visible: activeVehicle + visible: _activeVehicle anchors.fill: parent onClicked: linkSelectionMenu.popup() } diff --git a/src/ui/toolbar/MainToolBar.qml b/src/ui/toolbar/MainToolBar.qml index 454665800879f4560ffb62f0db6218f1d6923b29..fcd0eca597326e8de71726557a98301bf8c364d8 100644 --- a/src/ui/toolbar/MainToolBar.qml +++ b/src/ui/toolbar/MainToolBar.qml @@ -126,22 +126,40 @@ Rectangle { property string _userBrandImageOutdoor: QGroundControl.settingsManager.brandImageSettings.userBrandImageOutdoor.value property bool _userBrandingIndoor: _userBrandImageIndoor.length != 0 property bool _userBrandingOutdoor: _userBrandImageOutdoor.length != 0 - property string _brandImageIndoor: _userBrandingIndoor ? - _userBrandImageIndoor : (_userBrandingOutdoor ? - _userBrandImageOutdoor : (_corePluginBranding ? - QGroundControl.corePlugin.brandImageIndoor : (activeVehicle ? - activeVehicle.brandImageIndoor : "" - ) - ) - ) - property string _brandImageOutdoor: _userBrandingOutdoor ? - _userBrandImageOutdoor : (_userBrandingIndoor ? - _userBrandImageIndoor : (_corePluginBranding ? - QGroundControl.corePlugin.brandImageOutdoor : (activeVehicle ? - activeVehicle.brandImageOutdoor : "" - ) - ) - ) + property string _brandImageIndoor: brandImageIndoor() + property string _brandImageOutdoor: brandImageOutdoor() + + function brandImageIndoor() { + if (_userBrandingIndoor) { + return _userBrandImageIndoor + } else { + if (_userBrandingOutdoor) { + return _userBrandingOutdoor + } else { + if (_corePluginBranding) { + return QGroundControl.corePlugin.brandImageIndoor + } else { + return _activeVehicle ? _activeVehicle.brandImageIndoor : "" + } + } + } + } + + function brandImageOutdoor() { + if (_userBrandingOutdoor) { + return _userBrandingOutdoor + } else { + if (_userBrandingIndoor) { + return _userBrandingIndoor + } else { + if (_corePluginBranding) { + return QGroundControl.corePlugin.brandImageOutdoor + } else { + return _activeVehicle ? _activeVehicle.brandImageOutdoor : "" + } + } + } + } } // Small parameter download progress bar diff --git a/src/ui/toolbar/MessageIndicator.qml b/src/ui/toolbar/MessageIndicator.qml index c6ea34ae3ab42b86ee99bb399ffb7ac18ab9c629..668506b2b66f9e4acf799aad197f1037789ca7c8 100644 --- a/src/ui/toolbar/MessageIndicator.qml +++ b/src/ui/toolbar/MessageIndicator.qml @@ -21,26 +21,28 @@ import QGroundControl.Palette 1.0 //------------------------------------------------------------------------- //-- Message Indicator Item { + id: _root width: height anchors.top: parent.top anchors.bottom: parent.bottom property bool showIndicator: true - property bool _isMessageImportant: activeVehicle ? !activeVehicle.messageTypeNormal && !activeVehicle.messageTypeNone : false + property var _activeVehicle: QGroundControl.multiVehicleManager.activeVehicle + property bool _isMessageImportant: _activeVehicle ? !_activeVehicle.messageTypeNormal && !_activeVehicle.messageTypeNone : false function getMessageColor() { - if (activeVehicle) { - if (activeVehicle.messageTypeNone) + if (_activeVehicle) { + if (_activeVehicle.messageTypeNone) return qgcPal.colorGrey - if (activeVehicle.messageTypeNormal) + if (_activeVehicle.messageTypeNormal) return qgcPal.colorBlue; - if (activeVehicle.messageTypeWarning) + if (_activeVehicle.messageTypeWarning) return qgcPal.colorOrange; - if (activeVehicle.messageTypeError) + if (_activeVehicle.messageTypeError) return qgcPal.colorRed; // Cannot be so make make it obnoxious to show error - console.log("Invalid vehicle message type") + console.warn("MessageIndicator.qml:getMessageColor Invalid vehicle message type", _activeVehicle.messageTypeNone) return "purple"; } //-- It can only get here when closing (vehicle gone while window active) @@ -54,7 +56,7 @@ Item { sourceSize.height: height fillMode: Image.PreserveAspectFit cache: false - visible: activeVehicle && activeVehicle.messageCount > 0 && _isMessageImportant + visible: _activeVehicle && _activeVehicle.messageCount > 0 && _isMessageImportant } QGCColoredImage { @@ -68,6 +70,89 @@ Item { MouseArea { anchors.fill: parent - onClicked: mainWindow.showVehicleMessages() + onClicked: mainWindow.showIndicatorPopup(_root, vehicleMessagesPopup) + } + + Component { + id: vehicleMessagesPopup + + Rectangle { + width: mainWindow.width * 0.666 + height: mainWindow.height * 0.666 + radius: ScreenTools.defaultFontPixelHeight / 2 + color: qgcPal.window + border.color: qgcPal.text + + function formatMessage(message) { + message = message.replace(new RegExp("<#E>", "g"), "color: " + qgcPal.warningText + "; font: " + (ScreenTools.defaultFontPointSize.toFixed(0) - 1) + "pt monospace;"); + message = message.replace(new RegExp("<#I>", "g"), "color: " + qgcPal.warningText + "; font: " + (ScreenTools.defaultFontPointSize.toFixed(0) - 1) + "pt monospace;"); + message = message.replace(new RegExp("<#N>", "g"), "color: " + qgcPal.text + "; font: " + (ScreenTools.defaultFontPointSize.toFixed(0) - 1) + "pt monospace;"); + return message; + } + + Component.onCompleted: { + messageText.text = formatMessage(_activeVehicle.formattedMessages) + //-- Hack to scroll to last message + for (var i = 0; i < _activeVehicle.messageCount; i++) + messageFlick.flick(0,-5000) + _activeVehicle.resetMessages() + } + + Connections { + target: _activeVehicle + onNewFormattedMessage :{ + messageText.append(formatMessage(formattedMessage)) + //-- Hack to scroll down + messageFlick.flick(0,-500) + } + } + + QGCLabel { + anchors.centerIn: parent + text: qsTr("No Messages") + visible: messageText.length === 0 + } + + //-- Clear Messages + QGCColoredImage { + anchors.bottom: parent.bottom + anchors.right: parent.right + anchors.margins: ScreenTools.defaultFontPixelHeight * 0.5 + height: ScreenTools.isMobile ? ScreenTools.defaultFontPixelHeight * 1.5 : ScreenTools.defaultFontPixelHeight + width: height + sourceSize.height: height + source: "/res/TrashDelete.svg" + fillMode: Image.PreserveAspectFit + mipmap: true + smooth: true + color: qgcPal.text + visible: messageText.length !== 0 + MouseArea { + anchors.fill: parent + onClicked: { + if (_activeVehicle) { + _activeVehicle.clearMessages() + mainWindow.hideIndicatorPopup() + } + } + } + } + + QGCFlickable { + id: messageFlick + anchors.margins: ScreenTools.defaultFontPixelHeight + anchors.fill: parent + contentHeight: messageText.height + contentWidth: messageText.width + pixelAligned: true + + TextEdit { + id: messageText + readOnly: true + textFormat: TextEdit.RichText + color: qgcPal.text + } + } + } } } diff --git a/src/ui/toolbar/RCRSSIIndicator.qml b/src/ui/toolbar/RCRSSIIndicator.qml index 695ee97d0f70c60a5ec391f2b746eadbc6d07c01..3d65d6206b8fbe832a5e96dbdfeba330afeaa539 100644 --- a/src/ui/toolbar/RCRSSIIndicator.qml +++ b/src/ui/toolbar/RCRSSIIndicator.qml @@ -27,7 +27,7 @@ Item { property bool showIndicator: _activeVehicle.supportsRadio property var _activeVehicle: QGroundControl.multiVehicleManager.activeVehicle - property bool _rcRSSIAvailable: activeVehicle ? activeVehicle.rcRSSI > 0 && activeVehicle.rcRSSI <= 100 : false + property bool _rcRSSIAvailable: _activeVehicle ? _activeVehicle.rcRSSI > 0 && _activeVehicle.rcRSSI <= 100 : false Component { id: rcRSSIInfo @@ -48,7 +48,7 @@ Item { QGCLabel { id: rssiLabel - text: activeVehicle ? (activeVehicle.rcRSSI !== 255 ? qsTr("RC RSSI Status") : qsTr("RC RSSI Data Unavailable")) : qsTr("N/A", "No data available") + text: _activeVehicle ? (_activeVehicle.rcRSSI !== 255 ? qsTr("RC RSSI Status") : qsTr("RC RSSI Data Unavailable")) : qsTr("N/A", "No data available") font.family: ScreenTools.demiboldFontFamily anchors.horizontalCenter: parent.horizontalCenter } @@ -62,7 +62,7 @@ Item { anchors.horizontalCenter: parent.horizontalCenter QGCLabel { text: qsTr("RSSI:") } - QGCLabel { text: activeVehicle ? (activeVehicle.rcRSSI + "%") : 0 } + QGCLabel { text: _activeVehicle ? (_activeVehicle.rcRSSI + "%") : 0 } } } } @@ -88,7 +88,7 @@ Item { SignalStrength { anchors.verticalCenter: parent.verticalCenter size: parent.height * 0.5 - percent: _rcRSSIAvailable ? activeVehicle.rcRSSI : 0 + percent: _rcRSSIAvailable ? _activeVehicle.rcRSSI : 0 } } diff --git a/src/ui/toolbar/ROIIndicator.qml b/src/ui/toolbar/ROIIndicator.qml index 3da3a8d41e4cb11293a9f8936a7a3b227e188666..a5d1b13f2bf071a9f2dd01b2edf81e2d322692b8 100644 --- a/src/ui/toolbar/ROIIndicator.qml +++ b/src/ui/toolbar/ROIIndicator.qml @@ -28,7 +28,9 @@ Item { anchors.top: parent.top anchors.bottom: parent.bottom - property bool showIndicator: activeVehicle && activeVehicle.roiModeSupported + property bool showIndicator: _activeVehicle && _activeVehicle.roiModeSupported + + property var _activeVehicle: QGroundControl.multiVehicleManager.activeVehicle Component { id: roiInfo @@ -56,11 +58,11 @@ Item { QGCButton { id: roiButton - visible: activeVehicle && activeVehicle.isROIEnabled + visible: _activeVehicle && _activeVehicle.isROIEnabled text: qsTr("Disable ROI") onClicked: { - if(activeVehicle) - activeVehicle.stopGuidedModeROI() + if(_activeVehicle) + _activeVehicle.stopGuidedModeROI() mainWindow.hideIndicatorPopup() } } @@ -75,9 +77,9 @@ Item { anchors.bottom: parent.bottom sourceSize.height: height source: "/qmlimages/roi.svg" - color: activeVehicle && activeVehicle.isROIEnabled ? qgcPal.colorGreen : qgcPal.text + color: _activeVehicle && _activeVehicle.isROIEnabled ? qgcPal.colorGreen : qgcPal.text fillMode: Image.PreserveAspectFit - opacity: activeVehicle && activeVehicle.isROIEnabled ? 1 : 0.5 + opacity: _activeVehicle && _activeVehicle.isROIEnabled ? 1 : 0.5 } MouseArea { diff --git a/src/ui/toolbar/TelemetryRSSIIndicator.qml b/src/ui/toolbar/TelemetryRSSIIndicator.qml index 9642041d205c96e6f8fd53ac933d1f5292614b0a..b51a392b2f2e714497fb006b34a6720749b38b78 100644 --- a/src/ui/toolbar/TelemetryRSSIIndicator.qml +++ b/src/ui/toolbar/TelemetryRSSIIndicator.qml @@ -56,19 +56,19 @@ Item { columns: 2 anchors.horizontalCenter: parent.horizontalCenter QGCLabel { text: qsTr("Local RSSI:") } - QGCLabel { text: activeVehicle.telemetryLRSSI + " dBm"} + QGCLabel { text: _activeVehicle.telemetryLRSSI + " dBm"} QGCLabel { text: qsTr("Remote RSSI:") } - QGCLabel { text: activeVehicle.telemetryRRSSI + " dBm"} + QGCLabel { text: _activeVehicle.telemetryRRSSI + " dBm"} QGCLabel { text: qsTr("RX Errors:") } - QGCLabel { text: activeVehicle.telemetryRXErrors } + QGCLabel { text: _activeVehicle.telemetryRXErrors } QGCLabel { text: qsTr("Errors Fixed:") } - QGCLabel { text: activeVehicle.telemetryFixed } + QGCLabel { text: _activeVehicle.telemetryFixed } QGCLabel { text: qsTr("TX Buffer:") } - QGCLabel { text: activeVehicle.telemetryTXBuffer } + QGCLabel { text: _activeVehicle.telemetryTXBuffer } QGCLabel { text: qsTr("Local Noise:") } - QGCLabel { text: activeVehicle.telemetryLNoise } + QGCLabel { text: _activeVehicle.telemetryLNoise } QGCLabel { text: qsTr("Remote Noise:") } - QGCLabel { text: activeVehicle.telemetryRNoise } + QGCLabel { text: _activeVehicle.telemetryRNoise } } } }