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
f5d6ff4d
Commit
f5d6ff4d
authored
Jan 10, 2019
by
Gus Grubba
Browse files
Options
Browse Files
Download
Email Patches
Plain Diff
Move video streaming handling to the camera API.
parent
8dca2cd4
Changes
10
Expand all
Show whitespace changes
Inline
Side-by-side
Showing
10 changed files
with
526 additions
and
251 deletions
+526
-251
QGCCameraControl.cc
src/Camera/QGCCameraControl.cc
+268
-17
QGCCameraControl.h
src/Camera/QGCCameraControl.h
+80
-20
QGCCameraManager.cc
src/Camera/QGCCameraManager.cc
+76
-5
QGCCameraManager.h
src/Camera/QGCCameraManager.h
+11
-3
FlightDisplayViewVideo.qml
src/FlightDisplay/FlightDisplayViewVideo.qml
+2
-10
VideoManager.cc
src/FlightDisplay/VideoManager.cc
+64
-147
VideoManager.h
src/FlightDisplay/VideoManager.h
+14
-33
VideoSettings.cc
src/Settings/VideoSettings.cc
+6
-7
VideoSettings.h
src/Settings/VideoSettings.h
+0
-3
GeneralSettings.qml
src/ui/preferences/GeneralSettings.qml
+5
-6
No files found.
src/Camera/QGCCameraControl.cc
View file @
f5d6ff4d
This diff is collapsed.
Click to expand it.
src/Camera/QGCCameraControl.h
View file @
f5d6ff4d
This diff is collapsed.
Click to expand it.
src/Camera/QGCCameraManager.cc
View file @
f5d6ff4d
...
@@ -35,6 +35,7 @@ QGCCameraManager::setCurrentCamera(int sel)
...
@@ -35,6 +35,7 @@ QGCCameraManager::setCurrentCamera(int sel)
if
(
sel
!=
_currentCamera
&&
sel
>=
0
&&
sel
<
_cameras
.
count
())
{
if
(
sel
!=
_currentCamera
&&
sel
>=
0
&&
sel
<
_cameras
.
count
())
{
_currentCamera
=
sel
;
_currentCamera
=
sel
;
emit
currentCameraChanged
();
emit
currentCameraChanged
();
emit
streamChanged
();
}
}
}
}
...
@@ -80,6 +81,12 @@ QGCCameraManager::_mavlinkMessageReceived(const mavlink_message_t& message)
...
@@ -80,6 +81,12 @@ QGCCameraManager::_mavlinkMessageReceived(const mavlink_message_t& message)
case
MAVLINK_MSG_ID_PARAM_EXT_VALUE
:
case
MAVLINK_MSG_ID_PARAM_EXT_VALUE
:
_handleParamValue
(
message
);
_handleParamValue
(
message
);
break
;
break
;
case
MAVLINK_MSG_ID_VIDEO_STREAM_INFORMATION
:
_handleVideoStreamInfo
(
message
);
break
;
case
MAVLINK_MSG_ID_VIDEO_STREAM_STATUS
:
_handleVideoStreamStatus
(
message
);
break
;
}
}
}
}
}
}
...
@@ -100,6 +107,29 @@ QGCCameraManager::_handleHeartbeat(const mavlink_message_t &message)
...
@@ -100,6 +107,29 @@ QGCCameraManager::_handleHeartbeat(const mavlink_message_t &message)
}
}
}
}
//-----------------------------------------------------------------------------
QGCCameraControl
*
QGCCameraManager
::
currentCameraInstance
()
{
if
(
_currentCamera
<
_cameras
.
count
()
&&
_cameras
.
count
())
{
QGCCameraControl
*
pCamera
=
qobject_cast
<
QGCCameraControl
*>
(
_cameras
[
_currentCamera
]);
return
pCamera
;
}
return
nullptr
;
}
//-----------------------------------------------------------------------------
QGCVideoStreamInfo
*
QGCCameraManager
::
currentStreamInstance
()
{
QGCCameraControl
*
pCamera
=
currentCameraInstance
();
if
(
pCamera
)
{
QGCVideoStreamInfo
*
pInfo
=
pCamera
->
currentStreamInstance
();
return
pInfo
;
}
return
nullptr
;
}
//-----------------------------------------------------------------------------
//-----------------------------------------------------------------------------
QGCCameraControl
*
QGCCameraControl
*
QGCCameraManager
::
_findCamera
(
int
id
)
QGCCameraManager
::
_findCamera
(
int
id
)
...
@@ -202,6 +232,30 @@ QGCCameraManager::_handleParamValue(const mavlink_message_t& message)
...
@@ -202,6 +232,30 @@ QGCCameraManager::_handleParamValue(const mavlink_message_t& message)
}
}
}
}
//-----------------------------------------------------------------------------
void
QGCCameraManager
::
_handleVideoStreamInfo
(
const
mavlink_message_t
&
message
)
{
QGCCameraControl
*
pCamera
=
_findCamera
(
message
.
compid
);
if
(
pCamera
)
{
mavlink_video_stream_information_t
streamInfo
;
mavlink_msg_video_stream_information_decode
(
&
message
,
&
streamInfo
);
pCamera
->
handleVideoInfo
(
&
streamInfo
);
}
}
//-----------------------------------------------------------------------------
void
QGCCameraManager
::
_handleVideoStreamStatus
(
const
mavlink_message_t
&
message
)
{
QGCCameraControl
*
pCamera
=
_findCamera
(
message
.
compid
);
if
(
pCamera
)
{
mavlink_video_stream_status_t
streamStatus
;
mavlink_msg_video_stream_status_decode
(
&
message
,
&
streamStatus
);
pCamera
->
handleVideoStatus
(
&
streamStatus
);
}
}
//-----------------------------------------------------------------------------
//-----------------------------------------------------------------------------
void
void
QGCCameraManager
::
_requestCameraInfo
(
int
compID
)
QGCCameraManager
::
_requestCameraInfo
(
int
compID
)
...
@@ -224,11 +278,13 @@ QGCCameraManager::_activeJoystickChanged(Joystick* joystick)
...
@@ -224,11 +278,13 @@ QGCCameraManager::_activeJoystickChanged(Joystick* joystick)
if
(
_activeJoystick
)
{
if
(
_activeJoystick
)
{
disconnect
(
_activeJoystick
,
&
Joystick
::
stepZoom
,
this
,
&
QGCCameraManager
::
_stepZoom
);
disconnect
(
_activeJoystick
,
&
Joystick
::
stepZoom
,
this
,
&
QGCCameraManager
::
_stepZoom
);
disconnect
(
_activeJoystick
,
&
Joystick
::
stepCamera
,
this
,
&
QGCCameraManager
::
_stepCamera
);
disconnect
(
_activeJoystick
,
&
Joystick
::
stepCamera
,
this
,
&
QGCCameraManager
::
_stepCamera
);
disconnect
(
_activeJoystick
,
&
Joystick
::
stepStream
,
this
,
&
QGCCameraManager
::
_stepStream
);
}
}
_activeJoystick
=
joystick
;
_activeJoystick
=
joystick
;
if
(
_activeJoystick
)
{
if
(
_activeJoystick
)
{
connect
(
_activeJoystick
,
&
Joystick
::
stepZoom
,
this
,
&
QGCCameraManager
::
_stepZoom
);
connect
(
_activeJoystick
,
&
Joystick
::
stepZoom
,
this
,
&
QGCCameraManager
::
_stepZoom
);
connect
(
_activeJoystick
,
&
Joystick
::
stepCamera
,
this
,
&
QGCCameraManager
::
_stepCamera
);
connect
(
_activeJoystick
,
&
Joystick
::
stepCamera
,
this
,
&
QGCCameraManager
::
_stepCamera
);
connect
(
_activeJoystick
,
&
Joystick
::
stepStream
,
this
,
&
QGCCameraManager
::
_stepStream
);
}
}
}
}
...
@@ -239,13 +295,11 @@ QGCCameraManager::_stepZoom(int direction)
...
@@ -239,13 +295,11 @@ QGCCameraManager::_stepZoom(int direction)
if
(
_lastZoomChange
.
elapsed
()
>
250
)
{
if
(
_lastZoomChange
.
elapsed
()
>
250
)
{
_lastZoomChange
.
start
();
_lastZoomChange
.
start
();
qCDebug
(
CameraManagerLog
)
<<
"Step Camera Zoom"
<<
direction
;
qCDebug
(
CameraManagerLog
)
<<
"Step Camera Zoom"
<<
direction
;
if
(
_cameras
.
count
()
&&
_cameras
[
_currentCamera
])
{
QGCCameraControl
*
pCamera
=
currentCameraInstance
();
QGCCameraControl
*
pCamera
=
qobject_cast
<
QGCCameraControl
*>
(
_cameras
[
_currentCamera
]);
if
(
pCamera
)
{
if
(
pCamera
)
{
pCamera
->
stepZoom
(
direction
);
pCamera
->
stepZoom
(
direction
);
}
}
}
}
}
}
}
//-----------------------------------------------------------------------------
//-----------------------------------------------------------------------------
...
@@ -262,4 +316,21 @@ QGCCameraManager::_stepCamera(int direction)
...
@@ -262,4 +316,21 @@ QGCCameraManager::_stepCamera(int direction)
}
}
}
}
//-----------------------------------------------------------------------------
void
QGCCameraManager
::
_stepStream
(
int
direction
)
{
if
(
_lastCameraChange
.
elapsed
()
>
1000
)
{
_lastCameraChange
.
start
();
QGCCameraControl
*
pCamera
=
currentCameraInstance
();
if
(
pCamera
)
{
qCDebug
(
CameraManagerLog
)
<<
"Step Camera Stream"
<<
direction
;
int
c
=
pCamera
->
currentStream
()
+
direction
;
if
(
c
<
0
)
c
=
pCamera
->
streams
()
->
count
()
-
1
;
if
(
c
>=
pCamera
->
streams
()
->
count
())
c
=
0
;
pCamera
->
setCurrentStream
(
c
);
}
}
}
src/Camera/QGCCameraManager.h
View file @
f5d6ff4d
...
@@ -30,6 +30,7 @@ public:
...
@@ -30,6 +30,7 @@ public:
Q_PROPERTY
(
QmlObjectListModel
*
cameras
READ
cameras
NOTIFY
camerasChanged
)
Q_PROPERTY
(
QmlObjectListModel
*
cameras
READ
cameras
NOTIFY
camerasChanged
)
Q_PROPERTY
(
QStringList
cameraLabels
READ
cameraLabels
NOTIFY
cameraLabelsChanged
)
Q_PROPERTY
(
QStringList
cameraLabels
READ
cameraLabels
NOTIFY
cameraLabelsChanged
)
Q_PROPERTY
(
int
currentCamera
READ
currentCamera
WRITE
setCurrentCamera
NOTIFY
currentCameraChanged
)
Q_PROPERTY
(
int
currentCamera
READ
currentCamera
WRITE
setCurrentCamera
NOTIFY
currentCameraChanged
)
Q_PROPERTY
(
QGCCameraControl
*
currentCameraInstance
READ
currentCameraInstance
NOTIFY
currentCameraChanged
)
//-- Return a list of cameras provided by this vehicle
//-- Return a list of cameras provided by this vehicle
virtual
QmlObjectListModel
*
cameras
()
{
return
&
_cameras
;
}
virtual
QmlObjectListModel
*
cameras
()
{
return
&
_cameras
;
}
...
@@ -37,13 +38,17 @@ public:
...
@@ -37,13 +38,17 @@ public:
virtual
QStringList
cameraLabels
()
{
return
_cameraLabels
;
}
virtual
QStringList
cameraLabels
()
{
return
_cameraLabels
;
}
//-- Current selected camera
//-- Current selected camera
virtual
int
currentCamera
()
{
return
_currentCamera
;
}
virtual
int
currentCamera
()
{
return
_currentCamera
;
}
virtual
QGCCameraControl
*
currentCameraInstance
();
//-- Set current camera
//-- Set current camera
virtual
void
setCurrentCamera
(
int
sel
);
virtual
void
setCurrentCamera
(
int
sel
);
//-- Current stream
virtual
QGCVideoStreamInfo
*
currentStreamInstance
();
signals:
signals:
void
camerasChanged
();
void
camerasChanged
();
void
cameraLabelsChanged
();
void
cameraLabelsChanged
();
void
currentCameraChanged
();
void
currentCameraChanged
();
void
streamChanged
();
protected
slots
:
protected
slots
:
virtual
void
_vehicleReady
(
bool
ready
);
virtual
void
_vehicleReady
(
bool
ready
);
...
@@ -51,6 +56,7 @@ protected slots:
...
@@ -51,6 +56,7 @@ protected slots:
virtual
void
_activeJoystickChanged
(
Joystick
*
joystick
);
virtual
void
_activeJoystickChanged
(
Joystick
*
joystick
);
virtual
void
_stepZoom
(
int
direction
);
virtual
void
_stepZoom
(
int
direction
);
virtual
void
_stepCamera
(
int
direction
);
virtual
void
_stepCamera
(
int
direction
);
virtual
void
_stepStream
(
int
direction
);
protected:
protected:
virtual
QGCCameraControl
*
_findCamera
(
int
id
);
virtual
QGCCameraControl
*
_findCamera
(
int
id
);
...
@@ -62,6 +68,8 @@ protected:
...
@@ -62,6 +68,8 @@ protected:
virtual
void
_handleParamAck
(
const
mavlink_message_t
&
message
);
virtual
void
_handleParamAck
(
const
mavlink_message_t
&
message
);
virtual
void
_handleParamValue
(
const
mavlink_message_t
&
message
);
virtual
void
_handleParamValue
(
const
mavlink_message_t
&
message
);
virtual
void
_handleCaptureStatus
(
const
mavlink_message_t
&
message
);
virtual
void
_handleCaptureStatus
(
const
mavlink_message_t
&
message
);
virtual
void
_handleVideoStreamInfo
(
const
mavlink_message_t
&
message
);
virtual
void
_handleVideoStreamStatus
(
const
mavlink_message_t
&
message
);
protected:
protected:
Vehicle
*
_vehicle
=
nullptr
;
Vehicle
*
_vehicle
=
nullptr
;
...
...
src/FlightDisplay/FlightDisplayViewVideo.qml
View file @
f5d6ff4d
...
@@ -31,9 +31,7 @@ Item {
...
@@ -31,9 +31,7 @@ Item {
property
int
_curCameraIndex
:
_dynamicCameras
?
_dynamicCameras
.
currentCamera
:
0
property
int
_curCameraIndex
:
_dynamicCameras
?
_dynamicCameras
.
currentCamera
:
0
property
bool
_isCamera
:
_dynamicCameras
?
_dynamicCameras
.
cameras
.
count
>
0
:
false
property
bool
_isCamera
:
_dynamicCameras
?
_dynamicCameras
.
cameras
.
count
>
0
:
false
property
var
_camera
:
_isCamera
?
_dynamicCameras
.
cameras
.
get
(
_curCameraIndex
)
:
null
property
var
_camera
:
_isCamera
?
_dynamicCameras
.
cameras
.
get
(
_curCameraIndex
)
:
null
property
bool
_hasCameraZoom
:
_camera
&&
_camera
.
hasZoom
property
bool
_hasZoom
:
_camera
&&
_camera
.
hasZoom
property
bool
_hasVideoZoom
:
QGroundControl
.
videoManager
.
hasZoom
property
bool
_hasZoom
:
_hasCameraZoom
||
_hasVideoZoom
property
int
_fitMode
:
QGroundControl
.
settingsManager
.
videoSettings
.
videoFit
.
rawValue
property
int
_fitMode
:
QGroundControl
.
settingsManager
.
videoSettings
.
videoFit
.
rawValue
Rectangle
{
Rectangle
{
id
:
noVideo
id
:
noVideo
...
@@ -141,13 +139,7 @@ Item {
...
@@ -141,13 +139,7 @@ Item {
z
=
Math
.
round
(
pinch
.
scale
)
z
=
Math
.
round
(
pinch
.
scale
)
}
}
if
(
pinchZoom
.
zoom
!=
z
)
{
if
(
pinchZoom
.
zoom
!=
z
)
{
//-- Camera zoom takes predence
if
(
_hasCameraZoom
)
{
_camera
.
stepZoom
(
z
)
_camera
.
stepZoom
(
z
)
}
else
if
(
_hasVideoZoom
)
{
//-- Video zoom is for dumb cameras that only stream (do not present a camera interface)
QGroundControl
.
videoManager
.
stepZoom
(
z
)
}
}
}
}
}
}
}
...
...
src/FlightDisplay/VideoManager.cc
View file @
f5d6ff4d
This diff is collapsed.
Click to expand it.
src/FlightDisplay/VideoManager.h
View file @
f5d6ff4d
...
@@ -37,16 +37,13 @@ public:
...
@@ -37,16 +37,13 @@ public:
Q_PROPERTY
(
bool
hasVideo
READ
hasVideo
NOTIFY
hasVideoChanged
)
Q_PROPERTY
(
bool
hasVideo
READ
hasVideo
NOTIFY
hasVideoChanged
)
Q_PROPERTY
(
bool
isGStreamer
READ
isGStreamer
NOTIFY
isGStreamerChanged
)
Q_PROPERTY
(
bool
isGStreamer
READ
isGStreamer
NOTIFY
isGStreamerChanged
)
Q_PROPERTY
(
bool
isAutoStream
READ
isAutoStream
NOTIFY
isAutoStreamChanged
)
Q_PROPERTY
(
bool
isTaisync
READ
isTaisync
WRITE
setIsTaisync
NOTIFY
isTaisyncChanged
)
Q_PROPERTY
(
bool
isTaisync
READ
isTaisync
WRITE
setIsTaisync
NOTIFY
isTaisyncChanged
)
Q_PROPERTY
(
QString
videoSourceID
READ
videoSourceID
NOTIFY
videoSourceIDChanged
)
Q_PROPERTY
(
QString
videoSourceID
READ
videoSourceID
NOTIFY
videoSourceIDChanged
)
Q_PROPERTY
(
bool
uvcEnabled
READ
uvcEnabled
CONSTANT
)
Q_PROPERTY
(
bool
uvcEnabled
READ
uvcEnabled
CONSTANT
)
Q_PROPERTY
(
bool
fullScreen
READ
fullScreen
WRITE
setfullScreen
NOTIFY
fullScreenChanged
)
Q_PROPERTY
(
bool
fullScreen
READ
fullScreen
WRITE
setfullScreen
NOTIFY
fullScreenChanged
)
Q_PROPERTY
(
VideoReceiver
*
videoReceiver
READ
videoReceiver
CONSTANT
)
Q_PROPERTY
(
VideoReceiver
*
videoReceiver
READ
videoReceiver
CONSTANT
)
Q_PROPERTY
(
double
aspectRatio
READ
aspectRatio
NOTIFY
streamInfoChanged
)
Q_PROPERTY
(
double
aspectRatio
READ
aspectRatio
NOTIFY
aspectRatioChanged
)
Q_PROPERTY
(
bool
hasZoom
READ
hasZoom
NOTIFY
streamInfoChanged
)
Q_PROPERTY
(
bool
autoStreamConfigured
READ
autoStreamConfigured
NOTIFY
autoStreamConfiguredChanged
)
Q_PROPERTY
(
int
streamCount
READ
streamCount
NOTIFY
streamCountChanged
)
Q_PROPERTY
(
int
currentStream
READ
currentStream
WRITE
setCurrentStream
NOTIFY
currentStreamChanged
)
bool
hasVideo
();
bool
hasVideo
();
bool
isGStreamer
();
bool
isGStreamer
();
...
@@ -54,11 +51,8 @@ public:
...
@@ -54,11 +51,8 @@ public:
bool
isTaisync
()
{
return
_isTaisync
;
}
bool
isTaisync
()
{
return
_isTaisync
;
}
bool
fullScreen
()
{
return
_fullScreen
;
}
bool
fullScreen
()
{
return
_fullScreen
;
}
QString
videoSourceID
()
{
return
_videoSourceID
;
}
QString
videoSourceID
()
{
return
_videoSourceID
;
}
QString
autoURL
()
{
return
QString
(
_streamInfo
.
uri
);
}
double
aspectRatio
();
double
aspectRatio
();
bool
hasZoom
()
{
return
_streamInfo
.
flags
&
VIDEO_STREAM_HAS_BASIC_ZOOM
;
}
bool
autoStreamConfigured
();
int
currentStream
()
{
return
_currentStream
;
}
int
streamCount
()
{
return
_streamInfo
.
count
;
}
VideoReceiver
*
videoReceiver
()
{
return
_videoReceiver
;
}
VideoReceiver
*
videoReceiver
()
{
return
_videoReceiver
;
}
...
@@ -70,15 +64,12 @@ public:
...
@@ -70,15 +64,12 @@ public:
void
setfullScreen
(
bool
f
)
{
_fullScreen
=
f
;
emit
fullScreenChanged
();
}
void
setfullScreen
(
bool
f
)
{
_fullScreen
=
f
;
emit
fullScreenChanged
();
}
void
setIsTaisync
(
bool
t
)
{
_isTaisync
=
t
;
emit
isTaisyncChanged
();
}
void
setIsTaisync
(
bool
t
)
{
_isTaisync
=
t
;
emit
isTaisyncChanged
();
}
void
setCurrentStream
(
int
stream
);
// Override from QGCTool
// Override from QGCTool
void
setToolbox
(
QGCToolbox
*
toolbox
);
void
setToolbox
(
QGCToolbox
*
toolbox
);
Q_INVOKABLE
void
startVideo
()
{
_videoReceiver
->
start
();
}
Q_INVOKABLE
void
startVideo
()
{
_videoReceiver
->
start
();
}
Q_INVOKABLE
void
stopVideo
()
{
_videoReceiver
->
stop
();
}
Q_INVOKABLE
void
stopVideo
()
{
_videoReceiver
->
stop
();
}
Q_INVOKABLE
void
stepZoom
(
int
direction
);
Q_INVOKABLE
void
stepStream
(
int
direction
);
signals:
signals:
void
hasVideoChanged
();
void
hasVideoChanged
();
...
@@ -86,10 +77,9 @@ signals:
...
@@ -86,10 +77,9 @@ signals:
void
videoSourceIDChanged
();
void
videoSourceIDChanged
();
void
fullScreenChanged
();
void
fullScreenChanged
();
void
isAutoStreamChanged
();
void
isAutoStreamChanged
();
void
streamInfoChanged
();
void
isTaisyncChanged
();
void
isTaisyncChanged
();
void
currentStreamChanged
();
void
aspectRatioChanged
();
void
streamCountChanged
();
void
autoStreamConfiguredChanged
();
private
slots
:
private
slots
:
void
_videoSourceChanged
();
void
_videoSourceChanged
();
...
@@ -97,14 +87,12 @@ private slots:
...
@@ -97,14 +87,12 @@ private slots:
void
_rtspUrlChanged
();
void
_rtspUrlChanged
();
void
_tcpUrlChanged
();
void
_tcpUrlChanged
();
void
_updateUVC
();
void
_updateUVC
();
void
_streamInfoChanged
();
void
_setActiveVehicle
(
Vehicle
*
vehicle
);
void
_setActiveVehicle
(
Vehicle
*
vehicle
);
void
_a
ctiveJoystickChanged
(
Joystick
*
joystick
);
void
_a
spectRatioChanged
(
);
void
_
vehicleMessageReceived
(
const
mavlink_message_t
&
message
);
void
_
restartVideo
(
);
private:
private:
void
_updateSettings
();
void
_updateSettings
();
void
_restartVideo
();
private:
private:
bool
_isTaisync
=
false
;
bool
_isTaisync
=
false
;
...
@@ -113,13 +101,6 @@ private:
...
@@ -113,13 +101,6 @@ private:
QString
_videoSourceID
;
QString
_videoSourceID
;
bool
_fullScreen
=
false
;
bool
_fullScreen
=
false
;
Vehicle
*
_activeVehicle
=
nullptr
;
Vehicle
*
_activeVehicle
=
nullptr
;
Joystick
*
_activeJoystick
=
nullptr
;
mavlink_video_stream_information_t
_streamInfo
;
bool
_hasAutoStream
=
false
;
uint8_t
_videoStreamCompID
=
0
;
int
_currentStream
=
1
;
QTime
_lastZoomChange
;
QTime
_lastStreamChange
;
};
};
#endif
#endif
src/Settings/VideoSettings.cc
View file @
f5d6ff4d
...
@@ -21,7 +21,6 @@
...
@@ -21,7 +21,6 @@
const
char
*
VideoSettings
::
videoSourceNoVideo
=
"No Video Available"
;
const
char
*
VideoSettings
::
videoSourceNoVideo
=
"No Video Available"
;
const
char
*
VideoSettings
::
videoDisabled
=
"Video Stream Disabled"
;
const
char
*
VideoSettings
::
videoDisabled
=
"Video Stream Disabled"
;
const
char
*
VideoSettings
::
videoSourceAuto
=
"Automatic Video Stream"
;
const
char
*
VideoSettings
::
videoSourceRTSP
=
"RTSP Video Stream"
;
const
char
*
VideoSettings
::
videoSourceRTSP
=
"RTSP Video Stream"
;
const
char
*
VideoSettings
::
videoSourceUDP
=
"UDP Video Stream"
;
const
char
*
VideoSettings
::
videoSourceUDP
=
"UDP Video Stream"
;
const
char
*
VideoSettings
::
videoSourceTCP
=
"TCP-MPEG2 Video Stream"
;
const
char
*
VideoSettings
::
videoSourceTCP
=
"TCP-MPEG2 Video Stream"
;
...
@@ -35,7 +34,6 @@ DECLARE_SETTINGGROUP(Video, "Video")
...
@@ -35,7 +34,6 @@ DECLARE_SETTINGGROUP(Video, "Video")
// Setup enum values for videoSource settings into meta data
// Setup enum values for videoSource settings into meta data
QStringList
videoSourceList
;
QStringList
videoSourceList
;
#ifdef QGC_GST_STREAMING
#ifdef QGC_GST_STREAMING
videoSourceList
.
append
(
videoSourceAuto
);
videoSourceList
.
append
(
videoSourceRTSP
);
videoSourceList
.
append
(
videoSourceRTSP
);
#ifndef NO_UDP_VIDEO
#ifndef NO_UDP_VIDEO
videoSourceList
.
append
(
videoSourceUDP
);
videoSourceList
.
append
(
videoSourceUDP
);
...
@@ -133,10 +131,16 @@ bool VideoSettings::streamConfigured(void)
...
@@ -133,10 +131,16 @@ bool VideoSettings::streamConfigured(void)
#if !defined(QGC_GST_STREAMING)
#if !defined(QGC_GST_STREAMING)
return
false
;
return
false
;
#endif
#endif
//-- First, check if it's disabled
QString
vSource
=
videoSource
()
->
rawValue
().
toString
();
QString
vSource
=
videoSource
()
->
rawValue
().
toString
();
if
(
vSource
==
videoSourceNoVideo
||
vSource
==
videoDisabled
)
{
if
(
vSource
==
videoSourceNoVideo
||
vSource
==
videoDisabled
)
{
return
false
;
return
false
;
}
}
//-- Check if it's autoconfigured
if
(
qgcApp
()
->
toolbox
()
->
videoManager
()
->
autoStreamConfigured
())
{
qCDebug
(
VideoManagerLog
)
<<
"Stream auto configured"
;
return
true
;
}
//-- If UDP, check if port is set
//-- If UDP, check if port is set
if
(
vSource
==
videoSourceUDP
)
{
if
(
vSource
==
videoSourceUDP
)
{
qCDebug
(
VideoManagerLog
)
<<
"Testing configuration for UDP Stream:"
<<
udpPort
()
->
rawValue
().
toInt
();
qCDebug
(
VideoManagerLog
)
<<
"Testing configuration for UDP Stream:"
<<
udpPort
()
->
rawValue
().
toInt
();
...
@@ -157,11 +161,6 @@ bool VideoSettings::streamConfigured(void)
...
@@ -157,11 +161,6 @@ bool VideoSettings::streamConfigured(void)
qCDebug
(
VideoManagerLog
)
<<
"Testing configuration for MPEG-TS Stream:"
<<
udpPort
()
->
rawValue
().
toInt
();
qCDebug
(
VideoManagerLog
)
<<
"Testing configuration for MPEG-TS Stream:"
<<
udpPort
()
->
rawValue
().
toInt
();
return
udpPort
()
->
rawValue
().
toInt
()
!=
0
;
return
udpPort
()
->
rawValue
().
toInt
()
!=
0
;
}
}
//-- If Auto, check for received URL
if
(
vSource
==
videoSourceAuto
)
{
qCDebug
(
VideoManagerLog
)
<<
"Testing configuration for Auto Stream:"
<<
qgcApp
()
->
toolbox
()
->
videoManager
()
->
autoURL
();
return
!
qgcApp
()
->
toolbox
()
->
videoManager
()
->
autoURL
().
isEmpty
();
}
return
false
;
return
false
;
}
}
...
...
src/Settings/VideoSettings.h
View file @
f5d6ff4d
...
@@ -36,14 +36,12 @@ public:
...
@@ -36,14 +36,12 @@ public:
DEFINE_SETTINGFACT
(
disableWhenDisarmed
)
DEFINE_SETTINGFACT
(
disableWhenDisarmed
)
Q_PROPERTY
(
bool
streamConfigured
READ
streamConfigured
NOTIFY
streamConfiguredChanged
)
Q_PROPERTY
(
bool
streamConfigured
READ
streamConfigured
NOTIFY
streamConfiguredChanged
)
Q_PROPERTY
(
QString
autoVideoSource
READ
autoVideoSource
CONSTANT
)
Q_PROPERTY
(
QString
rtspVideoSource
READ
rtspVideoSource
CONSTANT
)
Q_PROPERTY
(
QString
rtspVideoSource
READ
rtspVideoSource
CONSTANT
)
Q_PROPERTY
(
QString
udpVideoSource
READ
udpVideoSource
CONSTANT
)
Q_PROPERTY
(
QString
udpVideoSource
READ
udpVideoSource
CONSTANT
)
Q_PROPERTY
(
QString
tcpVideoSource
READ
tcpVideoSource
CONSTANT
)
Q_PROPERTY
(
QString
tcpVideoSource
READ
tcpVideoSource
CONSTANT
)
Q_PROPERTY
(
QString
mpegtsVideoSource
READ
mpegtsVideoSource
CONSTANT
)
Q_PROPERTY
(
QString
mpegtsVideoSource
READ
mpegtsVideoSource
CONSTANT
)
bool
streamConfigured
();
bool
streamConfigured
();
QString
autoVideoSource
()
{
return
videoSourceAuto
;
}
QString
rtspVideoSource
()
{
return
videoSourceRTSP
;
}
QString
rtspVideoSource
()
{
return
videoSourceRTSP
;
}
QString
udpVideoSource
()
{
return
videoSourceUDP
;
}
QString
udpVideoSource
()
{
return
videoSourceUDP
;
}
QString
tcpVideoSource
()
{
return
videoSourceTCP
;
}
QString
tcpVideoSource
()
{
return
videoSourceTCP
;
}
...
@@ -53,7 +51,6 @@ public:
...
@@ -53,7 +51,6 @@ public:
static
const
char
*
videoDisabled
;
static
const
char
*
videoDisabled
;
static
const
char
*
videoSourceUDP
;
static
const
char
*
videoSourceUDP
;
static
const
char
*
videoSourceRTSP
;
static
const
char
*
videoSourceRTSP
;
static
const
char
*
videoSourceAuto
;
static
const
char
*
videoSourceTCP
;
static
const
char
*
videoSourceTCP
;
static
const
char
*
videoSourceMPEGTS
;
static
const
char
*
videoSourceMPEGTS
;
...
...
src/ui/preferences/GeneralSettings.qml
View file @
f5d6ff4d
...
@@ -47,7 +47,6 @@ QGCView {
...
@@ -47,7 +47,6 @@ QGCView {
property
string
_videoSource
:
QGroundControl
.
settingsManager
.
videoSettings
.
videoSource
.
value
property
string
_videoSource
:
QGroundControl
.
settingsManager
.
videoSettings
.
videoSource
.
value
property
bool
_isGst
:
QGroundControl
.
videoManager
.
isGStreamer
property
bool
_isGst
:
QGroundControl
.
videoManager
.
isGStreamer
property
bool
_isAutoStream
:
QGroundControl
.
videoManager
.
isAutoStream
property
bool
_isUDP
:
_isGst
&&
_videoSource
===
QGroundControl
.
settingsManager
.
videoSettings
.
udpVideoSource
property
bool
_isUDP
:
_isGst
&&
_videoSource
===
QGroundControl
.
settingsManager
.
videoSettings
.
udpVideoSource
property
bool
_isRTSP
:
_isGst
&&
_videoSource
===
QGroundControl
.
settingsManager
.
videoSettings
.
rtspVideoSource
property
bool
_isRTSP
:
_isGst
&&
_videoSource
===
QGroundControl
.
settingsManager
.
videoSettings
.
rtspVideoSource
property
bool
_isTCP
:
_isGst
&&
_videoSource
===
QGroundControl
.
settingsManager
.
videoSettings
.
tcpVideoSource
property
bool
_isTCP
:
_isGst
&&
_videoSource
===
QGroundControl
.
settingsManager
.
videoSettings
.
tcpVideoSource
...
@@ -691,7 +690,7 @@ QGCView {
...
@@ -691,7 +690,7 @@ QGCView {
QGCLabel
{
QGCLabel
{
id
:
videoSectionLabel
id
:
videoSectionLabel
text
:
qsTr
(
"
Video
"
)
text
:
qsTr
(
"
Video
"
)
visible
:
QGroundControl
.
settingsManager
.
videoSettings
.
visible
visible
:
QGroundControl
.
settingsManager
.
videoSettings
.
visible
&&
!
QGroundControl
.
videoManager
.
autoStreamConfigured
}
}
Rectangle
{
Rectangle
{
Layout.preferredWidth
:
videoGrid
.
width
+
(
_margins
*
2
)
Layout.preferredWidth
:
videoGrid
.
width
+
(
_margins
*
2
)
...
@@ -751,12 +750,12 @@ QGCView {
...
@@ -751,12 +750,12 @@ QGCView {
}
}
QGCLabel
{
QGCLabel
{
text
:
qsTr
(
"
Aspect Ratio
"
)
text
:
qsTr
(
"
Aspect Ratio
"
)
visible
:
!
_isAutoStream
&&
_isGst
&&
QGroundControl
.
settingsManager
.
videoSettings
.
aspectRatio
.
visible
visible
:
_isGst
&&
QGroundControl
.
settingsManager
.
videoSettings
.
aspectRatio
.
visible
}
}
FactTextField
{
FactTextField
{
Layout.preferredWidth
:
_comboFieldWidth
Layout.preferredWidth
:
_comboFieldWidth
fact
:
QGroundControl
.
settingsManager
.
videoSettings
.
aspectRatio
fact
:
QGroundControl
.
settingsManager
.
videoSettings
.
aspectRatio
visible
:
!
_isAutoStream
&&
_isGst
&&
QGroundControl
.
settingsManager
.
videoSettings
.
aspectRatio
.
visible
visible
:
_isGst
&&
QGroundControl
.
settingsManager
.
videoSettings
.
aspectRatio
.
visible
}
}
QGCLabel
{
QGCLabel
{
...
@@ -776,7 +775,7 @@ QGCView {
...
@@ -776,7 +775,7 @@ QGCView {
QGCLabel
{
QGCLabel
{
id
:
videoRecSectionLabel
id
:
videoRecSectionLabel
text
:
qsTr
(
"
Video Recording
"
)
text
:
qsTr
(
"
Video Recording
"
)
visible
:
QGroundControl
.
settingsManager
.
videoSettings
.
visible
&&
_isGst
visible
:
(
QGroundControl
.
settingsManager
.
videoSettings
.
visible
&&
_isGst
)
||
QGroundControl
.
videoManager
.
autoStreamConfigured
}
}
Rectangle
{
Rectangle
{
Layout.preferredWidth
:
videoRecCol
.
width
+
(
_margins
*
2
)
Layout.preferredWidth
:
videoRecCol
.
width
+
(
_margins
*
2
)
...
...
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