Unverified Commit 76b58cbc authored by Don Gagne's avatar Don Gagne Committed by GitHub

Merge pull request #9007 from DonLakeFlyer/VideoStreaming

Video Streaming: Camera ui allows switch to photo mode to capture individual images from stream
parents a688855e 138d683a
......@@ -4,6 +4,7 @@ Note: This file only contains high level features or important fixes.
## 4.1 - Daily build
* Video Streaming: New camera control supports capturing individual images from the stream
* Fly: Press and hold on arm button will change it to Force Arm. Click again to force arm.
* VTOL: General setting for transition distance which affects Plan takeoff, landing pattern creation
* VTOL: Much better VTOL support throughout QGC
......
......@@ -387,10 +387,7 @@ QGCCameraControl::takePhoto()
_captureInfoRetries = 0;
//-- Capture local image as well
if(qgcApp()->toolbox()->videoManager()) {
QString photoPath = qgcApp()->toolbox()->settingsManager()->appSettings()->savePath()->rawValue().toString() + QStringLiteral("/Photo");
QDir().mkpath(photoPath);
photoPath += + "/" + QDateTime::currentDateTime().toString("yyyy-MM-dd_hh.mm.ss.zzz") + ".jpg";
qgcApp()->toolbox()->videoManager()->grabImage(photoPath);
qgcApp()->toolbox()->videoManager()->grabImage();
}
return true;
}
......
......@@ -27,39 +27,103 @@ Rectangle {
height: mainLayout.height + (_margins * 2)
color: "#80000000"
radius: _margins
visible: !QGroundControl.settingsManager.flyViewSettings.alternateInstrumentPanel.rawValue && (_camera || _anyVideoStreamAvailable) && multiVehiclePanelSelector.showSingleVehiclePanel
property real _margins: ScreenTools.defaultFontPixelHeight / 2
property var _activeVehicle: QGroundControl.multiVehicleManager.activeVehicle
property var _cameraManager: _activeVehicle ? _activeVehicle.cameraManager : null
property var _videoManager: QGroundControl.videoManager
property bool _noCameras: _cameraManager ? _cameraManager.cameras.count === 0 : true
property bool _multipleCameras: _cameraManager ? _cameraManager.cameras.count > 1 : false
property bool _noMavlinkCameraStreams: _camera ? _camera.streamLabels.length : true
property bool _multipleMavlinkCameraStreams: _camera ? _camera.streamLabels.length > 1 : false
property bool _anyVideoStreamAvailable: _videoManager.hasVideo
property int _curCameraIndex: _cameraManager ? _cameraManager.currentCamera : -1
property int _curStreamIndex: _camera ? _camera.currentStream : -1
property var _camera: !_noCameras ? (_cameraManager.cameras.get(_curCameraIndex) && _cameraManager.cameras.get(_curCameraIndex).paramComplete ? _cameraManager.cameras.get(_curCameraIndex) : null) : null
property string _cameraName: _camera ? (_multipleCameras ? _camera.modelName : "") : qsTr("Video Stream")
property bool _hasThermalVideoStream: _camera ? _camera.thermalStreamInstance : false
property bool _cameraModeUndefined: _camera ? _camera.cameraMode === QGCCameraControl.CAM_MODE_UNDEFINED : true
property bool _cameraInVideoMode: _camera ? _camera.cameraMode === QGCCameraControl.CAM_MODE_VIDEO : false
property bool _cameraInPhotoMode: _camera ? _camera.cameraMode === QGCCameraControl.CAM_MODE_PHOTO : false
property bool _cameraElapsedMode: _camera && _camera.cameraMode === QGCCameraControl.CAM_MODE_PHOTO && _camera.photoMode === QGCCameraControl.PHOTO_CAPTURE_TIMELAPSE
property real _spacers: ScreenTools.defaultFontPixelHeight * 0.5
property real _labelFieldWidth: ScreenTools.defaultFontPixelWidth * 30
property real _editFieldWidth: ScreenTools.defaultFontPixelWidth * 30
property bool _communicationLost: _activeVehicle ? _activeVehicle.connectionLost : false
property bool _hasModes: _camera && _camera.hasModes
property bool _videoRecording: _camera && _camera.videoStatus === QGCCameraControl.VIDEO_CAPTURE_STATUS_RUNNING
property bool _photoIdle: _camera && (_camera.photoStatus === QGCCameraControl.PHOTO_CAPTURE_IDLE || _camera.photoStatus >= QGCCameraControl.PHOTO_CAPTURE_LAST)
property bool _storageReady: _camera && _camera.storageStatus === QGCCameraControl.STORAGE_READY
property bool _batteryReady: _camera && _camera.batteryRemaining >= 0
property bool _storageSupported: _camera && _camera.storageStatus === QGCCameraControl.STORAGE_NOT_SUPPORTED
property bool _canShoot: (!_cameraModeUndefined && ((_storageReady && _camera.storageFree > 0) || _storageSupported)) || _videoManager.streaming
property bool _isShooting: ((_cameraInVideoMode && _videoRecording) || (_cameraInPhotoMode && !_photoIdle)) || _videoManager.recording
property var _videoSettings: QGroundControl.settingsManager.videoSettings
visible: !QGroundControl.settingsManager.flyViewSettings.alternateInstrumentPanel.rawValue && (_mavlinkCamera || _videoStreamAvailable) && multiVehiclePanelSelector.showSingleVehiclePanel
property real _margins: ScreenTools.defaultFontPixelHeight / 2
property var _activeVehicle: QGroundControl.multiVehicleManager.activeVehicle
// The following properties relate to a simple video stream
property bool _videoStreamAvailable: _videoStreamManager.hasVideo
property var _videoStreamSettings: QGroundControl.settingsManager.videoSettings
property var _videoStreamManager: QGroundControl.videoManager
property bool _videoStreamAllowsPhotoWhileRecording: true
property bool _videoStreamIsStreaming: _videoStreamManager.streaming
property bool _videoStreamPhotoCaptureIsIdle: true
property bool _videoStreamRecording: _videoStreamManager.recording
property bool _videoStreamCanShoot: _videoStreamIsStreaming
property bool _videoStreamIsShootingInCurrentMode: _videoStreamInPhotoMode ? !_videoStreamPhotoCaptureIsIdle : _videoStreamRecording
property bool _videoStreamInPhotoMode: false
property bool _onlyVideoStreamAvailable: !_mavlinkCamera && _videoStreamManager.hasVideo
// The following properties relate to a mavlink protocol camera
property var _mavlinkCameraManager: _activeVehicle ? _activeVehicle.cameraManager : null
property int _mavlinkCameraManagerCurCameraIndex: _mavlinkCameraManager ? _mavlinkCameraManager.currentCamera : -1
property bool _noMavlinkCameras: _mavlinkCameraManager ? _mavlinkCameraManager.cameras.count === 0 : true
property var _mavlinkCamera: !_noMavlinkCameras ? (_mavlinkCameraManager.cameras.get(_mavlinkCameraManagerCurCameraIndex) && _mavlinkCameraManager.cameras.get(_mavlinkCameraManagerCurCameraIndex).paramComplete ? _mavlinkCameraManager.cameras.get(_mavlinkCameraManagerCurCameraIndex) : null) : null
property bool _multipleMavlinkCameras: _mavlinkCameraManager ? _mavlinkCameraManager.cameras.count > 1 : false
property bool _noMavlinkCameraStreams: _mavlinkCamera ? _mavlinkCamera.streamLabels.length : true
property bool _multipleMavlinkCameraStreams: _mavlinkCamera ? _mavlinkCamera.streamLabels.length > 1 : false
property int _mavlinCameraCurStreamIndex: _mavlinkCamera ? _mavlinkCamera.currentStream : -1
property bool _mavlinkCameraHasThermalVideoStream: _mavlinkCamera ? _mavlinkCamera.thermalStreamInstance : false
property bool _mavlinkCameraModeUndefined: _mavlinkCamera ? _mavlinkCamera.cameraMode === QGCCameraControl.CAM_MODE_UNDEFINED : true
property bool _mavlinkCameraInVideoMode: _mavlinkCamera ? _mavlinkCamera.cameraMode === QGCCameraControl.CAM_MODE_VIDEO : false
property bool _mavlinkCameraInPhotoMode: _mavlinkCamera ? _mavlinkCamera.cameraMode === QGCCameraControl.CAM_MODE_PHOTO : false
property bool _mavlinkCameraElapsedMode: _mavlinkCamera && _mavlinkCamera.cameraMode === QGCCameraControl.CAM_MODE_PHOTO && _mavlinkCamera.photoMode === QGCCameraControl.PHOTO_CAPTURE_TIMELAPSE
property bool _mavlinkCameraHasModes: _mavlinkCamera && _mavlinkCamera.hasModes
property bool _mavlinkCameraVideoIsRecording: _mavlinkCamera && _mavlinkCamera.videoStatus === QGCCameraControl.VIDEO_CAPTURE_STATUS_RUNNING
property bool _mavlinkCameraPhotoCaptureIsIdle: _mavlinkCamera && (_mavlinkCamera.photoStatus === QGCCameraControl.PHOTO_CAPTURE_IDLE || _mavlinkCamera.photoStatus >= QGCCameraControl.PHOTO_CAPTURE_LAST)
property bool _mavlinkCameraStorageReady: _mavlinkCamera && _mavlinkCamera.storageStatus === QGCCameraControl.STORAGE_READY
property bool _mavlinkCameraBatteryReady: _mavlinkCamera && _mavlinkCamera.batteryRemaining >= 0
property bool _mavlinkCameraStorageSupported: _mavlinkCamera && _mavlinkCamera.storageStatus === QGCCameraControl.STORAGE_NOT_SUPPORTED
property bool _mavlinkCameraAllowsPhotoWhileRecording: false
property bool _mavlinkCameraCanShoot: (!_mavlinkCameraModeUndefined && ((_mavlinkCameraStorageReady && _mavlinkCamera.storageFree > 0) || _mavlinkCameraStorageSupported)) || _videoStreamManager.streaming
property bool _mavlinkCameraIsShooting: ((_mavlinkCameraInVideoMode && _mavlinkCameraVideoIsRecording) || (_mavlinkCameraInPhotoMode && !_mavlinkCameraPhotoCaptureIsIdle)) || _videoStreamManager.recording
// The following settings and functions unify between a mavlink camera and a simple video stream for simple access
property bool _anyVideoStreamAvailable: _videoStreamManager.hasVideo
property string _mavlinkCameraName: _mavlinkCamera ? (_multipleMavlinkCameras ? _mavlinkCamera.modelName : "") : qsTr("Video Stream")
property bool _showModeIndicator: _mavlinkCamera ? _mavlinkCameraHasModes : _onlyVideoStreamAvailable
property bool _modeIndicatorPhotoMode: _mavlinkCamera ? _mavlinkCameraInPhotoMode : _videoStreamInPhotoMode
property bool _allowsPhotoWhileRecording: _mavlinkCamera ? _mavlinkCameraAllowsPhotoWhileRecording : _videoStreamAllowsPhotoWhileRecording
property bool _switchToPhotoModeAllowed: !_modeIndicatorPhotoMode && (_mavlinkCamera ? !_mavlinkCameraIsShooting : true)
property bool _switchToVideoModeAllowed: _modeIndicatorPhotoMode && (_mavlinkCamera ? !_mavlinkCameraIsShooting : true)
property bool _videoIsRecording: _mavlinkCamera ? _mavlinkCameraIsShooting : _videoStreamRecording
property bool _canShootInCurrentMode: _mavlinkCamera ? _mavlinkCameraCanShoot : _videoStreamCanShoot
property bool _isShootingInCurrentMode: _mavlinkCamera ? _mavlinkCameraIsShooting : _videoStreamIsShootingInCurrentMode
function setCameraMode(photoMode) {
_videoStreamInPhotoMode = photoMode
if (_mavlinkCamera) {
if (_mavlinkCameraInPhotoMode) {
_mavlinkCamera.setVideoMode()
} else {
_mavlinkCamera.setPhotoMode()
}
}
}
function toggleShooting() {
if (_mavlinkCamera) {
if(_mavlinkCameraInVideoMode) {
_mavlinkCamera.toggleVideo()
} else {
if(_mavlinkCameraInPhotoMode && !_mavlinkCameraPhotoCaptureIsIdle && _mavlinkCameraElapsedMode) {
_mavlinkCamera.stopTakePhoto()
} else {
_mavlinkCamera.takePhoto()
}
}
} else {
if (_videoStreamInPhotoMode) {
_videoStreamPhotoCaptureIsIdle = false
_videoStreamManager.grabImage()
videoStreamPhotoCaptureTimer.start()
} else {
if (_videoStreamManager.recording) {
_videoStreamManager.stopRecording()
} else {
_videoStreamManager.startRecording()
}
}
}
}
Timer {
id: videoStreamPhotoCaptureTimer
interval: 500
onTriggered: _videoStreamPhotoCaptureIsIdle = true
}
QGCPalette { id: qgcPal; colorGroupEnabled: enabled }
......@@ -88,26 +152,28 @@ Rectangle {
anchors.horizontalCenter: parent.horizontalCenter
spacing: ScreenTools.defaultFontPixelHeight / 2
//-- Photo/Video Mode Selector (Mavlink Cameras only)
// Photo/Video Mode Selector
// IMPORTANT: This control supports both mavlink cameras and simple video streams. Do no reference anything here which is not
// using the unified properties/functions.
Rectangle {
id: camMode
Layout.alignment: Qt.AlignHCenter
width: _hasModes ? ScreenTools.defaultFontPixelWidth * 10 : 0
height: _hasModes ? width / 2 : 0
width: ScreenTools.defaultFontPixelWidth * 10
height: width / 2
color: qgcPal.windowShadeLight
radius: height * 0.5
visible: _hasModes
visible: _showModeIndicator
//-- Video Mode
Rectangle {
width: parent.height
height: parent.height
color: _cameraInVideoMode ? qgcPal.window : qgcPal.windowShadeLight
radius: height * 0.5
anchors.left: parent.left
border.color: qgcPal.text
border.width: _cameraInVideoMode ? 1 : 0
anchors.verticalCenter: parent.verticalCenter
width: parent.height
height: parent.height
color: _modeIndicatorPhotoMode ? qgcPal.windowShadeLight : qgcPal.window
radius: height * 0.5
anchors.left: parent.left
border.color: qgcPal.text
border.width: _modeIndicatorPhotoMode ? 0 : 1
QGCColoredImage {
height: parent.height * 0.5
width: height
......@@ -115,26 +181,24 @@ Rectangle {
source: "/qmlimages/camera_video.svg"
fillMode: Image.PreserveAspectFit
sourceSize.height: height
color: _cameraInVideoMode ? qgcPal.colorGreen : qgcPal.text
color: _modeIndicatorPhotoMode ? qgcPal.text : qgcPal.colorGreen
MouseArea {
anchors.fill: parent
enabled: _cameraInPhotoMode && !_isShooting
onClicked: {
_camera.setVideoMode()
}
enabled: _switchToVideoModeAllowed
onClicked: setCameraMode(false)
}
}
}
//-- Photo Mode
Rectangle {
width: parent.height
height: parent.height
color: _cameraInPhotoMode ? qgcPal.window : qgcPal.windowShadeLight
radius: height * 0.5
anchors.right: parent.right
border.color: qgcPal.text
border.width: _cameraInPhotoMode ? 1 : 0
anchors.verticalCenter: parent.verticalCenter
width: parent.height
height: parent.height
color: _modeIndicatorPhotoMode ? qgcPal.window : qgcPal.windowShadeLight
radius: height * 0.5
anchors.right: parent.right
border.color: qgcPal.text
border.width: _modeIndicatorPhotoMode ? 1 : 0
QGCColoredImage {
height: parent.height * 0.5
width: height
......@@ -142,59 +206,40 @@ Rectangle {
source: "/qmlimages/camera_photo.svg"
fillMode: Image.PreserveAspectFit
sourceSize.height: height
color: _cameraInPhotoMode ? qgcPal.colorGreen : qgcPal.text
color: _modeIndicatorPhotoMode ? qgcPal.colorGreen : qgcPal.text
MouseArea {
anchors.fill: parent
enabled: _cameraInVideoMode && !_isShooting
onClicked: {
_camera.setPhotoMode()
}
enabled: _switchToPhotoModeAllowed
onClicked: setCameraMode(true)
}
}
}
}
// Take Photo, Start/Stop Video button
// IMPORTANT: This control supports both mavlink cameras and simple video streams. Do no reference anything here which is not
// using the unified properties/functions.
Rectangle {
Layout.alignment: Qt.AlignHCenter
color: Qt.rgba(0,0,0,0)
width: ScreenTools.defaultFontPixelWidth * 6
height: width
radius: width * 0.5
visible: _camera || _anyVideoStreamAvailable
border.color: qgcPal.buttonText
border.width: 3
Rectangle {
anchors.centerIn: parent
width: parent.width * (_isShooting ? 0.5 : 0.75)
width: parent.width * (_isShootingInCurrentMode ? 0.5 : 0.75)
height: width
radius: _isShooting ? 0 : width * 0.5
color: _canShoot ? qgcPal.colorRed : qgcPal.colorGrey
radius: _isShootingInCurrentMode ? 0 : width * 0.5
color: _canShootInCurrentMode ? qgcPal.colorRed : qgcPal.colorGrey
}
MouseArea {
anchors.fill: parent
enabled: _canShoot
onClicked: {
if (_camera) {
if(_cameraInVideoMode) {
_camera.toggleVideo()
} else {
if(_cameraInPhotoMode && !_photoIdle && _cameraElapsedMode) {
_camera.stopTakePhoto()
} else {
_camera.takePhoto()
}
}
} else {
if (_videoManager.recording) {
_videoManager.stopRecording()
} else {
_videoManager.startRecording()
}
}
}
enabled: _canShootInCurrentMode
onClicked: toggleShooting()
}
}
......@@ -205,32 +250,32 @@ Rectangle {
QGCLabel {
Layout.alignment: Qt.AlignHCenter
text: _cameraName
visible: _cameraName !== ""
text: _mavlinkCameraName
visible: _mavlinkCameraName !== ""
}
QGCLabel {
Layout.alignment: Qt.AlignHCenter
text: (_cameraInVideoMode && _camera.videoStatus === QGCCameraControl.VIDEO_CAPTURE_STATUS_RUNNING) ? _camera.recordTimeStr : "00:00:00"
text: (_mavlinkCameraInVideoMode && _mavlinkCamera.videoStatus === QGCCameraControl.VIDEO_CAPTURE_STATUS_RUNNING) ? _mavlinkCamera.recordTimeStr : "00:00:00"
font.pointSize: ScreenTools.largeFontPointSize
visible: _cameraInVideoMode
visible: _mavlinkCameraInVideoMode
}
QGCLabel {
Layout.alignment: Qt.AlignHCenter
text: _activeVehicle && _cameraInPhotoMode ? ('00000' + _activeVehicle.cameraTriggerPoints.count).slice(-5) : "0000_cameraPhotoMode0"
text: _activeVehicle && _mavlinkCameraInPhotoMode ? ('00000' + _activeVehicle.cameraTriggerPoints.count).slice(-5) : "0000_mavlinkCameraPhotoMode0"
font.pointSize: ScreenTools.largeFontPointSize
visible: _cameraInPhotoMode
visible: _mavlinkCameraInPhotoMode
}
QGCLabel {
Layout.alignment: Qt.AlignHCenter
text: _camera ? qsTr("Free Space: ") + _camera.storageFreeStr : ""
text: _mavlinkCamera ? qsTr("Free Space: ") + _mavlinkCamera.storageFreeStr : ""
font.pointSize: ScreenTools.defaultFontPointSize
visible: _storageReady
visible: _mavlinkCameraStorageReady
}
QGCLabel {
Layout.alignment: Qt.AlignHCenter
text: _camera ? qsTr("Battery: ") + _camera.batteryRemainingStr : ""
text: _mavlinkCamera ? qsTr("Battery: ") + _mavlinkCamera.batteryRemainingStr : ""
font.pointSize: ScreenTools.defaultFontPointSize
visible: _batteryReady
visible: _mavlinkCameraBatteryReady
}
}
}
......@@ -248,14 +293,14 @@ Rectangle {
GridLayout {
id: gridLayout
flow: GridLayout.TopToBottom
rows: dynamicRows + (_camera ? _camera.activeSettings.length : 0)
rows: dynamicRows + (_mavlinkCamera ? _mavlinkCamera.activeSettings.length : 0)
property int dynamicRows: 10
// First column
QGCLabel {
text: qsTr("Camera")
visible: _multipleCameras
visible: _multipleMavlinkCameras
onVisibleChanged: gridLayout.dynamicRows += visible ? 1 : -1
}
......@@ -267,35 +312,34 @@ Rectangle {
QGCLabel {
text: qsTr("Thermal View Mode")
visible: _hasThermalVideoStream
visible: _mavlinkCameraHasThermalVideoStream
onVisibleChanged: gridLayout.dynamicRows += visible ? 1 : -1
}
QGCLabel {
text: qsTr("Blend Opacity")
visible: _hasThermalVideoStream && _camera.thermalMode === QGCCameraControl.THERMAL_BLEND
visible: _mavlinkCameraHasThermalVideoStream && _mavlinkCamera.thermalMode === QGCCameraControl.THERMAL_BLEND
onVisibleChanged: gridLayout.dynamicRows += visible ? 1 : -1
}
// Mavlink Camera Protocol active settings
Repeater {
model: _camera ? _camera.activeSettings : []
model: _mavlinkCamera ? _mavlinkCamera.activeSettings : []
QGCLabel {
text: _camera.getFact(modelData).shortDescription
text: _mavlinkCamera.getFact(modelData).shortDescription
}
}
QGCLabel {
text: qsTr("Photo Mode")
visible: _hasModes
visible: _mavlinkCameraHasModes
onVisibleChanged: gridLayout.dynamicRows += visible ? 1 : -1
}
QGCLabel {
text: qsTr("Photo Interval (seconds)")
width: _labelFieldWidth
visible: _cameraInPhotoMode && _camera.photoMode === QGCCameraControl.PHOTO_CAPTURE_TIMELAPSE
visible: _mavlinkCameraInPhotoMode && _mavlinkCamera.photoMode === QGCCameraControl.PHOTO_CAPTURE_TIMELAPSE
onVisibleChanged: gridLayout.dynamicRows += visible ? 1 : -1
}
......@@ -313,13 +357,13 @@ Rectangle {
QGCLabel {
text: qsTr("Reset Camera Defaults")
visible: _camera
visible: _mavlinkCamera
onVisibleChanged: gridLayout.dynamicRows += visible ? 1 : -1
}
QGCLabel {
text: qsTr("Storage")
visible: _storageSupported
visible: _mavlinkCameraStorageSupported
onVisibleChanged: gridLayout.dynamicRows += visible ? 1 : -1
}
......@@ -327,49 +371,49 @@ Rectangle {
QGCComboBox {
Layout.fillWidth: true
sizeToContents: true
model: _cameraManager ? _cameraManager.cameraLabels : []
currentIndex: _curCameraIndex
visible: _multipleCameras
onActivated: _cameraManager.currentCamera = index
model: _mavlinkCameraManager ? _mavlinkCameraManager.cameraLabels : []
currentIndex: _mavlinkCameraManagerCurCameraIndex
visible: _multipleMavlinkCameras
onActivated: _mavlinkCameraManager.currentCamera = index
}
QGCComboBox {
Layout.fillWidth: true
sizeToContents: true
model: _camera ? _camera.streamLabels : []
currentIndex: _curStreamIndex
model: _mavlinkCamera ? _mavlinkCamera.streamLabels : []
currentIndex: _mavlinCameraCurStreamIndex
visible: _multipleMavlinkCameraStreams
onActivated: _camera.currentStream = index
onActivated: _mavlinkCamera.currentStream = index
}
QGCComboBox {
Layout.fillWidth: true
sizeToContents: true
model: [ qsTr("Off"), qsTr("Blend"), qsTr("Full"), qsTr("Picture In Picture") ]
currentIndex: _camera ? _camera.thermalMode : -1
visible: _hasThermalVideoStream
onActivated: _camera.thermalMode = index
currentIndex: _mavlinkCamera ? _mavlinkCamera.thermalMode : -1
visible: _mavlinkCameraHasThermalVideoStream
onActivated: _mavlinkCamera.thermalMode = index
}
QGCSlider {
Layout.fillWidth: true
maximumValue: 100
minimumValue: 0
value: _camera ? _camera.thermalOpacity : 0
value: _mavlinkCamera ? _mavlinkCamera.thermalOpacity : 0
updateValueWhileDragging: true
visible: _hasThermalVideoStream && _camera.thermalMode === QGCCameraControl.THERMAL_BLEND
onValueChanged: _camera.thermalOpacity = value
visible: _mavlinkCameraHasThermalVideoStream && _mavlinkCamera.thermalMode === QGCCameraControl.THERMAL_BLEND
onValueChanged: _mavlinkCamera.thermalOpacity = value
}
// Mavlink Camera Protocol active settings
Repeater {
model: _camera ? _camera.activeSettings : []
model: _mavlinkCamera ? _mavlinkCamera.activeSettings : []
RowLayout {
Layout.fillWidth: true
spacing: ScreenTools.defaultFontPixelWidth
property var _fact: _camera.getFact(modelData)
property var _fact: _mavlinkCamera.getFact(modelData)
property bool _isBool: _fact.typeIsBool
property bool _isCombo: !_isBool && _fact.enumStrings.length > 0
property bool _isSlider: _fact && !isNaN(_fact.increment)
......@@ -409,9 +453,9 @@ Rectangle {
Layout.fillWidth: true
sizeToContents: true
model: [ qsTr("Single"), qsTr("Time Lapse") ]
currentIndex: _camera ? _camera.photoMode : 0
visible: _hasModes
onActivated: _camera.photoMode = index
currentIndex: _mavlinkCamera ? _mavlinkCamera.photoMode : 0
visible: _mavlinkCameraHasModes
onActivated: _mavlinkCamera.photoMode = index
}
QGCSlider {
......@@ -419,27 +463,27 @@ Rectangle {
maximumValue: 60
minimumValue: 1
stepSize: 1
value: _camera ? _camera.photoLapse : 5
value: _mavlinkCamera ? _mavlinkCamera.photoLapse : 5
displayValue: true
updateValueWhileDragging: true
visible: _cameraInPhotoMode && _camera.photoMode === QGCCameraControl.PHOTO_CAPTURE_TIMELAPSE
visible: _mavlinkCameraInPhotoMode && _mavlinkCamera.photoMode === QGCCameraControl.PHOTO_CAPTURE_TIMELAPSE
onValueChanged: {
if (_camera) {
_camera.photoLapse = value
if (_mavlinkCamera) {
_mavlinkCamera.photoLapse = value
}
}
}
QGCSwitch {
checked: _videoSettings.gridLines.rawValue
checked: _videoStreamSettings.gridLines.rawValue
visible: _anyVideoStreamAvailable
onClicked: _videoSettings.gridLines.rawValue = checked ? 1 : 0
onClicked: _videoStreamSettings.gridLines.rawValue = checked ? 1 : 0
}
FactComboBox {
Layout.fillWidth: true
sizeToContents: true
fact: _videoSettings.videoFit
fact: _videoStreamSettings.videoFit
indexModel: false
visible: _anyVideoStreamAvailable
}
......@@ -447,7 +491,7 @@ Rectangle {
QGCButton {
Layout.fillWidth: true
text: qsTr("Reset")
visible: _camera
visible: _mavlinkCamera
onClicked: resetPrompt.open()
MessageDialog {
id: resetPrompt
......@@ -456,7 +500,7 @@ Rectangle {
standardButtons: StandardButton.Yes | StandardButton.No
onNo: resetPrompt.close()
onYes: {
_camera.resetSettings()
_mavlinkCamera.resetSettings()
resetPrompt.close()
}
}
......@@ -465,7 +509,7 @@ Rectangle {
QGCButton {
Layout.fillWidth: true
text: qsTr("Format")
visible: _storageSupported
visible: _mavlinkCameraStorageSupported
onClicked: formatPrompt.open()
MessageDialog {
id: formatPrompt
......@@ -474,7 +518,7 @@ Rectangle {
standardButtons: StandardButton.Yes | StandardButton.No
onNo: formatPrompt.close()
onYes: {
_camera.formatCard()
_mavlinkCamera.formatCard()
formatPrompt.close()
}
}
......
......@@ -27,12 +27,13 @@ const char* AppSettings::kmlFileExtension = "kml";
const char* AppSettings::shpFileExtension = "shp";
const char* AppSettings::logFileExtension = "ulg";
const char* AppSettings::parameterDirectory = "Parameters";
const char* AppSettings::telemetryDirectory = "Telemetry";
const char* AppSettings::missionDirectory = "Missions";
const char* AppSettings::logDirectory = "Logs";
const char* AppSettings::videoDirectory = "Video";
const char* AppSettings::crashDirectory = "CrashLogs";
const char* AppSettings::parameterDirectory = QT_TRANSLATE_NOOP("AppSettings", "Parameters");
const char* AppSettings::telemetryDirectory = QT_TRANSLATE_NOOP("AppSettings", "Telemetry");
const char* AppSettings::missionDirectory = QT_TRANSLATE_NOOP("AppSettings", "Missions");
const char* AppSettings::logDirectory = QT_TRANSLATE_NOOP("AppSettings", "Logs");
const char* AppSettings::videoDirectory = QT_TRANSLATE_NOOP("AppSettings", "Video");
const char* AppSettings::photoDirectory = QT_TRANSLATE_NOOP("AppSettings", "Photo");
const char* AppSettings::crashDirectory = QT_TRANSLATE_NOOP("AppSettings", "CrashLogs");
DECLARE_SETTINGGROUP(App, "")
{
......@@ -160,6 +161,7 @@ void AppSettings::_checkSavePathDirectories(void)
savePathDir.mkdir(missionDirectory);
savePathDir.mkdir(logDirectory);
savePathDir.mkdir(videoDirectory);
savePathDir.mkdir(photoDirectory);
savePathDir.mkdir(crashDirectory);
}
}
......@@ -219,6 +221,16 @@ QString AppSettings::videoSavePath(void)
return QString();
}
QString AppSettings::photoSavePath(void)
{
QString path = savePath()->rawValue().toString();
if (!path.isEmpty() && QDir(path).exists()) {
QDir dir(path);
return dir.filePath(photoDirectory);
}
return QString();
}
QString AppSettings::crashSavePath(void)
{
QString path = savePath()->rawValue().toString();
......
......@@ -71,6 +71,7 @@ public:
Q_PROPERTY(QString telemetrySavePath READ telemetrySavePath NOTIFY savePathsChanged)
Q_PROPERTY(QString logSavePath READ logSavePath NOTIFY savePathsChanged)
Q_PROPERTY(QString videoSavePath READ videoSavePath NOTIFY savePathsChanged)
Q_PROPERTY(QString photoSavePath READ photoSavePath NOTIFY savePathsChanged)
Q_PROPERTY(QString crashSavePath READ crashSavePath NOTIFY savePathsChanged)
Q_PROPERTY(QString planFileExtension MEMBER planFileExtension CONSTANT)
......@@ -87,6 +88,7 @@ public:
QString telemetrySavePath ();
QString logSavePath ();
QString videoSavePath ();
QString photoSavePath ();
QString crashSavePath ();
// Helper methods for working with firstRunPromptIds QVariant settings string list
......@@ -112,6 +114,7 @@ public:
static const char* missionDirectory;
static const char* logDirectory;
static const char* videoDirectory;
static const char* photoDirectory;
static const char* crashDirectory;
// Returns the current language setting bypassing the standard SettingsGroup path. This should only be used
......
......@@ -350,7 +350,12 @@ VideoManager::grabImage(const QString& imageFile)
return;
}
_imageFile = imageFile;
if (imageFile.isEmpty()) {
_imageFile = qgcApp()->toolbox()->settingsManager()->appSettings()->photoSavePath();
_imageFile += + "/" + QDateTime::currentDateTime().toString("yyyy-MM-dd_hh.mm.ss.zzz") + ".jpg";
} else {
_imageFile = imageFile;
}
emit imageFileChanged();
......
......@@ -109,7 +109,7 @@ public:
Q_INVOKABLE void startRecording (const QString& videoFile = QString());
Q_INVOKABLE void stopRecording ();
Q_INVOKABLE void grabImage(const QString& imageFile);
Q_INVOKABLE void grabImage(const QString& imageFile = QString());
signals:
void hasVideoChanged ();
......
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