4import QGroundControl.Controls
10 property Item pipState: videoPipState
12 property int _track_rec_x: 0
13 property int _track_rec_y: 0
17 pipView: _root.pipView
20 onWindowAboutToOpen: {
21 QGroundControl.videoManager.stopVideo()
22 videoStartDelay.start()
25 onWindowAboutToClose: {
26 QGroundControl.videoManager.stopVideo()
27 videoStartDelay.start()
31 if (pipState.state !== pipState.fullState) {
32 QGroundControl.videoManager.fullScreen = false
42 onTriggered: QGroundControl.videoManager.startVideo()
46 FlightDisplayViewVideo {
49 useSmallFont: _root.pipState.state !== _root.pipState.fullState
50 visible: QGroundControl.videoManager.isStreamSource
52 //-- UVC Video (USB Camera or Video Device)
56 visible: QGroundControl.videoManager.isUvc
57 source: QGroundControl.videoManager.uvcEnabled ? "qrc:/qml/QGroundControl/FlyView/FlightDisplayViewUVC.qml" : "qrc:/qml/QGroundControl/FlyView//FlightDisplayViewDummy.qml"
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
68 labelAnimation.start()
72 PropertyAnimation on opacity {
77 easing.type: Easing.InExpo
81 OnScreenGimbalController {
82 id: onScreenGimbalController
84 screenX: flyViewVideoMouseArea.mouseX
85 screenY: flyViewVideoMouseArea.mouseY
86 cameraTrackingEnabled: videoStreaming._camera && videoStreaming._camera.trackingEnabled
90 id: flyViewVideoMouseArea
92 enabled: pipState.state === pipState.fullState
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, {})
105 onClicked: onScreenGimbalController.clickControl()
106 onDoubleClicked: QGroundControl.videoManager.fullScreen = !QGroundControl.videoManager.fullScreen
108 onPressed:(mouse) => {
109 onScreenGimbalController.pressControl()
111 _track_rec_x = mouse.x
112 _track_rec_y = mouse.y
114 //create a new rectangle at the wanted position
115 if(videoStreaming._camera) {
116 if (videoStreaming._camera.trackingEnabled) {
117 trackingROI = trackingROIComponent.createObject(flyViewVideoMouseArea, {
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)
131 trackingROI.width = Math.abs(mouse.x - trackingROI.x)
133 if (mouse.y < trackingROI.y) {
134 trackingROI.y = mouse.y
135 trackingROI.height = Math.abs(mouse.y - _track_rec_y)
137 trackingROI.height = Math.abs(mouse.y - trackingROI.y)
141 onReleased: (mouse) => {
142 onScreenGimbalController.releaseControl()
144 //if there is already a selection, delete it
145 if (trackingROI !== null) {
146 trackingROI.destroy();
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)
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
161 //convert absolute coords in background to absolute video stream coords
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)
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())
178 var rec = Qt.rect(x0, y0, x1 - x0, y1 - y0)
179 videoStreaming._camera.startTracking(rec)
188 id: trackingROIComponent
191 color: Qt.rgba(0.1,0.85,0.1,0.25)
192 border.color: "green"
198 id: trackingStatusComponent
209 id: trackingStatusTimer
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
225 flyViewVideoMouseArea.trackingStatus.x = left
226 flyViewVideoMouseArea.trackingStatus.y = top
227 flyViewVideoMouseArea.trackingStatus.width = width
228 flyViewVideoMouseArea.trackingStatus.height = height
230 flyViewVideoMouseArea.trackingStatus.x = 0
231 flyViewVideoMouseArea.trackingStatus.y = 0
232 flyViewVideoMouseArea.trackingStatus.width = 0
233 flyViewVideoMouseArea.trackingStatus.height = 0
240 ProximityRadarVideoView{
242 vehicle: QGroundControl.multiVehicleManager.activeVehicle
245 ObstacleDistanceOverlayVideo {
247 showText: pipState.state === pipState.fullState