Skip to content
Projects
Groups
Snippets
Help
Loading...
Help
Support
Submit feedback
Contribute to GitLab
Sign in
Toggle navigation
Q
qgroundcontrol
Project
Project
Details
Activity
Releases
Cycle Analytics
Repository
Repository
Files
Commits
Branches
Tags
Contributors
Graph
Compare
Charts
Issues
0
Issues
0
List
Boards
Labels
Milestones
Merge Requests
0
Merge Requests
0
CI / CD
CI / CD
Pipelines
Jobs
Schedules
Charts
Wiki
Wiki
Snippets
Snippets
Members
Members
Collapse sidebar
Close sidebar
Activity
Graph
Charts
Create a new issue
Jobs
Commits
Issue Boards
Open sidebar
Valentin Platzgummer
qgroundcontrol
Commits
0e7f614d
Commit
0e7f614d
authored
May 02, 2019
by
Gus Grubba
Browse files
Options
Browse Files
Download
Email Patches
Plain Diff
Initial secondary (thermal) video support
parent
11cc6ae2
Changes
12
Hide whitespace changes
Inline
Side-by-side
Showing
12 changed files
with
327 additions
and
38 deletions
+327
-38
QGCCameraControl.cc
src/Camera/QGCCameraControl.cc
+76
-9
QGCCameraControl.h
src/Camera/QGCCameraControl.h
+24
-1
QGCCameraManager.cc
src/Camera/QGCCameraManager.cc
+12
-0
QGCCameraManager.h
src/Camera/QGCCameraManager.h
+2
-0
FlightDisplayView.qml
src/FlightDisplay/FlightDisplayView.qml
+4
-5
FlightDisplayViewVideo.qml
src/FlightDisplay/FlightDisplayViewVideo.qml
+45
-0
VideoManager.cc
src/FlightDisplay/VideoManager.cc
+97
-7
VideoManager.h
src/FlightDisplay/VideoManager.h
+19
-8
QGCVideoBackground.qml
src/FlightMap/QGCVideoBackground.qml
+3
-3
CameraPageWidget.qml
src/FlightMap/Widgets/CameraPageWidget.qml
+44
-3
VideoReceiver.cc
src/VideoStreaming/VideoReceiver.cc
+1
-1
VideoReceiver.h
src/VideoStreaming/VideoReceiver.h
+0
-1
No files found.
src/Camera/QGCCameraControl.cc
View file @
0e7f614d
...
...
@@ -58,6 +58,8 @@ static const char* kVersion = "version";
static
const
char
*
kPhotoMode
=
"PhotoMode"
;
static
const
char
*
kPhotoLapse
=
"PhotoLapse"
;
static
const
char
*
kPhotoLapseCount
=
"PhotoLapseCount"
;
static
const
char
*
kThermalOpacity
=
"ThermalOpacity"
;
static
const
char
*
kThermalMode
=
"ThermalMode"
;
//-----------------------------------------------------------------------------
// Known Parameters
...
...
@@ -174,9 +176,11 @@ QGCCameraControl::QGCCameraControl(const mavlink_camera_information_t *info, Veh
_initWhenReady
();
}
QSettings
settings
;
_photoMode
=
static_cast
<
PhotoMode
>
(
settings
.
value
(
kPhotoMode
,
static_cast
<
int
>
(
PHOTO_CAPTURE_SINGLE
)).
toInt
());
_photoLapse
=
settings
.
value
(
kPhotoLapse
,
1.0
).
toDouble
();
_photoMode
=
static_cast
<
PhotoMode
>
(
settings
.
value
(
kPhotoMode
,
static_cast
<
int
>
(
PHOTO_CAPTURE_SINGLE
)).
toInt
());
_photoLapse
=
settings
.
value
(
kPhotoLapse
,
1.0
).
toDouble
();
_photoLapseCount
=
settings
.
value
(
kPhotoLapseCount
,
0
).
toInt
();
_thermalOpacity
=
settings
.
value
(
kThermalOpacity
,
85.0
).
toDouble
();
_thermalMode
=
static_cast
<
ThermalViewMode
>
(
settings
.
value
(
kThermalMode
,
static_cast
<
uint32_t
>
(
THERMAL_BLEND
)).
toUInt
());
_recTimer
.
setSingleShot
(
false
);
_recTimer
.
setInterval
(
333
);
connect
(
&
_recTimer
,
&
QTimer
::
timeout
,
this
,
&
QGCCameraControl
::
_recTimerHandler
);
...
...
@@ -498,6 +502,30 @@ QGCCameraControl::setPhotoMode()
}
}
//-----------------------------------------------------------------------------
void
QGCCameraControl
::
setThermalMode
(
ThermalViewMode
mode
)
{
QSettings
settings
;
settings
.
setValue
(
kThermalMode
,
static_cast
<
uint32_t
>
(
mode
));
_thermalMode
=
mode
;
emit
thermalModeChanged
();
}
//-----------------------------------------------------------------------------
void
QGCCameraControl
::
setThermalOpacity
(
double
val
)
{
if
(
val
<
0.0
)
val
=
0.0
;
if
(
val
>
100.0
)
val
=
100.0
;
if
(
fabs
(
_thermalOpacity
-
val
)
>
0.1
)
{
_thermalOpacity
=
val
;
QSettings
settings
;
settings
.
setValue
(
kThermalOpacity
,
val
);
emit
thermalOpacityChanged
();
}
}
//-----------------------------------------------------------------------------
void
QGCCameraControl
::
setZoomLevel
(
qreal
level
)
...
...
@@ -1496,10 +1524,14 @@ QGCCameraControl::handleVideoInfo(const mavlink_video_stream_information_t* vi)
QGCVideoStreamInfo
*
pStream
=
new
QGCVideoStreamInfo
(
this
,
vi
);
QQmlEngine
::
setObjectOwnership
(
pStream
,
QQmlEngine
::
CppOwnership
);
_streams
.
append
(
pStream
);
_streamLabels
.
append
(
pStream
->
name
());
emit
streamsChanged
();
emit
streamLabelsChanged
();
qDebug
()
<<
_streamLabels
;
//-- Thermal is handled separately and not listed
if
(
!
pStream
->
isThermal
())
{
_streamLabels
.
append
(
pStream
->
name
());
emit
streamsChanged
();
emit
streamLabelsChanged
();
}
else
{
emit
thermalStreamChanged
();
}
}
//-- Check for missing count
if
(
_streams
.
count
()
<
_expectedCount
)
{
...
...
@@ -1531,7 +1563,7 @@ QGCCameraControl::handleVideoStatus(const mavlink_video_stream_status_t* vs)
void
QGCCameraControl
::
setCurrentStream
(
int
stream
)
{
if
(
stream
!=
_currentStream
&&
stream
>=
0
&&
stream
<
_streams
.
count
())
{
if
(
stream
!=
_currentStream
&&
stream
>=
0
&&
stream
<
_stream
Label
s
.
count
())
{
if
(
_currentStream
!=
stream
)
{
QGCVideoStreamInfo
*
pInfo
=
currentStreamInstance
();
if
(
pInfo
)
{
...
...
@@ -1606,13 +1638,31 @@ QGCCameraControl::autoStream()
QGCVideoStreamInfo
*
QGCCameraControl
::
currentStreamInstance
()
{
if
(
_currentStream
<
_stream
s
.
count
()
&&
_stream
s
.
count
())
{
QGCVideoStreamInfo
*
pStream
=
qobject_cast
<
QGCVideoStreamInfo
*>
(
_stream
s
[
_currentStream
]);
if
(
_currentStream
<
_stream
Labels
.
count
()
&&
_streamLabel
s
.
count
())
{
QGCVideoStreamInfo
*
pStream
=
_findStream
(
_streamLabel
s
[
_currentStream
]);
return
pStream
;
}
return
nullptr
;
}
//-----------------------------------------------------------------------------
QGCVideoStreamInfo
*
QGCCameraControl
::
thermalStreamInstance
()
{
//-- For now, it will return the first thermal listed (if any)
for
(
int
i
=
0
;
i
<
_streams
.
count
();
i
++
)
{
if
(
_streams
[
i
])
{
QGCVideoStreamInfo
*
pStream
=
qobject_cast
<
QGCVideoStreamInfo
*>
(
_streams
[
i
]);
if
(
pStream
)
{
if
(
pStream
->
isThermal
())
{
return
pStream
;
}
}
}
}
return
nullptr
;
}
//-----------------------------------------------------------------------------
void
QGCCameraControl
::
_requestStreamInfo
(
uint8_t
streamID
)
...
...
@@ -1660,6 +1710,23 @@ QGCCameraControl::_findStream(uint8_t id, bool report)
return
nullptr
;
}
//-----------------------------------------------------------------------------
QGCVideoStreamInfo
*
QGCCameraControl
::
_findStream
(
const
QString
name
)
{
for
(
int
i
=
0
;
i
<
_streams
.
count
();
i
++
)
{
if
(
_streams
[
i
])
{
QGCVideoStreamInfo
*
pStream
=
qobject_cast
<
QGCVideoStreamInfo
*>
(
_streams
[
i
]);
if
(
pStream
)
{
if
(
pStream
->
name
()
==
name
)
{
return
pStream
;
}
}
}
}
return
nullptr
;
}
//-----------------------------------------------------------------------------
void
QGCCameraControl
::
_streamTimeout
()
...
...
src/Camera/QGCCameraControl.h
View file @
0e7f614d
...
...
@@ -114,10 +114,18 @@ public:
PHOTO_CAPTURE_TIMELAPSE
,
};
enum
ThermalViewMode
{
THERMAL_OFF
=
0
,
THERMAL_BLEND
,
THERMAL_FULL
,
THERMAL_PIP
,
};
Q_ENUM
(
CameraMode
)
Q_ENUM
(
VideoStatus
)
Q_ENUM
(
PhotoStatus
)
Q_ENUM
(
PhotoMode
)
Q_ENUM
(
ThermalViewMode
)
Q_PROPERTY
(
int
version
READ
version
NOTIFY
infoChanged
)
Q_PROPERTY
(
QString
modelName
READ
modelName
NOTIFY
infoChanged
)
...
...
@@ -162,9 +170,12 @@ public:
Q_PROPERTY
(
bool
autoStream
READ
autoStream
NOTIFY
autoStreamChanged
)
Q_PROPERTY
(
QmlObjectListModel
*
streams
READ
streams
NOTIFY
streamsChanged
)
Q_PROPERTY
(
QGCVideoStreamInfo
*
currentStreamInstance
READ
currentStreamInstance
NOTIFY
currentStreamChanged
)
Q_PROPERTY
(
QGCVideoStreamInfo
*
thermalStreamInstance
READ
thermalStreamInstance
NOTIFY
thermalStreamChanged
)
Q_PROPERTY
(
quint32
recordTime
READ
recordTime
NOTIFY
recordTimeChanged
)
Q_PROPERTY
(
QString
recordTimeStr
READ
recordTimeStr
NOTIFY
recordTimeChanged
)
Q_PROPERTY
(
QStringList
streamLabels
READ
streamLabels
NOTIFY
streamLabelsChanged
)
Q_PROPERTY
(
ThermalViewMode
thermalMode
READ
thermalMode
WRITE
setThermalMode
NOTIFY
thermalModeChanged
)
Q_PROPERTY
(
double
thermalOpacity
READ
thermalOpacity
WRITE
setThermalOpacity
NOTIFY
thermalOpacityChanged
)
Q_INVOKABLE
virtual
void
setVideoMode
();
Q_INVOKABLE
virtual
void
setPhotoMode
();
...
...
@@ -216,6 +227,7 @@ public:
virtual
QmlObjectListModel
*
streams
()
{
return
&
_streams
;
}
virtual
QGCVideoStreamInfo
*
currentStreamInstance
();
virtual
QGCVideoStreamInfo
*
thermalStreamInstance
();
virtual
int
currentStream
()
{
return
_currentStream
;
}
virtual
void
setCurrentStream
(
int
stream
);
virtual
bool
autoStream
();
...
...
@@ -231,7 +243,12 @@ public:
virtual
Fact
*
mode
();
//-- Stream names to show the user (for selection)
virtual
QStringList
streamLabels
()
{
return
_streamLabels
;
}
virtual
QStringList
streamLabels
()
{
return
_streamLabels
;
}
virtual
ThermalViewMode
thermalMode
()
{
return
_thermalMode
;
}
virtual
void
setThermalMode
(
ThermalViewMode
mode
);
virtual
double
thermalOpacity
()
{
return
_thermalOpacity
;
}
virtual
void
setThermalOpacity
(
double
val
);
virtual
void
setZoomLevel
(
qreal
level
);
virtual
void
setFocusLevel
(
qreal
level
);
...
...
@@ -282,9 +299,12 @@ signals:
void
focusLevelChanged
();
void
streamsChanged
();
void
currentStreamChanged
();
void
thermalStreamChanged
();
void
autoStreamChanged
();
void
recordTimeChanged
();
void
streamLabelsChanged
();
void
thermalModeChanged
();
void
thermalOpacityChanged
();
protected:
virtual
void
_setVideoStatus
(
VideoStatus
status
);
...
...
@@ -293,6 +313,7 @@ protected:
virtual
void
_requestStreamInfo
(
uint8_t
streamID
);
virtual
void
_requestStreamStatus
(
uint8_t
streamID
);
virtual
QGCVideoStreamInfo
*
_findStream
(
uint8_t
streamID
,
bool
report
=
true
);
virtual
QGCVideoStreamInfo
*
_findStream
(
const
QString
name
);
protected
slots
:
virtual
void
_initWhenReady
();
...
...
@@ -376,4 +397,6 @@ protected:
QTimer
_streamStatusTimer
;
QmlObjectListModel
_streams
;
QStringList
_streamLabels
;
ThermalViewMode
_thermalMode
=
THERMAL_BLEND
;
double
_thermalOpacity
=
85
.
0
;
};
src/Camera/QGCCameraManager.cc
View file @
0e7f614d
...
...
@@ -171,6 +171,18 @@ QGCCameraManager::currentStreamInstance()
return
nullptr
;
}
//-----------------------------------------------------------------------------
QGCVideoStreamInfo
*
QGCCameraManager
::
thermalStreamInstance
()
{
QGCCameraControl
*
pCamera
=
currentCameraInstance
();
if
(
pCamera
)
{
QGCVideoStreamInfo
*
pInfo
=
pCamera
->
thermalStreamInstance
();
return
pInfo
;
}
return
nullptr
;
}
//-----------------------------------------------------------------------------
QGCCameraControl
*
QGCCameraManager
::
_findCamera
(
int
id
)
...
...
src/Camera/QGCCameraManager.h
View file @
0e7f614d
...
...
@@ -43,6 +43,8 @@ public:
virtual
void
setCurrentCamera
(
int
sel
);
//-- Current stream
virtual
QGCVideoStreamInfo
*
currentStreamInstance
();
//-- Current thermal stream
virtual
QGCVideoStreamInfo
*
thermalStreamInstance
();
signals:
void
camerasChanged
();
...
...
src/FlightDisplay/FlightDisplayView.qml
View file @
0e7f614d
...
...
@@ -7,14 +7,13 @@
*
****************************************************************************/
import
QtQuick
2.11
import
QtQuick
.
Controls
2.4
import
QtQuick
.
Dialogs
1.3
import
QtQuick
.
Layouts
1.11
import
QtQuick
2.3
import
QtQuick
.
Controls
1.2
import
QtQuick
.
Controls
.
Styles
1.4
import
QtQuick
.
Dialogs
1.2
import
QtLocation
5.3
import
QtPositioning
5.3
import
QtQuick
.
Layouts
1.2
import
QtQuick
.
Window
2.2
import
QtQml
.
Models
2.1
...
...
src/FlightDisplay/FlightDisplayViewVideo.qml
View file @
0e7f614d
...
...
@@ -33,6 +33,9 @@ Item {
property
var
_camera
:
_isCamera
?
_dynamicCameras
.
cameras
.
get
(
_curCameraIndex
)
:
null
property
bool
_hasZoom
:
_camera
&&
_camera
.
hasZoom
property
int
_fitMode
:
QGroundControl
.
settingsManager
.
videoSettings
.
videoFit
.
rawValue
property
double
_thermalHeightFactor
:
0.666
//-- TODO
Rectangle
{
id
:
noVideo
anchors.fill
:
parent
...
...
@@ -72,6 +75,7 @@ Item {
//-- Fit Width
return
_ar
!=
0.0
?
parent
.
width
*
(
1
/
_ar
)
:
parent
.
height
}
//-- Main Video
QGCVideoBackground
{
id
:
videoContent
height
:
parent
.
getHeight
()
...
...
@@ -119,12 +123,53 @@ Item {
visible
:
_showGrid
&&
!
QGroundControl
.
videoManager
.
fullScreen
}
}
//-- Thermal Image
Item
{
id
:
thermalItem
width
:
height
*
QGroundControl
.
videoManager
.
thermalAspectRatio
height
:
_camera
?
(
_camera
.
thermalMode
===
QGCCameraControl
.
THERMAL_PIP
?
ScreenTools
.
defaultFontPixelHeight
*
12
:
parent
.
height
*
_thermalHeightFactor
)
:
0
anchors.centerIn
:
parent
visible
:
QGroundControl
.
videoManager
.
hasThermal
&&
_camera
.
thermalMode
!==
QGCCameraControl
.
THERMAL_OFF
function
pipOrNot
()
{
if
(
_camera
)
{
if
(
_camera
.
thermalMode
===
QGCCameraControl
.
THERMAL_PIP
)
{
anchors
.
centerIn
=
undefined
anchors
.
top
=
parent
.
top
anchors
.
topMargin
=
mainWindow
.
header
.
height
+
(
ScreenTools
.
defaultFontPixelHeight
*
0.5
)
anchors
.
left
=
parent
.
left
anchors
.
leftMargin
=
ScreenTools
.
defaultFontPixelWidth
*
12
}
else
{
anchors
.
top
=
undefined
anchors
.
topMargin
=
undefined
anchors
.
left
=
undefined
anchors
.
leftMargin
=
undefined
anchors
.
centerIn
=
parent
}
}
}
Connections
{
target
:
_camera
onThermalModeChanged
:
thermalItem
.
pipOrNot
()
}
onVisibleChanged
:
{
thermalItem
.
pipOrNot
()
}
QGCVideoBackground
{
id
:
thermalVideo
anchors.fill
:
parent
receiver
:
QGroundControl
.
videoManager
.
thermalVideoReceiver
display
:
QGroundControl
.
videoManager
.
thermalVideoReceiver
?
QGroundControl
.
videoManager
.
thermalVideoReceiver
.
videoSurface
:
null
opacity
:
_camera
?
(
_camera
.
thermalMode
===
QGCCameraControl
.
THERMAL_BLEND
?
_camera
.
thermalOpacity
/
100
:
1.0
)
:
0
}
}
//-- Full screen toggle
MouseArea
{
anchors.fill
:
parent
onDoubleClicked
:
{
QGroundControl
.
videoManager
.
fullScreen
=
!
QGroundControl
.
videoManager
.
fullScreen
}
}
//-- Zoom
PinchArea
{
id
:
pinchZoom
enabled
:
_hasZoom
...
...
src/FlightDisplay/VideoManager.cc
View file @
0e7f614d
...
...
@@ -44,6 +44,9 @@ VideoManager::~VideoManager()
if
(
_videoReceiver
)
{
delete
_videoReceiver
;
}
if
(
_thermalVideoReceiver
)
{
delete
_thermalVideoReceiver
;
}
}
//-----------------------------------------------------------------------------
...
...
@@ -74,21 +77,76 @@ VideoManager::setToolbox(QGCToolbox *toolbox)
emit
isGStreamerChanged
();
qCDebug
(
VideoManagerLog
)
<<
"New Video Source:"
<<
videoSource
;
_videoReceiver
=
toolbox
->
corePlugin
()
->
createVideoReceiver
(
this
);
_thermalVideoReceiver
=
toolbox
->
corePlugin
()
->
createVideoReceiver
(
this
);
_updateSettings
();
if
(
isGStreamer
())
{
_videoReceiver
->
start
();
startVideo
();
}
else
{
_videoReceiver
->
stop
();
stopVideo
();
}
#endif
}
//-----------------------------------------------------------------------------
void
VideoManager
::
startVideo
()
{
if
(
_videoReceiver
)
_videoReceiver
->
start
();
if
(
_thermalVideoReceiver
)
_thermalVideoReceiver
->
start
();
}
//-----------------------------------------------------------------------------
void
VideoManager
::
stopVideo
()
{
if
(
_videoReceiver
)
_videoReceiver
->
stop
();
if
(
_thermalVideoReceiver
)
_thermalVideoReceiver
->
stop
();
}
//-----------------------------------------------------------------------------
double
VideoManager
::
aspectRatio
()
{
if
(
_activeVehicle
&&
_activeVehicle
->
dynamicCameras
())
{
QGCVideoStreamInfo
*
pInfo
=
_activeVehicle
->
dynamicCameras
()
->
currentStreamInstance
();
if
(
pInfo
)
{
qCDebug
(
VideoManagerLog
)
<<
"Primary AR: "
<<
pInfo
->
aspectRatio
();
return
pInfo
->
aspectRatio
();
}
}
return
_videoSettings
->
aspectRatio
()
->
rawValue
().
toDouble
();
}
//-----------------------------------------------------------------------------
double
VideoManager
::
thermalAspectRatio
()
{
if
(
_activeVehicle
&&
_activeVehicle
->
dynamicCameras
())
{
QGCVideoStreamInfo
*
pInfo
=
_activeVehicle
->
dynamicCameras
()
->
thermalStreamInstance
();
if
(
pInfo
)
{
qCDebug
(
VideoManagerLog
)
<<
"Thermal AR: "
<<
pInfo
->
aspectRatio
();
return
pInfo
->
aspectRatio
();
}
}
return
1.0
;
}
//-----------------------------------------------------------------------------
double
VideoManager
::
hfov
()
{
if
(
_activeVehicle
&&
_activeVehicle
->
dynamicCameras
())
{
QGCVideoStreamInfo
*
pInfo
=
_activeVehicle
->
dynamicCameras
()
->
currentStreamInstance
();
if
(
pInfo
)
{
return
pInfo
->
hfov
();
}
}
return
1.0
;
}
//-----------------------------------------------------------------------------
double
VideoManager
::
thermalHfov
()
{
if
(
_activeVehicle
&&
_activeVehicle
->
dynamicCameras
())
{
QGCVideoStreamInfo
*
pInfo
=
_activeVehicle
->
dynamicCameras
()
->
thermalStreamInstance
();
if
(
pInfo
)
{
return
pInfo
->
aspectRatio
();
}
...
...
@@ -96,6 +154,19 @@ double VideoManager::aspectRatio()
return
_videoSettings
->
aspectRatio
()
->
rawValue
().
toDouble
();
}
//-----------------------------------------------------------------------------
bool
VideoManager
::
hasThermal
()
{
if
(
_activeVehicle
&&
_activeVehicle
->
dynamicCameras
())
{
QGCVideoStreamInfo
*
pInfo
=
_activeVehicle
->
dynamicCameras
()
->
thermalStreamInstance
();
if
(
pInfo
)
{
return
true
;
}
}
return
false
;
}
//-----------------------------------------------------------------------------
bool
VideoManager
::
autoStreamConfigured
()
...
...
@@ -204,8 +275,9 @@ VideoManager::_updateSettings()
return
;
//-- Auto discovery
if
(
_activeVehicle
&&
_activeVehicle
->
dynamicCameras
())
{
QGCVideoStreamInfo
*
pInfo
=
_activeVehicle
->
dynamicCameras
()
->
currentStreamInstance
();
QGCVideoStreamInfo
*
pInfo
=
_activeVehicle
->
dynamicCameras
()
->
currentStreamInstance
();
if
(
pInfo
)
{
qCDebug
(
VideoManagerLog
)
<<
"Configure primary stream: "
<<
pInfo
->
uri
();
switch
(
pInfo
->
type
())
{
case
VIDEO_STREAM_TYPE_RTSP
:
case
VIDEO_STREAM_TYPE_TCP_MPEG
:
...
...
@@ -221,6 +293,26 @@ VideoManager::_updateSettings()
_videoReceiver
->
setUri
(
pInfo
->
uri
());
break
;
}
//-- Thermal stream (if any)
QGCVideoStreamInfo
*
pTinfo
=
_activeVehicle
->
dynamicCameras
()
->
thermalStreamInstance
();
if
(
pTinfo
)
{
qCDebug
(
VideoManagerLog
)
<<
"Configure secondary stream: "
<<
pTinfo
->
uri
();
switch
(
pTinfo
->
type
())
{
case
VIDEO_STREAM_TYPE_RTSP
:
case
VIDEO_STREAM_TYPE_TCP_MPEG
:
_thermalVideoReceiver
->
setUri
(
pTinfo
->
uri
());
break
;
case
VIDEO_STREAM_TYPE_RTPUDP
:
_thermalVideoReceiver
->
setUri
(
QStringLiteral
(
"udp://0.0.0.0:%1"
).
arg
(
pTinfo
->
uri
()));
break
;
case
VIDEO_STREAM_TYPE_MPEG_TS_H264
:
_thermalVideoReceiver
->
setUri
(
QStringLiteral
(
"mpegts://0.0.0.0:%1"
).
arg
(
pTinfo
->
uri
()));
break
;
default:
_thermalVideoReceiver
->
setUri
(
pTinfo
->
uri
());
break
;
}
}
return
;
}
}
...
...
@@ -241,11 +333,9 @@ VideoManager::_restartVideo()
{
#if defined(QGC_GST_STREAMING)
qCDebug
(
VideoManagerLog
)
<<
"Restart video streaming"
;
if
(
!
_videoReceiver
)
return
;
_videoReceiver
->
stop
();
stopVideo
();
_updateSettings
();
_videoReceiver
->
start
();
startVideo
();
emit
aspectRatioChanged
();
#endif
}
...
...
src/FlightDisplay/VideoManager.h
View file @
0e7f614d
...
...
@@ -42,8 +42,13 @@ public:
Q_PROPERTY
(
bool
uvcEnabled
READ
uvcEnabled
CONSTANT
)
Q_PROPERTY
(
bool
fullScreen
READ
fullScreen
WRITE
setfullScreen
NOTIFY
fullScreenChanged
)
Q_PROPERTY
(
VideoReceiver
*
videoReceiver
READ
videoReceiver
CONSTANT
)
Q_PROPERTY
(
VideoReceiver
*
thermalVideoReceiver
READ
thermalVideoReceiver
CONSTANT
)
Q_PROPERTY
(
double
aspectRatio
READ
aspectRatio
NOTIFY
aspectRatioChanged
)
Q_PROPERTY
(
double
thermalAspectRatio
READ
thermalAspectRatio
NOTIFY
aspectRatioChanged
)
Q_PROPERTY
(
double
hfov
READ
hfov
NOTIFY
aspectRatioChanged
)
Q_PROPERTY
(
double
thermalHfov
READ
thermalHfov
NOTIFY
aspectRatioChanged
)
Q_PROPERTY
(
bool
autoStreamConfigured
READ
autoStreamConfigured
NOTIFY
autoStreamConfiguredChanged
)
Q_PROPERTY
(
bool
hasThermal
READ
hasThermal
NOTIFY
aspectRatioChanged
)
bool
hasVideo
();
bool
isGStreamer
();
...
...
@@ -52,9 +57,14 @@ public:
bool
fullScreen
()
{
return
_fullScreen
;
}
QString
videoSourceID
()
{
return
_videoSourceID
;
}
double
aspectRatio
();
double
thermalAspectRatio
();
double
hfov
();
double
thermalHfov
();
bool
autoStreamConfigured
();
bool
hasThermal
();
VideoReceiver
*
videoReceiver
()
{
return
_videoReceiver
;
}
VideoReceiver
*
videoReceiver
()
{
return
_videoReceiver
;
}
VideoReceiver
*
thermalVideoReceiver
()
{
return
_thermalVideoReceiver
;
}
#if defined(QGC_DISABLE_UVC)
bool
uvcEnabled
()
{
return
false
;
}
...
...
@@ -68,8 +78,8 @@ public:
// Override from QGCTool
void
setToolbox
(
QGCToolbox
*
toolbox
);
Q_INVOKABLE
void
startVideo
()
{
_videoReceiver
->
start
();
}
Q_INVOKABLE
void
stopVideo
()
{
_videoReceiver
->
stop
();
}
Q_INVOKABLE
void
startVideo
()
;
Q_INVOKABLE
void
stopVideo
()
;
signals:
void
hasVideoChanged
();
...
...
@@ -95,12 +105,13 @@ private:
void
_updateSettings
();
private:
bool
_isTaisync
=
false
;
VideoReceiver
*
_videoReceiver
=
nullptr
;
VideoSettings
*
_videoSettings
=
nullptr
;
bool
_isTaisync
=
false
;
VideoReceiver
*
_videoReceiver
=
nullptr
;
VideoReceiver
*
_thermalVideoReceiver
=
nullptr
;
VideoSettings
*
_videoSettings
=
nullptr
;
QString
_videoSourceID
;
bool
_fullScreen
=
false
;
Vehicle
*
_activeVehicle
=
nullptr
;
bool
_fullScreen
=
false
;
Vehicle
*
_activeVehicle
=
nullptr
;
};
#endif
src/FlightMap/QGCVideoBackground.qml
View file @
0e7f614d
...
...
@@ -14,9 +14,9 @@
* @author Gus Grubba <mavlink@grubba.com>
*/
import
QtQuick
2.3
import
QtQuick
.
Controls
1.2
import
QGroundControl
.
QgcQtGStreamer
1.0
import
QtQuick
2.11
import
QtQuick
.
Controls
2.4
import
QGroundControl
.
QgcQtGStreamer
1.0
VideoItem
{
id
:
videoBackground
...
...
src/FlightMap/Widgets/CameraPageWidget.qml
View file @
0e7f614d
...
...
@@ -205,8 +205,8 @@ Column {
//-------------------------------------------
//-- Camera Selector
Row
{
visible
:
_isCamera
spacing
:
ScreenTools
.
defaultFontPixelWidth
spacing
:
ScreenTools
.
defaultFontPixelWidth
visible
:
_isCamera
&&
_dynamicCameras
.
cameraLabels
.
length
>
1
anchors.horizontalCenter
:
parent
.
horizontalCenter
QGCLabel
{
text
:
qsTr
(
"
Camera Selector:
"
)
...
...
@@ -225,6 +225,7 @@ Column {
//-- Stream Selector
Row
{
spacing
:
ScreenTools
.
defaultFontPixelWidth
visible
:
_isCamera
&&
_camera
.
streamLabels
.
length
>
1
anchors.horizontalCenter
:
parent
.
horizontalCenter
QGCLabel
{
text
:
qsTr
(
"
Stream Selector:
"
)
...
...
@@ -238,7 +239,47 @@ Column {
currentIndex
:
_camera
?
_camera
.
currentStream
:
0
}
}
//-------------------------------------------
//-- Thermal Modes
Row
{
spacing
:
ScreenTools
.
defaultFontPixelWidth
anchors.horizontalCenter
:
parent
.
horizontalCenter
visible
:
QGroundControl
.
videoManager
.
hasThermal
property
var
thermalModes
:
[
qsTr
(
"
Off
"
),
qsTr
(
"
Blend
"
),
qsTr
(
"
Full
"
),
qsTr
(
"
Picture In Picture
"
)]
QGCLabel
{
text
:
qsTr
(
"
Thermal View Mode
"
)
width
:
_labelFieldWidth
anchors.verticalCenter
:
parent
.
verticalCenter
}
QGCComboBox
{
width
:
_editFieldWidth
model
:
parent
.
thermalModes
currentIndex
:
_camera
?
_camera
.
thermalMode
:
0
onActivated
:
_camera
.
thermalMode
=
index
}
}
//-------------------------------------------
//-- Thermal Video Opacity
Row
{
spacing
:
ScreenTools
.
defaultFontPixelWidth
anchors.horizontalCenter
:
parent
.
horizontalCenter
visible
:
QGroundControl
.
videoManager
.
hasThermal
&&
_camera
.
thermalMode
===
QGCCameraControl
.
THERMAL_BLEND
QGCLabel
{
text
:
qsTr
(
"
Blend Opacity
"
)
width
:
_labelFieldWidth
anchors.verticalCenter
:
parent
.
verticalCenter
}
Slider
{
width
:
_editFieldWidth
maximumValue
:
100
minimumValue
:
0
value
:
_camera
?
_camera
.
thermalOpacity
:
0
updateValueWhileDragging
:
true
onValueChanged
:
{
_camera
.
thermalOpacity
=
value
}
}
}
//-------------------------------------------
//-- Camera Settings
Repeater
{
...
...
src/VideoStreaming/VideoReceiver.cc
View file @
0e7f614d
...
...
@@ -567,7 +567,7 @@ void
VideoReceiver
::
_handleStateChanged
()
{
if
(
_pipeline
)
{
_streaming
=
GST_STATE
(
_pipeline
)
==
GST_STATE_PLAYING
;
qCDebug
(
VideoReceiverLog
)
<<
"State changed, _streaming:"
<<
_streaming
;
//
qCDebug(VideoReceiverLog) << "State changed, _streaming:" << _streaming;
}
}
#endif
...
...
src/VideoStreaming/VideoReceiver.h
View file @
0e7f614d
...
...
@@ -7,7 +7,6 @@
*
****************************************************************************/
/**
* @file
* @brief QGC Video Receiver
...
...
Write
Preview
Markdown
is supported
0%
Try again
or
attach a new file
Attach a file
Cancel
You are about to add
0
people
to the discussion. Proceed with caution.
Finish editing this message first!
Cancel
Please
register
or
sign in
to comment