Unverified Commit bea95bb1 authored by Gus Grubba's avatar Gus Grubba Committed by GitHub

Merge pull request #5859 from mavlink/videoStreamControl

Video Stream Control Widget
parents d9c5a95d 57f0cf4a
...@@ -116,11 +116,23 @@ install: ...@@ -116,11 +116,23 @@ install:
# osx dependencies: qt, gstreamer, gstreamer-devel # osx dependencies: qt, gstreamer, gstreamer-devel
- if [ "${SPEC}" = "macx-clang" ]; then - if [ "${SPEC}" = "macx-clang" ]; then
wget --quiet https://s3-us-west-2.amazonaws.com/qgroundcontrol/dependencies/Qt5.9.1-mac-clang-min.tar.bz2 && wget --quiet https://s3-us-west-2.amazonaws.com/qgroundcontrol/dependencies/Qt5.9.1-mac-clang-min.tar.bz2 &&
tar jxf Qt5.9.1-mac-clang-min.tar.bz2 -C /tmp && tar jxf Qt5.9.1-mac-clang-min.tar.bz2 -C /tmp
;
fi
- if [ "${SPEC}" = "macx-clang" ]; then
wget --quiet https://s3-us-west-2.amazonaws.com/qgroundcontrol/dependencies/gstreamer-1.0-1.5.2-x86_64.pkg && wget --quiet https://s3-us-west-2.amazonaws.com/qgroundcontrol/dependencies/gstreamer-1.0-1.5.2-x86_64.pkg &&
sudo installer -verboseR -pkg gstreamer-1.0-1.5.2-x86_64.pkg -target / && sudo installer -verboseR -pkg gstreamer-1.0-1.5.2-x86_64.pkg -target /
;
fi
- if [ "${SPEC}" = "macx-clang" ]; then
wget --quiet https://s3-us-west-2.amazonaws.com/qgroundcontrol/dependencies/gstreamer-1.0-devel-1.5.2-x86_64.pkg && wget --quiet https://s3-us-west-2.amazonaws.com/qgroundcontrol/dependencies/gstreamer-1.0-devel-1.5.2-x86_64.pkg &&
sudo installer -verboseR -pkg gstreamer-1.0-devel-1.5.2-x86_64.pkg -target / && sudo installer -verboseR -pkg gstreamer-1.0-devel-1.5.2-x86_64.pkg -target /
;
fi
- if [ "${SPEC}" = "macx-clang" ]; then
wget --quiet https://s3-us-west-2.amazonaws.com/qgroundcontrol/dependencies/osx-gstreamer.tar.bz2 && wget --quiet https://s3-us-west-2.amazonaws.com/qgroundcontrol/dependencies/osx-gstreamer.tar.bz2 &&
sudo tar jxf osx-gstreamer.tar.bz2 -C /Library/Frameworks && sudo tar jxf osx-gstreamer.tar.bz2 -C /Library/Frameworks &&
export QT_DIR=Qt5.9-mac-clang/5.9.1/clang_64 && export QT_DIR=Qt5.9-mac-clang/5.9.1/clang_64 &&
......
...@@ -92,6 +92,7 @@ ...@@ -92,6 +92,7 @@
<file alias="QGroundControl/Controls/QGCPipable.qml">src/QmlControls/QGCPipable.qml</file> <file alias="QGroundControl/Controls/QGCPipable.qml">src/QmlControls/QGCPipable.qml</file>
<file alias="QGroundControl/Controls/QGCRadioButton.qml">src/QmlControls/QGCRadioButton.qml</file> <file alias="QGroundControl/Controls/QGCRadioButton.qml">src/QmlControls/QGCRadioButton.qml</file>
<file alias="QGroundControl/Controls/QGCSlider.qml">src/QmlControls/QGCSlider.qml</file> <file alias="QGroundControl/Controls/QGCSlider.qml">src/QmlControls/QGCSlider.qml</file>
<file alias="QGroundControl/Controls/QGCSwitch.qml">src/QmlControls/QGCSwitch.qml</file>
<file alias="QGroundControl/Controls/QGCTextField.qml">src/QmlControls/QGCTextField.qml</file> <file alias="QGroundControl/Controls/QGCTextField.qml">src/QmlControls/QGCTextField.qml</file>
<file alias="QGroundControl/Controls/QGCToolBarButton.qml">src/QmlControls/QGCToolBarButton.qml</file> <file alias="QGroundControl/Controls/QGCToolBarButton.qml">src/QmlControls/QGCToolBarButton.qml</file>
<file alias="QGroundControl/Controls/QGCView.qml">src/QmlControls/QGCView.qml</file> <file alias="QGroundControl/Controls/QGCView.qml">src/QmlControls/QGCView.qml</file>
...@@ -179,6 +180,7 @@ ...@@ -179,6 +180,7 @@
<file alias="VehicleSummary.qml">src/VehicleSetup/VehicleSummary.qml</file> <file alias="VehicleSummary.qml">src/VehicleSetup/VehicleSummary.qml</file>
<file alias="VirtualJoystick.qml">src/FlightDisplay/VirtualJoystick.qml</file> <file alias="VirtualJoystick.qml">src/FlightDisplay/VirtualJoystick.qml</file>
<file alias="CameraPageWidget.qml">src/FlightMap/Widgets/CameraPageWidget.qml</file> <file alias="CameraPageWidget.qml">src/FlightMap/Widgets/CameraPageWidget.qml</file>
<file alias="VideoPageWidget.qml">src/FlightMap/Widgets/VideoPageWidget.qml</file>
<file alias="ValuePageWidget.qml">src/FlightMap/Widgets/ValuePageWidget.qml</file> <file alias="ValuePageWidget.qml">src/FlightMap/Widgets/ValuePageWidget.qml</file>
<file alias="HealthPageWidget.qml">src/FlightMap/Widgets/HealthPageWidget.qml</file> <file alias="HealthPageWidget.qml">src/FlightMap/Widgets/HealthPageWidget.qml</file>
<file alias="VibrationPageWidget.qml">src/FlightMap/Widgets/VibrationPageWidget.qml</file> <file alias="VibrationPageWidget.qml">src/FlightMap/Widgets/VibrationPageWidget.qml</file>
......
...@@ -43,8 +43,6 @@ QGCView { ...@@ -43,8 +43,6 @@ QGCView {
property var _geoFenceController: _planMasterController.geoFenceController property var _geoFenceController: _planMasterController.geoFenceController
property var _rallyPointController: _planMasterController.rallyPointController property var _rallyPointController: _planMasterController.rallyPointController
property var _activeVehicle: QGroundControl.multiVehicleManager.activeVehicle property var _activeVehicle: QGroundControl.multiVehicleManager.activeVehicle
property var _videoReceiver: QGroundControl.videoManager.videoReceiver
property bool _recordingVideo: _videoReceiver && _videoReceiver.recording
property bool _mainIsMap: QGroundControl.videoManager.hasVideo ? QGroundControl.loadBoolGlobalSetting(_mainIsMapKey, true) : true property bool _mainIsMap: QGroundControl.videoManager.hasVideo ? QGroundControl.loadBoolGlobalSetting(_mainIsMapKey, true) : true
property bool _isPipVisible: QGroundControl.videoManager.hasVideo ? QGroundControl.loadBoolGlobalSetting(_PIPVisibleKey, true) : false property bool _isPipVisible: QGroundControl.videoManager.hasVideo ? QGroundControl.loadBoolGlobalSetting(_PIPVisibleKey, true) : false
property real _savedZoomLevel: 0 property real _savedZoomLevel: 0
...@@ -346,63 +344,6 @@ QGCView { ...@@ -346,63 +344,6 @@ QGCView {
property var qgcView: root property var qgcView: root
} }
// Button to start/stop video recording
Item {
z: _flightVideoPipControl.z + 1
anchors.margins: ScreenTools.defaultFontPixelHeight / 2
anchors.bottom: _flightVideo.bottom
anchors.right: _flightVideo.right
height: ScreenTools.defaultFontPixelHeight * 2
width: height
visible: _videoReceiver && _videoReceiver.videoRunning && QGroundControl.settingsManager.videoSettings.showRecControl.rawValue && _flightVideo.visible && !_isCamera && !QGroundControl.videoManager.fullScreen
opacity: 0.75
readonly property string recordBtnBackground: "BackgroundName"
Rectangle {
id: recordBtnBackground
anchors.top: parent.top
anchors.bottom: parent.bottom
width: height
radius: _recordingVideo ? 0 : height
color: "red"
SequentialAnimation on visible {
running: _recordingVideo
loops: Animation.Infinite
PropertyAnimation { to: false; duration: 1000 }
PropertyAnimation { to: true; duration: 1000 }
}
}
QGCColoredImage {
anchors.top: parent.top
anchors.bottom: parent.bottom
anchors.horizontalCenter: parent.horizontalCenter
width: height * 0.625
sourceSize.width: width
source: "/qmlimages/CameraIcon.svg"
visible: recordBtnBackground.visible
fillMode: Image.PreserveAspectFit
color: "white"
}
MouseArea {
anchors.fill: parent
onClicked: {
if (_videoReceiver) {
if (_recordingVideo) {
_videoReceiver.stopRecording()
// reset blinking animation
recordBtnBackground.visible = true
} else {
_videoReceiver.startRecording()
}
}
}
}
}
MultiVehicleList { MultiVehicleList {
anchors.margins: _margins anchors.margins: _margins
anchors.top: singleMultiSelector.bottom anchors.top: singleMultiSelector.bottom
......
...@@ -34,7 +34,7 @@ Item { ...@@ -34,7 +34,7 @@ Item {
color: Qt.rgba(0,0,0,0.75) color: Qt.rgba(0,0,0,0.75)
visible: !(_videoReceiver && _videoReceiver.videoRunning) visible: !(_videoReceiver && _videoReceiver.videoRunning)
QGCLabel { QGCLabel {
text: qsTr("WAITING FOR VIDEO") text: QGroundControl.settingsManager.videoSettings.streamEnabled.rawValue ? qsTr("WAITING FOR VIDEO") : qsTr("VIDEO DISABLED")
font.family: ScreenTools.demiboldFontFamily font.family: ScreenTools.demiboldFontFamily
color: "white" color: "white"
font.pointSize: _mainIsMap ? ScreenTools.smallFontPointSize : ScreenTools.largeFontPointSize font.pointSize: _mainIsMap ? ScreenTools.smallFontPointSize : ScreenTools.largeFontPointSize
......
...@@ -40,7 +40,7 @@ Item { ...@@ -40,7 +40,7 @@ Item {
function getPreferredInstrumentWidth() { function getPreferredInstrumentWidth() {
if(ScreenTools.isMobile) { if(ScreenTools.isMobile) {
return ScreenTools.isTinyScreen ? mainWindow.width * 0.2 : mainWindow.width * 0.15 return mainWindow.width * 0.25
} }
return ScreenTools.defaultFontPixelWidth * 30 return ScreenTools.defaultFontPixelWidth * 30
} }
......
...@@ -20,7 +20,7 @@ import QGroundControl.Palette 1.0 ...@@ -20,7 +20,7 @@ import QGroundControl.Palette 1.0
/// Instrument panel shown when virtual thumbsticks are visible /// Instrument panel shown when virtual thumbsticks are visible
Rectangle { Rectangle {
id: root id: root
width: ScreenTools.isTinyScreen ? getPreferredInstrumentWidth() * 1.5 : getPreferredInstrumentWidth() width: getPreferredInstrumentWidth()
height: _outerRadius * 2 height: _outerRadius * 2
radius: _outerRadius radius: _outerRadius
color: qgcPal.window color: qgcPal.window
......
/****************************************************************************
*
* (c) 2009-2016 QGROUNDCONTROL PROJECT <http://www.qgroundcontrol.org>
*
* QGroundControl is licensed according to the terms in the file
* COPYING.md in the root of the source code directory.
*
****************************************************************************/
import QtQuick 2.4
import QtPositioning 5.2
import QtQuick.Layouts 1.2
import QtQuick.Controls 1.4
import QtQuick.Dialogs 1.2
import QtGraphicalEffects 1.0
import QGroundControl 1.0
import QGroundControl.ScreenTools 1.0
import QGroundControl.Controls 1.0
import QGroundControl.Palette 1.0
import QGroundControl.Vehicle 1.0
import QGroundControl.Controllers 1.0
import QGroundControl.FactSystem 1.0
import QGroundControl.FactControls 1.0
/// Video streaming page for Instrument Panel PageView
Item {
width: pageWidth
height: videoGrid.height + (ScreenTools.defaultFontPixelHeight * 2)
anchors.margins: ScreenTools.defaultFontPixelWidth * 2
anchors.centerIn: parent
property var _activeVehicle: QGroundControl.multiVehicleManager.activeVehicle
property bool _communicationLost: _activeVehicle ? _activeVehicle.connectionLost : false
property var _videoReceiver: QGroundControl.videoManager.videoReceiver
property bool _recordingVideo: _videoReceiver && _videoReceiver.recording
property bool _videoRunning: _videoReceiver && _videoReceiver.videoRunning
property bool _streamingEnabled: QGroundControl.settingsManager.videoSettings.streamConfigured
QGCPalette { id:qgcPal; colorGroupEnabled: true }
GridLayout {
id: videoGrid
columns: 2
columnSpacing: ScreenTools.defaultFontPixelWidth * 2
rowSpacing: ScreenTools.defaultFontPixelHeight
anchors.centerIn: parent
Connections {
// For some reason, the normal signal is not reflected in the control below
target: QGroundControl.settingsManager.videoSettings.streamEnabled
onRawValueChanged: {
enableSwitch.checked = QGroundControl.settingsManager.videoSettings.streamEnabled.rawValue
}
}
// Enable/Disable Video Streaming
QGCLabel {
text: qsTr("Enable Stream")
font.pointSize: ScreenTools.smallFontPointSize
}
QGCSwitch {
id: enableSwitch
enabled: _streamingEnabled
checked: QGroundControl.settingsManager.videoSettings.streamEnabled.rawValue
onClicked: {
if(checked) {
QGroundControl.settingsManager.videoSettings.streamEnabled.rawValue = 1
_videoReceiver.start()
} else {
QGroundControl.settingsManager.videoSettings.streamEnabled.rawValue = 0
_videoReceiver.stop()
}
}
}
// Grid Lines
QGCLabel {
text: qsTr("Grid Lines")
font.pointSize: ScreenTools.smallFontPointSize
visible: QGroundControl.videoManager.isGStreamer && QGroundControl.settingsManager.videoSettings.gridLines.visible
}
QGCSwitch {
enabled: _streamingEnabled && _activeVehicle
checked: QGroundControl.settingsManager.videoSettings.gridLines.rawValue
visible: QGroundControl.videoManager.isGStreamer && QGroundControl.settingsManager.videoSettings.gridLines.visible
onClicked: {
if(checked) {
QGroundControl.settingsManager.videoSettings.gridLines.rawValue = 1
} else {
QGroundControl.settingsManager.videoSettings.gridLines.rawValue = 0
}
}
}
QGCLabel {
text: _recordingVideo ? qsTr("Stop Recording") : qsTr("Record Stream")
font.pointSize: ScreenTools.smallFontPointSize
visible: QGroundControl.settingsManager.videoSettings.showRecControl.rawValue
}
// Button to start/stop video recording
Item {
anchors.margins: ScreenTools.defaultFontPixelHeight / 2
height: ScreenTools.defaultFontPixelHeight * 2
width: height
Layout.alignment: Qt.AlignHCenter
visible: QGroundControl.settingsManager.videoSettings.showRecControl.rawValue
Rectangle {
id: recordBtnBackground
anchors.top: parent.top
anchors.bottom: parent.bottom
width: height
radius: _recordingVideo ? 0 : height
color: (_videoRunning && _streamingEnabled) ? "red" : "gray"
SequentialAnimation on opacity {
running: _recordingVideo
loops: Animation.Infinite
PropertyAnimation { to: 0.5; duration: 500 }
PropertyAnimation { to: 1.0; duration: 500 }
}
}
QGCColoredImage {
anchors.top: parent.top
anchors.bottom: parent.bottom
anchors.horizontalCenter: parent.horizontalCenter
width: height * 0.625
sourceSize.width: width
source: "/qmlimages/CameraIcon.svg"
visible: recordBtnBackground.visible
fillMode: Image.PreserveAspectFit
color: "white"
}
MouseArea {
anchors.fill: parent
enabled: _videoRunning && _streamingEnabled
onClicked: {
if (_recordingVideo) {
_videoReceiver.stopRecording()
// reset blinking animation
recordBtnBackground.opacity = 1
} else {
_videoReceiver.startRecording()
}
}
}
}
QGCLabel {
text: qsTr("Video Streaming Not Configured")
font.pointSize: ScreenTools.smallFontPointSize
visible: !_streamingEnabled
Layout.columnSpan: 2
}
}
}
...@@ -38,7 +38,7 @@ Rectangle { ...@@ -38,7 +38,7 @@ Rectangle {
width: parent.height -(_margins * 2) width: parent.height -(_margins * 2)
sourceSize.width: width sourceSize.width: width
fillMode: Image.PreserveAspectFit fillMode: Image.PreserveAspectFit
visible: pageWidgetLoader.item.showSettingsIcon visible: pageWidgetLoader.item ? (pageWidgetLoader.item.showSettingsIcon ? pageWidgetLoader.item.showSettingsIcon : false) : false
QGCMouseArea { QGCMouseArea {
fillItem: parent fillItem: parent
......
/****************************************************************************
*
* (c) 2009-2016 QGROUNDCONTROL PROJECT <http://www.qgroundcontrol.org>
*
* QGroundControl is licensed according to the terms in the file
* COPYING.md in the root of the source code directory.
*
****************************************************************************/
import QtQuick 2.3
import QtQuick.Controls 1.2
import QtQuick.Controls.Styles 1.4
import QGroundControl.Palette 1.0
import QGroundControl.ScreenTools 1.0
Switch {
id: _root
QGCPalette { id:qgcPal; colorGroupEnabled: true }
style: SwitchStyle {
groove: Rectangle {
implicitWidth: ScreenTools.defaultFontPixelWidth * 6
implicitHeight: ScreenTools.defaultFontPixelHeight
color: (control.checked && control.enabled) ? qgcPal.colorGreen : qgcPal.colorGrey
radius: 3
border.color: qgcPal.button
border.width: 1
}
}
}
...@@ -52,6 +52,7 @@ QGCMovableItem 1.0 QGCMovableItem.qml ...@@ -52,6 +52,7 @@ QGCMovableItem 1.0 QGCMovableItem.qml
QGCPipable 1.0 QGCPipable.qml QGCPipable 1.0 QGCPipable.qml
QGCRadioButton 1.0 QGCRadioButton.qml QGCRadioButton 1.0 QGCRadioButton.qml
QGCSlider 1.0 QGCSlider.qml QGCSlider 1.0 QGCSlider.qml
QGCSwitch 1.0 QGCSwitch.qml
QGCTextField 1.0 QGCTextField.qml QGCTextField 1.0 QGCTextField.qml
QGCToolBarButton 1.0 QGCToolBarButton.qml QGCToolBarButton 1.0 QGCToolBarButton.qml
QGCView 1.0 QGCView.qml QGCView 1.0 QGCView.qml
......
...@@ -94,5 +94,19 @@ ...@@ -94,5 +94,19 @@
"min": 1, "min": 1,
"units": "s", "units": "s",
"defaultValue": 2 "defaultValue": 2
},
{
"name": "StreamEnabled",
"shortDescription": "Video Stream Enabled",
"longDescription": "Start/Stop Video Stream.",
"type": "bool",
"defaultValue": true
},
{
"name": "DisableWhenDisarmed",
"shortDescription": "Video Stream Disnabled When Armed",
"longDescription": "Disable Video Stream when disarmed.",
"type": "bool",
"defaultValue": false
} }
] ]
...@@ -30,6 +30,8 @@ const char* VideoSettings::recordingFormatName = "RecordingFormat"; ...@@ -30,6 +30,8 @@ const char* VideoSettings::recordingFormatName = "RecordingFormat";
const char* VideoSettings::maxVideoSizeName = "MaxVideoSize"; const char* VideoSettings::maxVideoSizeName = "MaxVideoSize";
const char* VideoSettings::enableStorageLimitName = "EnableStorageLimit"; const char* VideoSettings::enableStorageLimitName = "EnableStorageLimit";
const char* VideoSettings::rtspTimeoutName = "RtspTimeout"; const char* VideoSettings::rtspTimeoutName = "RtspTimeout";
const char* VideoSettings::streamEnabledName = "StreamEnabled";
const char* VideoSettings::disableWhenDisarmedName ="DisableWhenDisarmed";
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";
...@@ -50,6 +52,8 @@ VideoSettings::VideoSettings(QObject* parent) ...@@ -50,6 +52,8 @@ VideoSettings::VideoSettings(QObject* parent)
, _maxVideoSizeFact(NULL) , _maxVideoSizeFact(NULL)
, _enableStorageLimitFact(NULL) , _enableStorageLimitFact(NULL)
, _rtspTimeoutFact(NULL) , _rtspTimeoutFact(NULL)
, _streamEnabledFact(NULL)
, _disableWhenDisarmedFact(NULL)
{ {
QQmlEngine::setObjectOwnership(this, QQmlEngine::CppOwnership); QQmlEngine::setObjectOwnership(this, QQmlEngine::CppOwnership);
qmlRegisterUncreatableType<VideoSettings>("QGroundControl.SettingsManager", 1, 0, "VideoSettings", "Reference only"); qmlRegisterUncreatableType<VideoSettings>("QGroundControl.SettingsManager", 1, 0, "VideoSettings", "Reference only");
...@@ -94,8 +98,8 @@ Fact* VideoSettings::videoSource(void) ...@@ -94,8 +98,8 @@ Fact* VideoSettings::videoSource(void)
{ {
if (!_videoSourceFact) { if (!_videoSourceFact) {
_videoSourceFact = _createSettingsFact(videoSourceName); _videoSourceFact = _createSettingsFact(videoSourceName);
connect(_videoSourceFact, &Fact::valueChanged, this, &VideoSettings::_configChanged);
} }
return _videoSourceFact; return _videoSourceFact;
} }
...@@ -103,8 +107,8 @@ Fact* VideoSettings::udpPort(void) ...@@ -103,8 +107,8 @@ Fact* VideoSettings::udpPort(void)
{ {
if (!_udpPortFact) { if (!_udpPortFact) {
_udpPortFact = _createSettingsFact(udpPortName); _udpPortFact = _createSettingsFact(udpPortName);
connect(_udpPortFact, &Fact::valueChanged, this, &VideoSettings::_configChanged);
} }
return _udpPortFact; return _udpPortFact;
} }
...@@ -112,8 +116,8 @@ Fact* VideoSettings::rtspUrl(void) ...@@ -112,8 +116,8 @@ Fact* VideoSettings::rtspUrl(void)
{ {
if (!_rtspUrlFact) { if (!_rtspUrlFact) {
_rtspUrlFact = _createSettingsFact(rtspUrlName); _rtspUrlFact = _createSettingsFact(rtspUrlName);
connect(_rtspUrlFact, &Fact::valueChanged, this, &VideoSettings::_configChanged);
} }
return _rtspUrlFact; return _rtspUrlFact;
} }
...@@ -121,8 +125,8 @@ Fact* VideoSettings::tcpUrl(void) ...@@ -121,8 +125,8 @@ Fact* VideoSettings::tcpUrl(void)
{ {
if (!_tcpUrlFact) { if (!_tcpUrlFact) {
_tcpUrlFact = _createSettingsFact(tcpUrlName); _tcpUrlFact = _createSettingsFact(tcpUrlName);
connect(_tcpUrlFact, &Fact::valueChanged, this, &VideoSettings::_configChanged);
} }
return _tcpUrlFact; return _tcpUrlFact;
} }
...@@ -131,7 +135,6 @@ Fact* VideoSettings::aspectRatio(void) ...@@ -131,7 +135,6 @@ Fact* VideoSettings::aspectRatio(void)
if (!_videoAspectRatioFact) { if (!_videoAspectRatioFact) {
_videoAspectRatioFact = _createSettingsFact(videoAspectRatioName); _videoAspectRatioFact = _createSettingsFact(videoAspectRatioName);
} }
return _videoAspectRatioFact; return _videoAspectRatioFact;
} }
...@@ -140,7 +143,6 @@ Fact* VideoSettings::gridLines(void) ...@@ -140,7 +143,6 @@ Fact* VideoSettings::gridLines(void)
if (!_gridLinesFact) { if (!_gridLinesFact) {
_gridLinesFact = _createSettingsFact(videoGridLinesName); _gridLinesFact = _createSettingsFact(videoGridLinesName);
} }
return _gridLinesFact; return _gridLinesFact;
} }
...@@ -149,7 +151,6 @@ Fact* VideoSettings::showRecControl(void) ...@@ -149,7 +151,6 @@ Fact* VideoSettings::showRecControl(void)
if (!_showRecControlFact) { if (!_showRecControlFact) {
_showRecControlFact = _createSettingsFact(showRecControlName); _showRecControlFact = _createSettingsFact(showRecControlName);
} }
return _showRecControlFact; return _showRecControlFact;
} }
...@@ -158,7 +159,6 @@ Fact* VideoSettings::recordingFormat(void) ...@@ -158,7 +159,6 @@ Fact* VideoSettings::recordingFormat(void)
if (!_recordingFormatFact) { if (!_recordingFormatFact) {
_recordingFormatFact = _createSettingsFact(recordingFormatName); _recordingFormatFact = _createSettingsFact(recordingFormatName);
} }
return _recordingFormatFact; return _recordingFormatFact;
} }
...@@ -167,7 +167,6 @@ Fact* VideoSettings::maxVideoSize(void) ...@@ -167,7 +167,6 @@ Fact* VideoSettings::maxVideoSize(void)
if (!_maxVideoSizeFact) { if (!_maxVideoSizeFact) {
_maxVideoSizeFact = _createSettingsFact(maxVideoSizeName); _maxVideoSizeFact = _createSettingsFact(maxVideoSizeName);
} }
return _maxVideoSizeFact; return _maxVideoSizeFact;
} }
...@@ -176,7 +175,6 @@ Fact* VideoSettings::enableStorageLimit(void) ...@@ -176,7 +175,6 @@ Fact* VideoSettings::enableStorageLimit(void)
if (!_enableStorageLimitFact) { if (!_enableStorageLimitFact) {
_enableStorageLimitFact = _createSettingsFact(enableStorageLimitName); _enableStorageLimitFact = _createSettingsFact(enableStorageLimitName);
} }
return _enableStorageLimitFact; return _enableStorageLimitFact;
} }
...@@ -185,6 +183,50 @@ Fact* VideoSettings::rtspTimeout(void) ...@@ -185,6 +183,50 @@ Fact* VideoSettings::rtspTimeout(void)
if (!_rtspTimeoutFact) { if (!_rtspTimeoutFact) {
_rtspTimeoutFact = _createSettingsFact(rtspTimeoutName); _rtspTimeoutFact = _createSettingsFact(rtspTimeoutName);
} }
return _rtspTimeoutFact; return _rtspTimeoutFact;
} }
Fact* VideoSettings::streamEnabled(void)
{
if (!_streamEnabledFact) {
_streamEnabledFact = _createSettingsFact(streamEnabledName);
}
return _streamEnabledFact;
}
Fact* VideoSettings::disableWhenDisarmed(void)
{
if (!_disableWhenDisarmedFact) {
_disableWhenDisarmedFact = _createSettingsFact(disableWhenDisarmedName);
}
return _disableWhenDisarmedFact;
}
bool VideoSettings::streamConfigured(void)
{
#if !defined(QGC_GST_STREAMING)
return false;
#endif
QString vSource = videoSource()->rawValue().toString();
if(vSource == videoSourceNoVideo || vSource == videoDisabled) {
return false;
}
//-- If UDP, check if port is set
if(vSource == videoSourceUDP) {
return udpPort()->rawValue().toInt() != 0;
}
//-- If RTSP, check for URL
if(vSource == videoSourceRTSP) {
return !rtspUrl()->rawValue().toString().isEmpty();
}
//-- If TCP, check for URL
if(vSource == videoSourceTCP) {
return !tcpUrl()->rawValue().toString().isEmpty();
}
return false;
}
void VideoSettings::_configChanged(QVariant)
{
emit streamConfiguredChanged();
}
...@@ -19,29 +19,35 @@ class VideoSettings : public SettingsGroup ...@@ -19,29 +19,35 @@ class VideoSettings : public SettingsGroup
public: public:
VideoSettings(QObject* parent = NULL); VideoSettings(QObject* parent = NULL);
Q_PROPERTY(Fact* videoSource READ videoSource CONSTANT) Q_PROPERTY(Fact* videoSource READ videoSource CONSTANT)
Q_PROPERTY(Fact* udpPort READ udpPort CONSTANT) Q_PROPERTY(Fact* udpPort READ udpPort CONSTANT)
Q_PROPERTY(Fact* tcpUrl READ tcpUrl CONSTANT) Q_PROPERTY(Fact* tcpUrl READ tcpUrl CONSTANT)
Q_PROPERTY(Fact* rtspUrl READ rtspUrl CONSTANT) Q_PROPERTY(Fact* rtspUrl READ rtspUrl CONSTANT)
Q_PROPERTY(Fact* aspectRatio READ aspectRatio CONSTANT) Q_PROPERTY(Fact* aspectRatio READ aspectRatio CONSTANT)
Q_PROPERTY(Fact* gridLines READ gridLines CONSTANT) Q_PROPERTY(Fact* gridLines READ gridLines CONSTANT)
Q_PROPERTY(Fact* showRecControl READ showRecControl CONSTANT) Q_PROPERTY(Fact* showRecControl READ showRecControl CONSTANT)
Q_PROPERTY(Fact* recordingFormat READ recordingFormat CONSTANT) Q_PROPERTY(Fact* recordingFormat READ recordingFormat CONSTANT)
Q_PROPERTY(Fact* maxVideoSize READ maxVideoSize CONSTANT) Q_PROPERTY(Fact* maxVideoSize READ maxVideoSize CONSTANT)
Q_PROPERTY(Fact* enableStorageLimit READ enableStorageLimit CONSTANT) Q_PROPERTY(Fact* enableStorageLimit READ enableStorageLimit CONSTANT)
Q_PROPERTY(Fact* rtspTimeout READ rtspTimeout CONSTANT) Q_PROPERTY(Fact* rtspTimeout READ rtspTimeout CONSTANT)
Q_PROPERTY(Fact* streamEnabled READ streamEnabled CONSTANT)
Q_PROPERTY(Fact* disableWhenDisarmed READ disableWhenDisarmed CONSTANT)
Q_PROPERTY(bool streamConfigured READ streamConfigured NOTIFY streamConfiguredChanged)
Fact* videoSource (void); Fact* videoSource (void);
Fact* udpPort (void); Fact* udpPort (void);
Fact* rtspUrl (void); Fact* rtspUrl (void);
Fact* tcpUrl (void); Fact* tcpUrl (void);
Fact* aspectRatio (void); Fact* aspectRatio (void);
Fact* gridLines (void); Fact* gridLines (void);
Fact* showRecControl (void); Fact* showRecControl (void);
Fact* recordingFormat (void); Fact* recordingFormat (void);
Fact* maxVideoSize (void); Fact* maxVideoSize (void);
Fact* enableStorageLimit(void); Fact* enableStorageLimit (void);
Fact* rtspTimeout (void); Fact* rtspTimeout (void);
Fact* streamEnabled (void);
Fact* disableWhenDisarmed (void);
bool streamConfigured (void);
static const char* videoSettingsGroupName; static const char* videoSettingsGroupName;
...@@ -56,6 +62,8 @@ public: ...@@ -56,6 +62,8 @@ public:
static const char* maxVideoSizeName; static const char* maxVideoSizeName;
static const char* enableStorageLimitName; static const char* enableStorageLimitName;
static const char* rtspTimeoutName; static const char* rtspTimeoutName;
static const char* streamEnabledName;
static const char* disableWhenDisarmedName;
static const char* videoSourceNoVideo; static const char* videoSourceNoVideo;
static const char* videoDisabled; static const char* videoDisabled;
...@@ -63,6 +71,12 @@ public: ...@@ -63,6 +71,12 @@ public:
static const char* videoSourceRTSP; static const char* videoSourceRTSP;
static const char* videoSourceTCP; static const char* videoSourceTCP;
signals:
void streamConfiguredChanged ();
private slots:
void _configChanged (QVariant value);
private: private:
SettingsFact* _videoSourceFact; SettingsFact* _videoSourceFact;
SettingsFact* _udpPortFact; SettingsFact* _udpPortFact;
...@@ -75,6 +89,8 @@ private: ...@@ -75,6 +89,8 @@ private:
SettingsFact* _maxVideoSizeFact; SettingsFact* _maxVideoSizeFact;
SettingsFact* _enableStorageLimitFact; SettingsFact* _enableStorageLimitFact;
SettingsFact* _rtspTimeoutFact; SettingsFact* _rtspTimeoutFact;
SettingsFact* _streamEnabledFact;
SettingsFact* _disableWhenDisarmedFact;
}; };
#endif #endif
...@@ -33,6 +33,8 @@ ...@@ -33,6 +33,8 @@
#include "QGCCorePlugin.h" #include "QGCCorePlugin.h"
#include "ADSBVehicle.h" #include "ADSBVehicle.h"
#include "QGCCameraManager.h" #include "QGCCameraManager.h"
#include "VideoReceiver.h"
#include "VideoManager.h"
QGC_LOGGING_CATEGORY(VehicleLog, "VehicleLog") QGC_LOGGING_CATEGORY(VehicleLog, "VehicleLog")
...@@ -1121,6 +1123,11 @@ void Vehicle::_handleHeartbeat(mavlink_message_t& message) ...@@ -1121,6 +1123,11 @@ void Vehicle::_handleHeartbeat(mavlink_message_t& message)
_clearCameraTriggerPoints(); _clearCameraTriggerPoints();
} else { } else {
_mapTrajectoryStop(); _mapTrajectoryStop();
// Also handle Video Streaming
if(_settingsManager->videoSettings()->disableWhenDisarmed()->rawValue().toBool()) {
_settingsManager->videoSettings()->streamEnabled()->setRawValue(false);
qgcApp()->toolbox()->videoManager()->videoReceiver()->stop();
}
} }
} }
......
...@@ -67,8 +67,10 @@ VideoReceiver::VideoReceiver(QObject* parent) ...@@ -67,8 +67,10 @@ VideoReceiver::VideoReceiver(QObject* parent)
, _videoSurface(NULL) , _videoSurface(NULL)
, _videoRunning(false) , _videoRunning(false)
, _showFullScreen(false) , _showFullScreen(false)
, _videoSettings(NULL)
{ {
_videoSurface = new VideoSurface; _videoSurface = new VideoSurface;
_videoSettings = qgcApp()->toolbox()->settingsManager()->videoSettings();
#if defined(QGC_GST_STREAMING) #if defined(QGC_GST_STREAMING)
_setVideoSink(_videoSurface->videoSink()); _setVideoSink(_videoSurface->videoSink());
_timer.setSingleShot(true); _timer.setSingleShot(true);
...@@ -147,8 +149,10 @@ VideoReceiver::_connected() ...@@ -147,8 +149,10 @@ VideoReceiver::_connected()
_timer.stop(); _timer.stop();
_socket->deleteLater(); _socket->deleteLater();
_socket = NULL; _socket = NULL;
_serverPresent = true; if(_videoSettings->streamEnabled()->rawValue().toBool()) {
start(); _serverPresent = true;
start();
}
} }
#endif #endif
...@@ -161,7 +165,9 @@ VideoReceiver::_socketError(QAbstractSocket::SocketError socketError) ...@@ -161,7 +165,9 @@ VideoReceiver::_socketError(QAbstractSocket::SocketError socketError)
_socket->deleteLater(); _socket->deleteLater();
_socket = NULL; _socket = NULL;
//-- Try again in 5 seconds //-- Try again in 5 seconds
_timer.start(5000); if(_videoSettings->streamEnabled()->rawValue().toBool()) {
_timer.start(5000);
}
} }
#endif #endif
...@@ -175,18 +181,19 @@ VideoReceiver::_timeout() ...@@ -175,18 +181,19 @@ VideoReceiver::_timeout()
delete _socket; delete _socket;
_socket = NULL; _socket = NULL;
} }
//-- RTSP will try to connect to the server. If it cannot connect, if(_videoSettings->streamEnabled()->rawValue().toBool()) {
// it will simply give up and never try again. Instead, we keep //-- RTSP will try to connect to the server. If it cannot connect,
// attempting a connection on this timer. Once a connection is // it will simply give up and never try again. Instead, we keep
// found to be working, only then we actually start the stream. // attempting a connection on this timer. Once a connection is
QUrl url(_uri); // found to be working, only then we actually start the stream.
_socket = new QTcpSocket; QUrl url(_uri);
_socket->setProxy(QNetworkProxy::NoProxy); _socket = new QTcpSocket;
connect(_socket, static_cast<void (QTcpSocket::*)(QAbstractSocket::SocketError)>(&QTcpSocket::error), this, &VideoReceiver::_socketError); _socket->setProxy(QNetworkProxy::NoProxy);
connect(_socket, &QTcpSocket::connected, this, &VideoReceiver::_connected); connect(_socket, static_cast<void (QTcpSocket::*)(QAbstractSocket::SocketError)>(&QTcpSocket::error), this, &VideoReceiver::_socketError);
//qCDebug(VideoReceiverLog) << "Trying to connect to:" << url.host() << url.port(); connect(_socket, &QTcpSocket::connected, this, &VideoReceiver::_connected);
_socket->connectToHost(url.host(), url.port()); _socket->connectToHost(url.host(), url.port());
_timer.start(5000); _timer.start(5000);
}
} }
#endif #endif
...@@ -203,6 +210,11 @@ VideoReceiver::_timeout() ...@@ -203,6 +210,11 @@ VideoReceiver::_timeout()
void void
VideoReceiver::start() VideoReceiver::start()
{ {
if(!_videoSettings->streamEnabled()->rawValue().toBool() ||
!_videoSettings->streamConfigured()) {
qCDebug(VideoReceiverLog) << "start() but not enabled/configured";
return;
}
#if defined(QGC_GST_STREAMING) #if defined(QGC_GST_STREAMING)
qCDebug(VideoReceiverLog) << "start()"; qCDebug(VideoReceiverLog) << "start()";
...@@ -550,7 +562,7 @@ void ...@@ -550,7 +562,7 @@ void
VideoReceiver::_cleanupOldVideos() VideoReceiver::_cleanupOldVideos()
{ {
//-- Only perform cleanup if storage limit is enabled //-- Only perform cleanup if storage limit is enabled
if(qgcApp()->toolbox()->settingsManager()->videoSettings()->enableStorageLimit()->rawValue().toBool()) { if(_videoSettings->enableStorageLimit()->rawValue().toBool()) {
QString savePath = qgcApp()->toolbox()->settingsManager()->appSettings()->videoSavePath(); QString savePath = qgcApp()->toolbox()->settingsManager()->appSettings()->videoSavePath();
QDir videoDir = QDir(savePath); QDir videoDir = QDir(savePath);
videoDir.setFilter(QDir::Files | QDir::Readable | QDir::NoSymLinks | QDir::Writable); videoDir.setFilter(QDir::Files | QDir::Readable | QDir::NoSymLinks | QDir::Writable);
...@@ -566,7 +578,7 @@ VideoReceiver::_cleanupOldVideos() ...@@ -566,7 +578,7 @@ VideoReceiver::_cleanupOldVideos()
if(!vidList.isEmpty()) { if(!vidList.isEmpty()) {
uint64_t total = 0; uint64_t total = 0;
//-- Settings are stored using MB //-- Settings are stored using MB
uint64_t maxSize = (qgcApp()->toolbox()->settingsManager()->videoSettings()->maxVideoSize()->rawValue().toUInt() * 1024 * 1024); uint64_t maxSize = (_videoSettings->maxVideoSize()->rawValue().toUInt() * 1024 * 1024);
//-- Compute total used storage //-- Compute total used storage
for(int i = 0; i < vidList.size(); i++) { for(int i = 0; i < vidList.size(); i++) {
total += vidList[i].size(); total += vidList[i].size();
...@@ -614,7 +626,7 @@ VideoReceiver::startRecording(void) ...@@ -614,7 +626,7 @@ VideoReceiver::startRecording(void)
return; return;
} }
uint32_t muxIdx = qgcApp()->toolbox()->settingsManager()->videoSettings()->recordingFormat()->rawValue().toUInt(); uint32_t muxIdx = _videoSettings->recordingFormat()->rawValue().toUInt();
if(muxIdx >= NUM_MUXES) { if(muxIdx >= NUM_MUXES) {
qgcApp()->showMessage(tr("Invalid video format defined.")); qgcApp()->showMessage(tr("Invalid video format defined."));
return; return;
...@@ -803,7 +815,7 @@ VideoReceiver::_updateTimer() ...@@ -803,7 +815,7 @@ VideoReceiver::_updateTimer()
if(_videoRunning) { if(_videoRunning) {
uint32_t timeout = 1; uint32_t timeout = 1;
if(qgcApp()->toolbox() && qgcApp()->toolbox()->settingsManager()) { if(qgcApp()->toolbox() && qgcApp()->toolbox()->settingsManager()) {
timeout = qgcApp()->toolbox()->settingsManager()->videoSettings()->rtspTimeout()->rawValue().toUInt(); timeout = _videoSettings->rtspTimeout()->rawValue().toUInt();
} }
time_t elapsed = 0; time_t elapsed = 0;
time_t lastFrame = _videoSurface->lastFrame(); time_t lastFrame = _videoSurface->lastFrame();
...@@ -814,7 +826,7 @@ VideoReceiver::_updateTimer() ...@@ -814,7 +826,7 @@ VideoReceiver::_updateTimer()
stop(); stop();
} }
} else { } else {
if(!running() && !_uri.isEmpty()) { if(!running() && !_uri.isEmpty() && _videoSettings->streamEnabled()->rawValue().toBool()) {
start(); start();
} }
} }
......
...@@ -30,6 +30,8 @@ ...@@ -30,6 +30,8 @@
Q_DECLARE_LOGGING_CATEGORY(VideoReceiverLog) Q_DECLARE_LOGGING_CATEGORY(VideoReceiverLog)
class VideoSettings;
class VideoReceiver : public QObject class VideoReceiver : public QObject
{ {
Q_OBJECT Q_OBJECT
...@@ -38,9 +40,9 @@ public: ...@@ -38,9 +40,9 @@ public:
Q_PROPERTY(bool recording READ recording NOTIFY recordingChanged) Q_PROPERTY(bool recording READ recording NOTIFY recordingChanged)
#endif #endif
Q_PROPERTY(VideoSurface* videoSurface READ videoSurface CONSTANT) Q_PROPERTY(VideoSurface* videoSurface READ videoSurface CONSTANT)
Q_PROPERTY(bool videoRunning READ videoRunning NOTIFY videoRunningChanged) Q_PROPERTY(bool videoRunning READ videoRunning NOTIFY videoRunningChanged)
Q_PROPERTY(QString imageFile READ imageFile NOTIFY imageFileChanged) Q_PROPERTY(QString imageFile READ imageFile NOTIFY imageFileChanged)
Q_PROPERTY(bool showFullScreen READ showFullScreen WRITE setShowFullScreen NOTIFY showFullScreenChanged) Q_PROPERTY(bool showFullScreen READ showFullScreen WRITE setShowFullScreen NOTIFY showFullScreenChanged)
explicit VideoReceiver(QObject* parent = 0); explicit VideoReceiver(QObject* parent = 0);
~VideoReceiver(); ~VideoReceiver();
...@@ -57,6 +59,7 @@ public: ...@@ -57,6 +59,7 @@ public:
bool videoRunning () { return _videoRunning; } bool videoRunning () { return _videoRunning; }
QString imageFile () { return _imageFile; } QString imageFile () { return _imageFile; }
bool showFullScreen () { return _showFullScreen; } bool showFullScreen () { return _showFullScreen; }
void grabImage (QString imageFile); void grabImage (QString imageFile);
void setShowFullScreen (bool show) { _showFullScreen = show; emit showFullScreenChanged(); } void setShowFullScreen (bool show) { _showFullScreen = show; emit showFullScreenChanged(); }
...@@ -136,7 +139,7 @@ private: ...@@ -136,7 +139,7 @@ private:
VideoSurface* _videoSurface; VideoSurface* _videoSurface;
bool _videoRunning; bool _videoRunning;
bool _showFullScreen; bool _showFullScreen;
VideoSettings* _videoSettings;
}; };
#endif // VIDEORECEIVER_H #endif // VIDEORECEIVER_H
...@@ -39,6 +39,7 @@ public: ...@@ -39,6 +39,7 @@ public:
, defaultOptions (NULL) , defaultOptions (NULL)
, valuesPageWidgetInfo (NULL) , valuesPageWidgetInfo (NULL)
, cameraPageWidgetInfo (NULL) , cameraPageWidgetInfo (NULL)
, videoPageWidgetInfo (NULL)
, healthPageWidgetInfo (NULL) , healthPageWidgetInfo (NULL)
, vibrationPageWidgetInfo (NULL) , vibrationPageWidgetInfo (NULL)
{ {
...@@ -80,6 +81,7 @@ public: ...@@ -80,6 +81,7 @@ public:
QmlComponentInfo* valuesPageWidgetInfo; QmlComponentInfo* valuesPageWidgetInfo;
QmlComponentInfo* cameraPageWidgetInfo; QmlComponentInfo* cameraPageWidgetInfo;
QmlComponentInfo* videoPageWidgetInfo;
QmlComponentInfo* healthPageWidgetInfo; QmlComponentInfo* healthPageWidgetInfo;
QmlComponentInfo* vibrationPageWidgetInfo; QmlComponentInfo* vibrationPageWidgetInfo;
QVariantList instrumentPageWidgetList; QVariantList instrumentPageWidgetList;
...@@ -148,13 +150,19 @@ QVariantList &QGCCorePlugin::settingsPages() ...@@ -148,13 +150,19 @@ QVariantList &QGCCorePlugin::settingsPages()
QVariantList& QGCCorePlugin::instrumentPages(void) QVariantList& QGCCorePlugin::instrumentPages(void)
{ {
if (!_p->valuesPageWidgetInfo) { if (!_p->valuesPageWidgetInfo) {
_p->valuesPageWidgetInfo = new QmlComponentInfo(tr("Values"), QUrl::fromUserInput("qrc:/qml/ValuePageWidget.qml")); _p->valuesPageWidgetInfo = new QmlComponentInfo(tr("Values"), QUrl::fromUserInput("qrc:/qml/ValuePageWidget.qml"));
_p->cameraPageWidgetInfo = new QmlComponentInfo(tr("Camera"), QUrl::fromUserInput("qrc:/qml/CameraPageWidget.qml")); _p->cameraPageWidgetInfo = new QmlComponentInfo(tr("Camera"), QUrl::fromUserInput("qrc:/qml/CameraPageWidget.qml"));
_p->healthPageWidgetInfo = new QmlComponentInfo(tr("Health"), QUrl::fromUserInput("qrc:/qml/HealthPageWidget.qml")); #if defined(QGC_GST_STREAMING)
_p->videoPageWidgetInfo = new QmlComponentInfo(tr("Video Stream"), QUrl::fromUserInput("qrc:/qml/VideoPageWidget.qml"));
#endif
_p->healthPageWidgetInfo = new QmlComponentInfo(tr("Health"), QUrl::fromUserInput("qrc:/qml/HealthPageWidget.qml"));
_p->vibrationPageWidgetInfo = new QmlComponentInfo(tr("Vibration"), QUrl::fromUserInput("qrc:/qml/VibrationPageWidget.qml")); _p->vibrationPageWidgetInfo = new QmlComponentInfo(tr("Vibration"), QUrl::fromUserInput("qrc:/qml/VibrationPageWidget.qml"));
_p->instrumentPageWidgetList.append(QVariant::fromValue(_p->valuesPageWidgetInfo)); _p->instrumentPageWidgetList.append(QVariant::fromValue(_p->valuesPageWidgetInfo));
_p->instrumentPageWidgetList.append(QVariant::fromValue(_p->cameraPageWidgetInfo)); _p->instrumentPageWidgetList.append(QVariant::fromValue(_p->cameraPageWidgetInfo));
#if defined(QGC_GST_STREAMING)
_p->instrumentPageWidgetList.append(QVariant::fromValue(_p->videoPageWidgetInfo));
#endif
_p->instrumentPageWidgetList.append(QVariant::fromValue(_p->healthPageWidgetInfo)); _p->instrumentPageWidgetList.append(QVariant::fromValue(_p->healthPageWidgetInfo));
_p->instrumentPageWidgetList.append(QVariant::fromValue(_p->vibrationPageWidgetInfo)); _p->instrumentPageWidgetList.append(QVariant::fromValue(_p->vibrationPageWidgetInfo));
} }
......
...@@ -37,7 +37,7 @@ QGCView { ...@@ -37,7 +37,7 @@ QGCView {
property Fact _appFontPointSize: QGroundControl.settingsManager.appSettings.appFontPointSize property Fact _appFontPointSize: QGroundControl.settingsManager.appSettings.appFontPointSize
property Fact _userBrandImageIndoor: QGroundControl.settingsManager.brandImageSettings.userBrandImageIndoor property Fact _userBrandImageIndoor: QGroundControl.settingsManager.brandImageSettings.userBrandImageIndoor
property Fact _userBrandImageOutdoor: QGroundControl.settingsManager.brandImageSettings.userBrandImageOutdoor property Fact _userBrandImageOutdoor: QGroundControl.settingsManager.brandImageSettings.userBrandImageOutdoor
property real _labelWidth: ScreenTools.defaultFontPixelWidth * 15 property real _labelWidth: ScreenTools.defaultFontPixelWidth * 20
property real _editFieldWidth: ScreenTools.defaultFontPixelWidth * 30 property real _editFieldWidth: ScreenTools.defaultFontPixelWidth * 30
property Fact _mapProvider: QGroundControl.settingsManager.flightMapSettings.mapProvider property Fact _mapProvider: QGroundControl.settingsManager.flightMapSettings.mapProvider
property Fact _mapType: QGroundControl.settingsManager.flightMapSettings.mapType property Fact _mapType: QGroundControl.settingsManager.flightMapSettings.mapType
...@@ -590,13 +590,13 @@ QGCView { ...@@ -590,13 +590,13 @@ QGCView {
spacing: ScreenTools.defaultFontPixelWidth spacing: ScreenTools.defaultFontPixelWidth
visible: QGroundControl.videoManager.isGStreamer && videoSource.currentIndex && videoSource.currentIndex < 3 && QGroundControl.settingsManager.videoSettings.gridLines.visible visible: QGroundControl.videoManager.isGStreamer && videoSource.currentIndex && videoSource.currentIndex < 3 && QGroundControl.settingsManager.videoSettings.gridLines.visible
QGCLabel { QGCLabel {
text: qsTr("Grid Lines:") text: qsTr("Disable When Disarmed:")
width: _labelWidth width: _labelWidth
anchors.verticalCenter: parent.verticalCenter anchors.verticalCenter: parent.verticalCenter
} }
FactComboBox { FactCheckBox {
width: _editFieldWidth text: ""
fact: QGroundControl.settingsManager.videoSettings.gridLines fact: QGroundControl.settingsManager.videoSettings.disableWhenDisarmed
anchors.verticalCenter: parent.verticalCenter anchors.verticalCenter: parent.verticalCenter
} }
} }
......
Markdown is supported
0% or
You are about to add 0 people to the discussion. Proceed with caution.
Finish editing this message first!
Please register or to comment