Commit b2f7fc86 authored by Gus Grubba's avatar Gus Grubba

Multi camera Support

Added (UI) support for vehicles exposing more than one camera.
parent 7ce0a866
...@@ -15,6 +15,7 @@ QGCCameraManager::QGCCameraManager(Vehicle *vehicle) ...@@ -15,6 +15,7 @@ QGCCameraManager::QGCCameraManager(Vehicle *vehicle)
: _vehicle(vehicle) : _vehicle(vehicle)
, _vehicleReadyState(false) , _vehicleReadyState(false)
, _currentTask(0) , _currentTask(0)
, _currentCamera(0)
{ {
QQmlEngine::setObjectOwnership(this, QQmlEngine::CppOwnership); QQmlEngine::setObjectOwnership(this, QQmlEngine::CppOwnership);
qCDebug(CameraManagerLog) << "QGCCameraManager Created"; qCDebug(CameraManagerLog) << "QGCCameraManager Created";
...@@ -27,6 +28,16 @@ QGCCameraManager::~QGCCameraManager() ...@@ -27,6 +28,16 @@ QGCCameraManager::~QGCCameraManager()
{ {
} }
//-----------------------------------------------------------------------------
void
QGCCameraManager::setCurrentCamera(int sel)
{
if(sel != _currentCamera && sel >= 0 && sel < _cameras.count()) {
_currentCamera = sel;
emit currentCameraChanged();
}
}
//----------------------------------------------------------------------------- //-----------------------------------------------------------------------------
void void
QGCCameraManager::_vehicleReady(bool ready) QGCCameraManager::_vehicleReady(bool ready)
...@@ -121,7 +132,9 @@ QGCCameraManager::_handleCameraInfo(const mavlink_message_t& message) ...@@ -121,7 +132,9 @@ QGCCameraManager::_handleCameraInfo(const mavlink_message_t& message)
if(pCamera) { if(pCamera) {
QQmlEngine::setObjectOwnership(pCamera, QQmlEngine::CppOwnership); QQmlEngine::setObjectOwnership(pCamera, QQmlEngine::CppOwnership);
_cameras.append(pCamera); _cameras.append(pCamera);
_cameraLabels << pCamera->modelName();
emit camerasChanged(); emit camerasChanged();
emit cameraLabelsChanged();
} }
} }
} }
......
...@@ -25,13 +25,23 @@ public: ...@@ -25,13 +25,23 @@ public:
QGCCameraManager(Vehicle* vehicle); QGCCameraManager(Vehicle* vehicle);
virtual ~QGCCameraManager(); virtual ~QGCCameraManager();
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(int currentCamera READ currentCamera WRITE setCurrentCamera 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; }
//-- Camera names to show the user (for selection)
virtual QStringList cameraLabels () { return _cameraLabels; }
//-- Current selected camera
virtual int currentCamera () { return _currentCamera; }
//-- Set current camera
virtual void setCurrentCamera (int sel);
signals: signals:
void camerasChanged (); void camerasChanged ();
void cameraLabelsChanged ();
void currentCameraChanged ();
protected slots: protected slots:
virtual void _vehicleReady (bool ready); virtual void _vehicleReady (bool ready);
...@@ -53,5 +63,7 @@ protected: ...@@ -53,5 +63,7 @@ protected:
bool _vehicleReadyState; bool _vehicleReadyState;
int _currentTask; int _currentTask;
QmlObjectListModel _cameras; QmlObjectListModel _cameras;
QStringList _cameraLabels;
QMap<int, bool> _cameraInfoRequested; QMap<int, bool> _cameraInfoRequested;
int _currentCamera;
}; };
...@@ -33,10 +33,10 @@ Column { ...@@ -33,10 +33,10 @@ Column {
property var _activeVehicle: QGroundControl.multiVehicleManager.activeVehicle property var _activeVehicle: QGroundControl.multiVehicleManager.activeVehicle
property var _dynamicCameras: _activeVehicle ? _activeVehicle.dynamicCameras : null property var _dynamicCameras: _activeVehicle ? _activeVehicle.dynamicCameras : null
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(0) : null // Single camera support for the time being property var _camera: _isCamera ? _dynamicCameras.cameras.get(_curCameraIndex) : null
property bool _cameraModeUndefined: _isCamera ? _dynamicCameras.cameras.get(0).cameraMode === QGCCameraControl.CAMERA_MODE_UNDEFINED : true property bool _cameraModeUndefined: _isCamera ? _dynamicCameras.cameras.get(_curCameraIndex).cameraMode === QGCCameraControl.CAMERA_MODE_UNDEFINED : true
property bool _cameraVideoMode: _isCamera ? _dynamicCameras.cameras.get(0).cameraMode === 1 : false property bool _cameraVideoMode: _isCamera ? _dynamicCameras.cameras.get(_curCameraIndex).cameraMode === 1 : false
property bool _cameraPhotoMode: _isCamera ? _dynamicCameras.cameras.get(0).cameraMode === 0 : false property bool _cameraPhotoMode: _isCamera ? _dynamicCameras.cameras.get(_curCameraIndex).cameraMode === 0 : false
property bool _cameraPhotoIdle: _isCamera && _camera.photoStatus === QGCCameraControl.PHOTO_CAPTURE_IDLE 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 bool _cameraElapsedMode: _isCamera && _camera.cameraMode === QGCCameraControl.CAM_MODE_PHOTO && _camera.photoMode === QGCCameraControl.PHOTO_CAPTURE_TIMELAPSE
property real _spacers: ScreenTools.defaultFontPixelHeight * 0.5 property real _spacers: ScreenTools.defaultFontPixelHeight * 0.5
...@@ -46,6 +46,7 @@ Column { ...@@ -46,6 +46,7 @@ Column {
property bool _hasModes: _isCamera && _camera && _camera.hasModes property bool _hasModes: _isCamera && _camera && _camera.hasModes
property bool _videoRecording: _camera && _camera.videoStatus === QGCCameraControl.VIDEO_CAPTURE_STATUS_RUNNING property bool _videoRecording: _camera && _camera.videoStatus === QGCCameraControl.VIDEO_CAPTURE_STATUS_RUNNING
property bool _noStorage: _camera && _camera.storageTotal === 0 property bool _noStorage: _camera && _camera.storageTotal === 0
property int _curCameraIndex: _dynamicCameras ? _dynamicCameras.currentCamera : 0
function showSettings() { function showSettings() {
qgcView.showDialog(cameraSettings, _cameraVideoMode ? qsTr("Video Settings") : qsTr("Camera Settings"), 70, StandardButton.Ok) qgcView.showDialog(cameraSettings, _cameraVideoMode ? qsTr("Video Settings") : qsTr("Camera Settings"), 70, StandardButton.Ok)
...@@ -202,6 +203,23 @@ Column { ...@@ -202,6 +203,23 @@ Column {
anchors.left: parent.left anchors.left: parent.left
anchors.right: parent.right anchors.right: parent.right
spacing: _margins spacing: _margins
Row {
visible: _isCamera
spacing: ScreenTools.defaultFontPixelWidth
anchors.horizontalCenter: parent.horizontalCenter
QGCLabel {
text: qsTr("Camera Selector:")
width: _labelFieldWidth
anchors.verticalCenter: parent.verticalCenter
}
QGCComboBox {
id: cameraSelector
model: _isCamera ? _dynamicCameras.cameraLabels : []
width: _editFieldWidth
onActivated: _dynamicCameras.cameras = index
currentIndex: 0
}
}
//------------------------------------------- //-------------------------------------------
//-- Camera Settings //-- Camera Settings
Repeater { Repeater {
......
...@@ -45,7 +45,7 @@ QVariant QmlObjectListModel::data(const QModelIndex &index, int role) const ...@@ -45,7 +45,7 @@ QVariant QmlObjectListModel::data(const QModelIndex &index, int role) const
return QVariant(); return QVariant();
} }
if (index.row() >= _objectList.count()) { if (index.row() < 0 || index.row() >= _objectList.count()) {
return QVariant(); return QVariant();
} }
...@@ -120,11 +120,17 @@ bool QmlObjectListModel::removeRows(int position, int rows, const QModelIndex& p ...@@ -120,11 +120,17 @@ bool QmlObjectListModel::removeRows(int position, int rows, const QModelIndex& p
QObject* QmlObjectListModel::operator[](int index) QObject* QmlObjectListModel::operator[](int index)
{ {
if (index < 0 || index >= _objectList.count()) {
return NULL;
}
return _objectList[index]; return _objectList[index];
} }
const QObject* QmlObjectListModel::operator[](int index) const const QObject* QmlObjectListModel::operator[](int index) const
{ {
if (index < 0 || index >= _objectList.count()) {
return NULL;
}
return _objectList[index]; return _objectList[index];
} }
......
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