QGroundControl
Ground Control Station for MAVLink Drones
Loading...
Searching...
No Matches
FlyViewVideo.qml
Go to the documentation of this file.
1import QtQuick
2
3import QGroundControl
4import QGroundControl.Controls
5
6Item {
7 id: _root
8
9 property Item pipView
10 property Item pipState: videoPipState
11
12 property int _track_rec_x: 0
13 property int _track_rec_y: 0
14
15 PipState {
16 id: videoPipState
17 pipView: _root.pipView
18 isDark: true
19
20 onWindowAboutToOpen: {
21 QGroundControl.videoManager.stopVideo()
22 videoStartDelay.start()
23 }
24
25 onWindowAboutToClose: {
26 QGroundControl.videoManager.stopVideo()
27 videoStartDelay.start()
28 }
29
30 onStateChanged: {
31 if (pipState.state !== pipState.fullState) {
32 QGroundControl.videoManager.fullScreen = false
33 }
34 }
35 }
36
37 Timer {
38 id: videoStartDelay
39 interval: 2000;
40 running: false
41 repeat: false
42 onTriggered: QGroundControl.videoManager.startVideo()
43 }
44
45 //-- Video Streaming
46 FlightDisplayViewVideo {
47 id: videoStreaming
48 anchors.fill: parent
49 useSmallFont: _root.pipState.state !== _root.pipState.fullState
50 visible: QGroundControl.videoManager.isStreamSource
51 }
52 //-- UVC Video (USB Camera or Video Device)
53 Loader {
54 id: cameraLoader
55 anchors.fill: parent
56 visible: QGroundControl.videoManager.isUvc
57 source: QGroundControl.videoManager.uvcEnabled ? "qrc:/qml/QGroundControl/FlyView/FlightDisplayViewUVC.qml" : "qrc:/qml/QGroundControl/FlyView//FlightDisplayViewDummy.qml"
58 }
59
60 QGCLabel {
61 text: qsTr("Double-click to exit full screen")
62 font.pointSize: ScreenTools.largeFontPointSize
63 visible: QGroundControl.videoManager.fullScreen && flyViewVideoMouseArea.containsMouse
64 anchors.centerIn: parent
65
66 onVisibleChanged: {
67 if (visible) {
68 labelAnimation.start()
69 }
70 }
71
72 PropertyAnimation on opacity {
73 id: labelAnimation
74 duration: 10000
75 from: 1.0
76 to: 0.0
77 easing.type: Easing.InExpo
78 }
79 }
80
81 OnScreenGimbalController {
82 id: onScreenGimbalController
83 anchors.fill: parent
84 screenX: flyViewVideoMouseArea.mouseX
85 screenY: flyViewVideoMouseArea.mouseY
86 cameraTrackingEnabled: videoStreaming._camera && videoStreaming._camera.trackingEnabled
87 }
88
89 MouseArea {
90 id: flyViewVideoMouseArea
91 anchors.fill: parent
92 enabled: pipState.state === pipState.fullState
93 hoverEnabled: true
94
95 property double x0: 0
96 property double x1: 0
97 property double y0: 0
98 property double y1: 0
99 property double offset_x: 0
100 property double offset_y: 0
101 property double radius: 20
102 property var trackingROI: null
103 property var trackingStatus: trackingStatusComponent.createObject(flyViewVideoMouseArea, {})
104
105 onClicked: onScreenGimbalController.clickControl()
106 onDoubleClicked: QGroundControl.videoManager.fullScreen = !QGroundControl.videoManager.fullScreen
107
108 onPressed:(mouse) => {
109 onScreenGimbalController.pressControl()
110
111 _track_rec_x = mouse.x
112 _track_rec_y = mouse.y
113
114 //create a new rectangle at the wanted position
115 if(videoStreaming._camera) {
116 if (videoStreaming._camera.trackingEnabled) {
117 trackingROI = trackingROIComponent.createObject(flyViewVideoMouseArea, {
118 "x": mouse.x,
119 "y": mouse.y
120 });
121 }
122 }
123 }
124 onPositionChanged: (mouse) => {
125 //on move, update the width of rectangle
126 if (trackingROI !== null) {
127 if (mouse.x < trackingROI.x) {
128 trackingROI.x = mouse.x
129 trackingROI.width = Math.abs(mouse.x - _track_rec_x)
130 } else {
131 trackingROI.width = Math.abs(mouse.x - trackingROI.x)
132 }
133 if (mouse.y < trackingROI.y) {
134 trackingROI.y = mouse.y
135 trackingROI.height = Math.abs(mouse.y - _track_rec_y)
136 } else {
137 trackingROI.height = Math.abs(mouse.y - trackingROI.y)
138 }
139 }
140 }
141 onReleased: (mouse) => {
142 onScreenGimbalController.releaseControl()
143
144 //if there is already a selection, delete it
145 if (trackingROI !== null) {
146 trackingROI.destroy();
147 }
148
149 if(videoStreaming._camera) {
150 if (videoStreaming._camera.trackingEnabled) {
151 // order coordinates --> top/left and bottom/right
152 x0 = Math.min(_track_rec_x, mouse.x)
153 x1 = Math.max(_track_rec_x, mouse.x)
154 y0 = Math.min(_track_rec_y, mouse.y)
155 y1 = Math.max(_track_rec_y, mouse.y)
156
157 //calculate offset between video stream rect and background (black stripes)
158 offset_x = (parent.width - videoStreaming.getWidth()) / 2
159 offset_y = (parent.height - videoStreaming.getHeight()) / 2
160
161 //convert absolute coords in background to absolute video stream coords
162 x0 = x0 - offset_x
163 x1 = x1 - offset_x
164 y0 = y0 - offset_y
165 y1 = y1 - offset_y
166
167 //convert absolute to relative coordinates and limit range to 0...1
168 x0 = Math.max(Math.min(x0 / videoStreaming.getWidth(), 1.0), 0.0)
169 x1 = Math.max(Math.min(x1 / videoStreaming.getWidth(), 1.0), 0.0)
170 y0 = Math.max(Math.min(y0 / videoStreaming.getHeight(), 1.0), 0.0)
171 y1 = Math.max(Math.min(y1 / videoStreaming.getHeight(), 1.0), 0.0)
172
173 //use point message if rectangle is very small
174 if (Math.abs(_track_rec_x - mouse.x) < 10 && Math.abs(_track_rec_y - mouse.y) < 10) {
175 var pt = Qt.point(x0, y0)
176 videoStreaming._camera.startTracking(pt, radius / videoStreaming.getWidth())
177 } else {
178 var rec = Qt.rect(x0, y0, x1 - x0, y1 - y0)
179 videoStreaming._camera.startTracking(rec)
180 }
181 _track_rec_x = 0
182 _track_rec_y = 0
183 }
184 }
185 }
186
187 Component {
188 id: trackingROIComponent
189
190 Rectangle {
191 color: Qt.rgba(0.1,0.85,0.1,0.25)
192 border.color: "green"
193 border.width: 1
194 }
195 }
196
197 Component {
198 id: trackingStatusComponent
199
200 Rectangle {
201 color: "transparent"
202 border.color: "red"
203 border.width: 5
204 radius: 5
205 }
206 }
207
208 Timer {
209 id: trackingStatusTimer
210 interval: 50
211 repeat: true
212 running: true
213 onTriggered: {
214 if (videoStreaming._camera) {
215 if (videoStreaming._camera.trackingEnabled && videoStreaming._camera.trackingImageStatus) {
216 var margin_hor = (parent.parent.width - videoStreaming.getWidth()) / 2
217 var margin_ver = (parent.parent.height - videoStreaming.getHeight()) / 2
218 var left = margin_hor + videoStreaming.getWidth() * videoStreaming._camera.trackingImageRect.left
219 var top = margin_ver + videoStreaming.getHeight() * videoStreaming._camera.trackingImageRect.top
220 var right = margin_hor + videoStreaming.getWidth() * videoStreaming._camera.trackingImageRect.right
221 var bottom = margin_ver + !isNaN(videoStreaming._camera.trackingImageRect.bottom) ? videoStreaming.getHeight() * videoStreaming._camera.trackingImageRect.bottom : top + (right - left)
222 var width = right - left
223 var height = bottom - top
224
225 flyViewVideoMouseArea.trackingStatus.x = left
226 flyViewVideoMouseArea.trackingStatus.y = top
227 flyViewVideoMouseArea.trackingStatus.width = width
228 flyViewVideoMouseArea.trackingStatus.height = height
229 } else {
230 flyViewVideoMouseArea.trackingStatus.x = 0
231 flyViewVideoMouseArea.trackingStatus.y = 0
232 flyViewVideoMouseArea.trackingStatus.width = 0
233 flyViewVideoMouseArea.trackingStatus.height = 0
234 }
235 }
236 }
237 }
238 }
239
240 ProximityRadarVideoView{
241 anchors.fill: parent
242 vehicle: QGroundControl.multiVehicleManager.activeVehicle
243 }
244
245 ObstacleDistanceOverlayVideo {
246 id: obstacleDistance
247 showText: pipState.state === pipState.fullState
248 }
249}