Commit 85dc2937 authored by Gus Grubba's avatar Gus Grubba

Check and respect camera storage status

parent 4a529bd8
......@@ -6,6 +6,7 @@ Note: This file only contains high level features or important fixes.
### 3.6.0 - Daily Build
* Check and respect camera storage status
* QGC now requires Qt 5.11 or greater. The idea is to standardize on Qt 5.12 (LTS). Just waiting for a solution for Windows as Qt dropped support for 32-bit.
* New, QtQuick MAVLink Inspector. The basics are already there but it still needs the ability to filter compID.
* Fixed application storage location on iOS. It was trying to save things where it could not.
......
Subproject commit 600bbff722a13cfa61fe053de1da07069bab1d10
Subproject commit a91f8b4784a4660d3bf2b38619dae90e659a7535
......@@ -203,6 +203,9 @@ QGCCameraControl::_initWhenReady()
qCDebug(CameraControlLog) << "Basic, MAVLink only messages.";
_requestCameraSettings();
QTimer::singleShot(250, this, &QGCCameraControl::_checkForVideoStreams);
//-- Basic cameras have no parameters
_paramComplete = true;
emit parametersReady();
} else {
_requestAllParameters();
//-- Give some time to load the parameters before going after the camera settings
......@@ -1458,17 +1461,22 @@ void
QGCCameraControl::handleStorageInfo(const mavlink_storage_information_t& st)
{
qCDebug(CameraControlLog) << "handleStorageInfo:" << st.available_capacity << st.status << st.storage_count << st.storage_id << st.total_capacity << st.used_capacity;
if(st.status == STORAGE_STATUS_READY) {
uint32_t t = static_cast<uint32_t>(st.total_capacity);
if(_storageTotal != t) {
_storageTotal = t;
}
//-- Always emit this
emit storageTotalChanged();
}
uint32_t a = static_cast<uint32_t>(st.available_capacity);
if(_storageFree != a) {
_storageFree = a;
emit storageFreeChanged();
}
}
if(_storageStatus != static_cast<StorageStatus>(st.status)) {
_storageStatus = static_cast<StorageStatus>(st.status);
emit storageStatusChanged();
}
}
//-----------------------------------------------------------------------------
......
......@@ -114,6 +114,14 @@ public:
PHOTO_CAPTURE_TIMELAPSE,
};
//-- Storage Status
enum StorageStatus {
STORAGE_EMPTY = STORAGE_STATUS_EMPTY,
STORAGE_UNFORMATTED = STORAGE_STATUS_UNFORMATTED,
STORAGE_READY = STORAGE_STATUS_READY,
STORAGE_NOT_SUPPORTED = STORAGE_STATUS_NOT_SUPPORTED
};
enum ThermalViewMode {
THERMAL_OFF = 0,
THERMAL_BLEND,
......@@ -125,6 +133,7 @@ public:
Q_ENUM(VideoStatus)
Q_ENUM(PhotoStatus)
Q_ENUM(PhotoMode)
Q_ENUM(StorageStatus)
Q_ENUM(ThermalViewMode)
Q_PROPERTY(int version READ version NOTIFY infoChanged)
......@@ -163,6 +172,7 @@ public:
Q_PROPERTY(VideoStatus videoStatus READ videoStatus NOTIFY videoStatusChanged)
Q_PROPERTY(PhotoStatus photoStatus READ photoStatus NOTIFY photoStatusChanged)
Q_PROPERTY(CameraMode cameraMode READ cameraMode WRITE setCameraMode NOTIFY cameraModeChanged)
Q_PROPERTY(StorageStatus storageStatus READ storageStatus NOTIFY storageStatusChanged)
Q_PROPERTY(qreal photoLapse READ photoLapse WRITE setPhotoLapse NOTIFY photoLapseChanged)
Q_PROPERTY(int photoLapseCount READ photoLapseCount WRITE setPhotoLapseCount NOTIFY photoLapseCountChanged)
Q_PROPERTY(PhotoMode photoMode READ photoMode WRITE setPhotoMode NOTIFY photoModeChanged)
......@@ -217,6 +227,7 @@ public:
virtual qreal photoLapse () { return _photoLapse; }
virtual int photoLapseCount () { return _photoLapseCount; }
virtual CameraMode cameraMode () { return _cameraMode; }
virtual StorageStatus storageStatus () { return _storageStatus; }
virtual QStringList activeSettings ();
virtual quint32 storageFree () { return _storageFree; }
virtual QString storageFreeStr ();
......@@ -305,6 +316,7 @@ signals:
void streamLabelsChanged ();
void thermalModeChanged ();
void thermalOpacityChanged ();
void storageStatusChanged ();
protected:
virtual void _setVideoStatus (VideoStatus status);
......@@ -367,6 +379,7 @@ protected:
QString _vendor;
QString _cacheFile;
CameraMode _cameraMode = CAM_MODE_UNDEFINED;
StorageStatus _storageStatus = STORAGE_NOT_SUPPORTED;
PhotoMode _photoMode = PHOTO_CAPTURE_SINGLE;
qreal _photoLapse = 1.0;
int _photoLapseCount = 0;
......
......@@ -32,19 +32,21 @@ Column {
property var _dynamicCameras: activeVehicle ? activeVehicle.dynamicCameras : null
property bool _isCamera: _dynamicCameras ? _dynamicCameras.cameras.count > 0 : false
property var _camera: _isCamera ? _dynamicCameras.cameras.get(_curCameraIndex) : null
property bool _cameraModeUndefined: _isCamera ? _dynamicCameras.cameras.get(_curCameraIndex).cameraMode === QGCCameraControl.CAMERA_MODE_UNDEFINED : true
property bool _cameraVideoMode: _isCamera ? _dynamicCameras.cameras.get(_curCameraIndex).cameraMode === 1 : false
property bool _cameraPhotoMode: _isCamera ? _dynamicCameras.cameras.get(_curCameraIndex).cameraMode === 0 : false
property bool _cameraPhotoIdle: _isCamera && _camera.photoStatus === QGCCameraControl.PHOTO_CAPTURE_IDLE
property bool _cameraElapsedMode: _isCamera && _camera.cameraMode === QGCCameraControl.CAM_MODE_PHOTO && _camera.photoMode === QGCCameraControl.PHOTO_CAPTURE_TIMELAPSE
property var _camera: _isCamera ? (_dynamicCameras.cameras.get(_curCameraIndex) && _dynamicCameras.cameras.get(_curCameraIndex).paramComplete ? _dynamicCameras.cameras.get(_curCameraIndex) : null) : null
property bool _cameraModeUndefined: _camera ? _dynamicCameras.cameras.get(_curCameraIndex).cameraMode === QGCCameraControl.CAMERA_MODE_UNDEFINED : true
property bool _cameraVideoMode: _camera ? _dynamicCameras.cameras.get(_curCameraIndex).cameraMode === 1 : false
property bool _cameraPhotoMode: _camera ? _dynamicCameras.cameras.get(_curCameraIndex).cameraMode === 0 : false
property bool _cameraPhotoIdle: _camera && _camera.photoStatus === QGCCameraControl.PHOTO_CAPTURE_IDLE
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: _isCamera && _camera && _camera.hasModes
property bool _hasModes: _camera && _camera && _camera.hasModes
property bool _videoRecording: _camera && _camera.videoStatus === QGCCameraControl.VIDEO_CAPTURE_STATUS_RUNNING
property bool _noStorage: _camera && _camera.storageTotal === 0
property bool _storageReady: _camera && _camera.storageStatus === QGCCameraControl.STORAGE_READY
property bool _storageIgnored: _camera && _camera.storageStatus === QGCCameraControl.STORAGE_NOT_SUPPORTED
property bool _canShoot: !_videoRecording && _cameraPhotoIdle && ((_storageReady && _camera.storageFree > 0) || _storageIgnored)
property int _curCameraIndex: _dynamicCameras ? _dynamicCameras.currentCamera : 0
function showSettings() {
......@@ -55,16 +57,16 @@ Column {
QGCButton {
anchors.horizontalCenter: parent.horizontalCenter
text: qsTr("Trigger Camera")
visible: !_isCamera
visible: !_camera
onClicked: activeVehicle.triggerCamera()
enabled: activeVehicle
}
Item { width: 1; height: ScreenTools.defaultFontPixelHeight; visible: _isCamera; }
Item { width: 1; height: ScreenTools.defaultFontPixelHeight; visible: _camera; }
//-- Actual controller
QGCLabel {
id: cameraLabel
text: _isCamera ? _camera.modelName : qsTr("Camera")
visible: _isCamera
text: _camera ? _camera.modelName : qsTr("Camera")
visible: _camera
font.pointSize: ScreenTools.smallFontPointSize
anchors.horizontalCenter: parent.horizontalCenter
}
......@@ -72,7 +74,7 @@ Column {
text: _camera ? qsTr("Free Space: ") + _camera.storageFreeStr : ""
font.pointSize: ScreenTools.smallFontPointSize
anchors.horizontalCenter: parent.horizontalCenter
visible: _camera && !_noStorage
visible: _camera && _storageReady
}
//-- Camera Mode (visible only if camera has modes)
Item { width: 1; height: ScreenTools.defaultFontPixelHeight * 0.75; visible: camMode.visible; }
......@@ -147,7 +149,7 @@ Column {
width: ScreenTools.defaultFontPixelWidth * 6
height: width
radius: width * 0.5
visible: _isCamera
visible: _camera
border.color: qgcPal.buttonText
border.width: 3
anchors.horizontalCenter: parent.horizontalCenter
......@@ -155,12 +157,12 @@ Column {
width: parent.width * (_videoRecording || (_cameraPhotoMode && !_cameraPhotoIdle && _cameraElapsedMode) ? 0.5 : 0.75)
height: width
radius: _videoRecording || (_cameraPhotoMode && !_cameraPhotoIdle && _cameraElapsedMode) ? 0 : width * 0.5
color: _cameraModeUndefined ? qgcPal.colorGrey : qgcPal.colorRed
color: (_cameraModeUndefined || !_canShoot) ? qgcPal.colorGrey : qgcPal.colorRed
anchors.centerIn: parent
}
MouseArea {
anchors.fill: parent
enabled: !_cameraModeUndefined
enabled: !_cameraModeUndefined && _canShoot
onClicked: {
if(_cameraVideoMode) {
_camera.toggleVideo()
......@@ -174,7 +176,7 @@ Column {
}
}
}
Item { width: 1; height: ScreenTools.defaultFontPixelHeight * 0.75; visible: _isCamera; }
Item { width: 1; height: ScreenTools.defaultFontPixelHeight * 0.75; visible: _camera; }
QGCLabel {
text: (_cameraVideoMode && _camera.videoStatus === QGCCameraControl.VIDEO_CAPTURE_STATUS_RUNNING) ? _camera.recordTimeStr : "00:00:00"
font.pointSize: ScreenTools.smallFontPointSize
......@@ -187,7 +189,7 @@ Column {
visible: _cameraPhotoMode
anchors.horizontalCenter: parent.horizontalCenter
}
Item { width: 1; height: ScreenTools.defaultFontPixelHeight; visible: _isCamera; }
Item { width: 1; height: ScreenTools.defaultFontPixelHeight; visible: _camera; }
Component {
id: cameraSettings
QGCViewDialog {
......
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