Browse Source

Merge pull request #7469 from mavlink/handleAutoVideoStream

Handle auto video stream
QGC4.4
Gus Grubba 6 years ago committed by GitHub
parent
commit
e684dbe5f8
No known key found for this signature in database
GPG Key ID: 4AEE18F83AFDEB23
  1. 6
      src/FlightDisplay/FlightDisplayViewVideo.qml
  2. 45
      src/FlightMap/Widgets/CameraPageWidget.qml
  3. 12
      src/FlightMap/Widgets/VideoPageWidget.qml
  4. 86
      src/api/QGCCorePlugin.cc
  5. 14
      src/api/QGCCorePlugin.h

6
src/FlightDisplay/FlightDisplayViewVideo.qml

@ -34,7 +34,7 @@ Item { @@ -34,7 +34,7 @@ Item {
property bool _hasZoom: _camera && _camera.hasZoom
property int _fitMode: QGroundControl.settingsManager.videoSettings.videoFit.rawValue
property double _thermalHeightFactor: 0.666 //-- TODO
property double _thermalHeightFactor: 0.85 //-- TODO
Rectangle {
id: noVideo
@ -83,7 +83,7 @@ Item { @@ -83,7 +83,7 @@ Item {
anchors.centerIn: parent
receiver: _videoReceiver
display: _videoReceiver && _videoReceiver.videoSurface
visible: _videoReceiver && _videoReceiver.videoRunning
visible: _videoReceiver && _videoReceiver.videoRunning && !(QGroundControl.videoManager.hasThermal && _camera.thermalMode === QGCCameraControl.THERMAL_FULL)
Connections {
target: _videoReceiver
onImageFileChanged: {
@ -127,7 +127,7 @@ Item { @@ -127,7 +127,7 @@ Item {
Item {
id: thermalItem
width: height * QGroundControl.videoManager.thermalAspectRatio
height: _camera ? (_camera.thermalMode === QGCCameraControl.THERMAL_PIP ? ScreenTools.defaultFontPixelHeight * 12 : parent.height * _thermalHeightFactor) : 0
height: _camera ? (_camera.thermalMode === QGCCameraControl.THERMAL_FULL ? parent.height : (_camera.thermalMode === QGCCameraControl.THERMAL_PIP ? ScreenTools.defaultFontPixelHeight * 12 : parent.height * _thermalHeightFactor)) : 0
anchors.centerIn: parent
visible: QGroundControl.videoManager.hasThermal && _camera.thermalMode !== QGCCameraControl.THERMAL_OFF
function pipOrNot() {

45
src/FlightMap/Widgets/CameraPageWidget.qml

@ -390,9 +390,52 @@ Column { @@ -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")

12
src/FlightMap/Widgets/VideoPageWidget.qml

@ -35,6 +35,10 @@ Item { @@ -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 { @@ -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 { @@ -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 { @@ -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 { @@ -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

86
src/api/QGCCorePlugin.cc

@ -17,6 +17,7 @@ @@ -17,6 +17,7 @@
#include "QmlObjectListModel.h"
#include "VideoReceiver.h"
#include "QGCLoggingCategory.h"
#include "QGCCameraManager.h"
#include <QtQml>
#include <QQmlEngine>
@ -123,6 +124,86 @@ void QGCCorePlugin::setToolbox(QGCToolbox *toolbox) @@ -123,6 +124,86 @@ void QGCCorePlugin::setToolbox(QGCToolbox *toolbox)
QQmlEngine::setObjectOwnership(this, QQmlEngine::CppOwnership);
qmlRegisterUncreatableType<QGCCorePlugin>("QGroundControl.QGCCorePlugin", 1, 0, "QGCCorePlugin", "Reference only");
qmlRegisterUncreatableType<QGCOptions>("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);
_dynamicCameras = nullptr;
}
_activeVehicle = activeVehicle;
if(_activeVehicle) {
connect(_activeVehicle, &Vehicle::dynamicCamerasChanged, this, &QGCCorePlugin::_dynamicCamerasChanged);
}
}
}
void QGCCorePlugin::_dynamicCamerasChanged()
{
if(_currentCamera) {
disconnect(_currentCamera, &QGCCameraControl::autoStreamChanged, this, &QGCCorePlugin::_autoStreamChanged);
_currentCamera = nullptr;
}
if(_activeVehicle) {
_dynamicCameras = _activeVehicle->dynamicCameras();
if(_dynamicCameras) {
connect(_dynamicCameras, &QGCCameraManager::currentCameraChanged, this, &QGCCorePlugin::_currentCameraChanged);
}
}
}
void QGCCorePlugin::_currentCameraChanged()
{
if(_dynamicCameras) {
QGCCameraControl* cp = _dynamicCameras->currentCameraInstance();
if(_currentCamera) {
disconnect(_currentCamera, &QGCCameraControl::autoStreamChanged, this, &QGCCorePlugin::_autoStreamChanged);
}
if(_currentCamera != cp) {
_currentCamera = cp;
connect(_currentCamera, &QGCCameraControl::autoStreamChanged, this, &QGCCorePlugin::_autoStreamChanged);
}
}
}
void QGCCorePlugin::_autoStreamChanged()
{
_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 +271,10 @@ QVariantList& QGCCorePlugin::instrumentPages() @@ -190,7 +271,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(!_currentCamera || !_currentCamera->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"));

14
src/api/QGCCorePlugin.h

@ -33,6 +33,8 @@ class LinkInterface; @@ -33,6 +33,8 @@ class LinkInterface;
class QmlObjectListModel;
class VideoReceiver;
class PlanMasterController;
class QGCCameraManager;
class QGCCameraControl;
class QGCCorePlugin : public QGCTool
{
@ -158,9 +160,21 @@ signals: @@ -158,9 +160,21 @@ signals:
void showTouchAreasChanged (bool showTouchAreas);
void showAdvancedUIChanged (bool showAdvancedUI);
protected slots:
void _activeVehicleChanged (Vehicle* activeVehicle);
void _dynamicCamerasChanged ();
void _currentCameraChanged ();
void _autoStreamChanged ();
protected:
void _resetInstrumentPages ();
protected:
bool _showTouchAreas;
bool _showAdvancedUI;
Vehicle* _activeVehicle = nullptr;
QGCCameraManager* _dynamicCameras = nullptr;
QGCCameraControl* _currentCamera = nullptr;
private:
QGCCorePlugin_p* _p;

Loading…
Cancel
Save