diff --git a/src/FlightMap/Widgets/CameraPageWidget.qml b/src/FlightMap/Widgets/CameraPageWidget.qml index 7f1bb241c2b0a7cb2e6e714470d02aa6c9939192..46b26be83956c187ac3d1edc5e5cdd9a92dbbfc5 100644 --- a/src/FlightMap/Widgets/CameraPageWidget.qml +++ b/src/FlightMap/Widgets/CameraPageWidget.qml @@ -390,9 +390,52 @@ Column { } } //------------------------------------------- + // Grid Lines + Row { + visible: _camera && _camera.autoStream + spacing: ScreenTools.defaultFontPixelWidth + anchors.horizontalCenter: parent.horizontalCenter + QGCLabel { + text: qsTr("Grid Lines") + width: _labelFieldWidth + anchors.verticalCenter: parent.verticalCenter + } + QGCSwitch { + enabled: _streamingEnabled && activeVehicle + checked: QGroundControl.settingsManager.videoSettings.gridLines.rawValue + width: _editFieldWidth + anchors.verticalCenter: parent.verticalCenter + onClicked: { + if(checked) { + QGroundControl.settingsManager.videoSettings.gridLines.rawValue = 1 + } else { + QGroundControl.settingsManager.videoSettings.gridLines.rawValue = 0 + } + } + } + } + //------------------------------------------- + //-- Video Fit + Row { + visible: _camera && _camera.autoStream + spacing: ScreenTools.defaultFontPixelWidth + anchors.horizontalCenter: parent.horizontalCenter + QGCLabel { + text: qsTr("Video Screen Fit") + width: _labelFieldWidth + anchors.verticalCenter: parent.verticalCenter + } + FactComboBox { + fact: QGroundControl.settingsManager.videoSettings.videoFit + indexModel: false + width: _editFieldWidth + anchors.verticalCenter: parent.verticalCenter + } + } + //------------------------------------------- //-- Reset Camera Row { - spacing: ScreenTools.defaultFontPixelWidth + spacing: ScreenTools.defaultFontPixelWidth anchors.horizontalCenter: parent.horizontalCenter QGCLabel { text: qsTr("Reset Camera Defaults") diff --git a/src/FlightMap/Widgets/VideoPageWidget.qml b/src/FlightMap/Widgets/VideoPageWidget.qml index b710c4b67d18affcc2418a37dc38386e817a3d5a..31410408a0f1bf335dc7701d97d1ffa7261b66d2 100644 --- a/src/FlightMap/Widgets/VideoPageWidget.qml +++ b/src/FlightMap/Widgets/VideoPageWidget.qml @@ -35,6 +35,10 @@ Item { property bool _recordingVideo: _videoReceiver && _videoReceiver.recording property bool _videoRunning: _videoReceiver && _videoReceiver.videoRunning property bool _streamingEnabled: QGroundControl.settingsManager.videoSettings.streamConfigured + property var _dynamicCameras: activeVehicle ? activeVehicle.dynamicCameras : null + property int _curCameraIndex: _dynamicCameras ? _dynamicCameras.currentCamera : 0 + property bool _isCamera: _dynamicCameras ? _dynamicCameras.cameras.count > 0 : false + property var _camera: _isCamera ? (_dynamicCameras.cameras.get(_curCameraIndex) && _dynamicCameras.cameras.get(_curCameraIndex).paramComplete ? _dynamicCameras.cameras.get(_curCameraIndex) : null) : null QGCPalette { id:qgcPal; colorGroupEnabled: true } @@ -55,9 +59,11 @@ Item { QGCLabel { text: qsTr("Enable Stream") font.pointSize: ScreenTools.smallFontPointSize + visible: !_camera || !_camera.autoStream } QGCSwitch { id: enableSwitch + visible: !_camera || !_camera.autoStream enabled: _streamingEnabled checked: QGroundControl.settingsManager.videoSettings.streamEnabled.rawValue Layout.alignment: Qt.AlignHCenter @@ -93,10 +99,12 @@ Item { //-- Video Fit QGCLabel { text: qsTr("Video Screen Fit") + visible: !_camera || !_camera.autoStream font.pointSize: ScreenTools.smallFontPointSize } FactComboBox { fact: QGroundControl.settingsManager.videoSettings.videoFit + visible: !_camera || !_camera.autoStream indexModel: false Layout.alignment: Qt.AlignHCenter } @@ -104,7 +112,7 @@ Item { QGCLabel { text: _recordingVideo ? qsTr("Stop Recording") : qsTr("Record Stream") font.pointSize: ScreenTools.smallFontPointSize - visible: QGroundControl.settingsManager.videoSettings.showRecControl.rawValue + visible: (!_camera || !_camera.autoStream) && QGroundControl.settingsManager.videoSettings.showRecControl.rawValue } // Button to start/stop video recording Item { @@ -112,7 +120,7 @@ Item { height: ScreenTools.defaultFontPixelHeight * 2 width: height Layout.alignment: Qt.AlignHCenter - visible: QGroundControl.settingsManager.videoSettings.showRecControl.rawValue + visible: (!_camera || !_camera.autoStream) && QGroundControl.settingsManager.videoSettings.showRecControl.rawValue Rectangle { id: recordBtnBackground anchors.top: parent.top diff --git a/src/api/QGCCorePlugin.cc b/src/api/QGCCorePlugin.cc index 0fc9861ba36514df576a65b7de5d7d0849cd0999..c0cdd4a59fea8d70ff86e977ce8f0c753200326e 100644 --- a/src/api/QGCCorePlugin.cc +++ b/src/api/QGCCorePlugin.cc @@ -17,6 +17,7 @@ #include "QmlObjectListModel.h" #include "VideoReceiver.h" #include "QGCLoggingCategory.h" +#include "QGCCameraManager.h" #include #include @@ -123,6 +124,63 @@ void QGCCorePlugin::setToolbox(QGCToolbox *toolbox) QQmlEngine::setObjectOwnership(this, QQmlEngine::CppOwnership); qmlRegisterUncreatableType("QGroundControl.QGCCorePlugin", 1, 0, "QGCCorePlugin", "Reference only"); qmlRegisterUncreatableType("QGroundControl.QGCOptions", 1, 0, "QGCOptions", "Reference only"); + //-- Handle Camera and Video Changes + connect(toolbox->multiVehicleManager(), &MultiVehicleManager::activeVehicleChanged, this, &QGCCorePlugin::_activeVehicleChanged); +} + +void QGCCorePlugin::_activeVehicleChanged(Vehicle* activeVehicle) +{ + if(activeVehicle != _activeVehicle) { + if(_activeVehicle) { + disconnect(_activeVehicle, &Vehicle::dynamicCamerasChanged, this, &QGCCorePlugin::_dynamicCamerasChanged); + } + if(_dynamicCameras) { + disconnect(_dynamicCameras, &QGCCameraManager::currentCameraChanged, this, &QGCCorePlugin::_currentCameraChanged); + } + _activeVehicle = activeVehicle; + connect(_activeVehicle, &Vehicle::dynamicCamerasChanged, this, &QGCCorePlugin::_dynamicCamerasChanged); + } +} + +void QGCCorePlugin::_dynamicCamerasChanged() +{ + if(_activeVehicle) { + _dynamicCameras = _activeVehicle->dynamicCameras(); + connect(_dynamicCameras, &QGCCameraManager::currentCameraChanged, this, &QGCCorePlugin::_currentCameraChanged); + } +} + +void QGCCorePlugin::_currentCameraChanged() +{ + _resetInstrumentPages(); + emit instrumentPagesChanged(); +} + +void QGCCorePlugin::_resetInstrumentPages() +{ + if (_p->valuesPageWidgetInfo) { + _p->valuesPageWidgetInfo->deleteLater(); + _p->valuesPageWidgetInfo = nullptr; + } + if(_p->cameraPageWidgetInfo) { + _p->cameraPageWidgetInfo->deleteLater(); + _p->cameraPageWidgetInfo = nullptr; + } +#if defined(QGC_GST_STREAMING) + if(_p->videoPageWidgetInfo) { + _p->videoPageWidgetInfo->deleteLater(); + _p->videoPageWidgetInfo = nullptr; + } +#endif + if(_p->healthPageWidgetInfo) { + _p->healthPageWidgetInfo->deleteLater(); + _p->healthPageWidgetInfo = nullptr; + } + if(_p->vibrationPageWidgetInfo) { + _p->vibrationPageWidgetInfo->deleteLater(); + _p->vibrationPageWidgetInfo = nullptr; + } + _p->instrumentPageWidgetList.clear(); } QVariantList &QGCCorePlugin::settingsPages() @@ -190,7 +248,10 @@ QVariantList& QGCCorePlugin::instrumentPages() _p->valuesPageWidgetInfo = new QmlComponentInfo(tr("Values"), QUrl::fromUserInput("qrc:/qml/ValuePageWidget.qml")); _p->cameraPageWidgetInfo = new QmlComponentInfo(tr("Camera"), QUrl::fromUserInput("qrc:/qml/CameraPageWidget.qml")); #if defined(QGC_GST_STREAMING) - _p->videoPageWidgetInfo = new QmlComponentInfo(tr("Video Stream"), QUrl::fromUserInput("qrc:/qml/VideoPageWidget.qml")); + if(!_dynamicCameras || !_dynamicCameras->currentCameraInstance() || !_dynamicCameras->currentCameraInstance()->autoStream()) { + //-- Video Page Widget only available if using manual video 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")); diff --git a/src/api/QGCCorePlugin.h b/src/api/QGCCorePlugin.h index 1162b541814a244d985c50c60dcfb424db897566..37c6f12c09d7e691e4178e47bb8315560bf06a22 100644 --- a/src/api/QGCCorePlugin.h +++ b/src/api/QGCCorePlugin.h @@ -33,6 +33,7 @@ class LinkInterface; class QmlObjectListModel; class VideoReceiver; class PlanMasterController; +class QGCCameraManager; class QGCCorePlugin : public QGCTool { @@ -158,9 +159,19 @@ signals: void showTouchAreasChanged (bool showTouchAreas); void showAdvancedUIChanged (bool showAdvancedUI); +protected slots: + void _activeVehicleChanged (Vehicle* activeVehicle); + void _dynamicCamerasChanged (); + void _currentCameraChanged (); + +protected: + void _resetInstrumentPages (); + protected: bool _showTouchAreas; bool _showAdvancedUI; + Vehicle* _activeVehicle = nullptr; + QGCCameraManager* _dynamicCameras = nullptr; private: QGCCorePlugin_p* _p;