Unverified Commit aa8a9ac6 authored by Don Gagne's avatar Don Gagne Committed by GitHub

Merge branch 'master' into TerrainProfile

parents 8e661ea0 027488a4
......@@ -7,6 +7,6 @@
[submodule "libs/OpenSSL/android_openssl"]
path = libs/OpenSSL/android_openssl
url = https://github.com/Auterion/android_openssl
[submodule "libs/gst-plugins-good"]
[submodule "libs/qmlglsink/gst-plugins-good"]
path = libs/qmlglsink/gst-plugins-good
url = https://github.com/mavlink/gst-plugins-good.git
# VideoReceiverApp
## Application
This is a simple test application developed to make VideoReceiver library development and testing easier. It can also be used as part of CI for system tests.
## Use cases and options
Application's behaviour depends on the executable name. There are two modes - QML and console. QML mode is enabled by renaming application executable to something that starts with **Q** (for example QVideoReceiverApp). In this case **video-sink** option is not available and application always tries to use **qmlglsink** for video rendering. In regular case (executable name does not start with **Q**) **autovideosink** or **fakesink** are used, depending on options.
### Available options and required arguments
```VideoReceiverApp [options] url```
for example:
```VideoReceiverApp -d --stop-decoding 30 rtsp://127.0.0.1:8554/test```
#### Options
```-h, --help``` - displays help
```-t, --timeout <seconds>``` - specifies source timeout
```-c, --connect <attempts>``` - specifies number of connection attempts
```-d, --decode``` - enables or disables video decoding and rendering
```--no-decode``` - disables video decoding and rendering if it was enabled by default
```--stop-decoding <seconds>``` - specifies amount of seconds after which decoding should be stopped
```-r, --record <file>``` - enables record video into file
```-f, --format <format>``` - specifies recording file format, where format 0 - MKV, 1 - MOV, 2 - MP4
```--stop-recording <seconds>``` - specifies amount of seconds after which recording should be stopped
```--video-sink <sink>``` - specifies which video sink to use : 0 - autovideosink, 1 - fakesink
#### Arguments
```url``` - required, specifies video URL.
Following URLs are supported:
```rtsp://<host>:<port>/mount/point``` - usual RTSP URL
```udp://<interface>:<port>``` - H.264 over RTP/UDP
```udp265://<interface>:<port>``` - H.265 over RTP/UDP
```tsusb://<interface>:<port>``` - Taisync's forwarded H.264 byte aligned NALU stream over UDP
```tcp://<host>:<port>``` - MPEG-2 TS over TCP
```mpegts://<interface>:<port>``` - MPEG-2 TS over UDP
......@@ -155,6 +155,9 @@ private:
unsigned int _fileFormat = VideoReceiver::FILE_FORMAT_MIN;
unsigned _stopRecordingAfter = 15;
bool _useFakeSink = false;
bool _streaming = false;
bool _decoding = false;
bool _recording = false;
};
void
......@@ -299,52 +302,27 @@ VideoReceiverApp::exec()
startStreaming();
QObject::connect(_receiver, &VideoReceiver::timeout, [this](){
QObject::connect(_receiver, &VideoReceiver::timeout, [](){
qCDebug(AppLog) << "Streaming timeout";
_dispatch([this](){
if (_receiver->streaming()) {
_receiver->stop();
} else {
if (--_connect > 0) {
qCDebug(AppLog) << "Restarting streaming";
_dispatch([this](){
startStreaming();
});
} else {
qCDebug(AppLog) << "Closing...";
delete _receiver;
_app.exit();
}
}
});
});
QObject::connect(_receiver, &VideoReceiver::streamingChanged, [this](){
if (_receiver->streaming()) {
QObject::connect(_receiver, &VideoReceiver::streamingChanged, [this](bool active){
_streaming = active;
if (_streaming) {
qCDebug(AppLog) << "Streaming started";
} else {
qCDebug(AppLog) << "Streaming stopped";
_dispatch([this](){
if (--_connect > 0) {
qCDebug(AppLog) << "Restarting streaming";
startStreaming();
} else {
qCDebug(AppLog) << "Closing...";
delete _receiver;
_app.exit();
}
});
}
});
QObject::connect(_receiver, &VideoReceiver::decodingChanged, [this](){
if (_receiver->decoding()) {
QObject::connect(_receiver, &VideoReceiver::decodingChanged, [this](bool active){
_decoding = active;
if (_decoding) {
qCDebug(AppLog) << "Decoding started";
} else {
qCDebug(AppLog) << "Decoding stopped";
if (_receiver->streaming()) {
if (!_receiver->recording()) {
if (_streaming) {
if (!_recording) {
_dispatch([this](){
_receiver->stop();
});
......@@ -353,13 +331,14 @@ VideoReceiverApp::exec()
}
});
QObject::connect(_receiver, &VideoReceiver::recordingChanged, [this](){
if (_receiver->recording()) {
QObject::connect(_receiver, &VideoReceiver::recordingChanged, [this](bool active){
_recording = active;
if (_recording) {
qCDebug(AppLog) << "Recording started";
} else {
qCDebug(AppLog) << "Recording stopped";
if (_receiver->streaming()) {
if (!_receiver->decoding()) {
if (_streaming) {
if (!_decoding) {
_dispatch([this](){
_receiver->stop();
});
......@@ -368,6 +347,44 @@ VideoReceiverApp::exec()
}
});
QObject::connect(_receiver, &VideoReceiver::onStartComplete, [this](VideoReceiver::STATUS status){
if (status != VideoReceiver::STATUS_OK) {
qCDebug(AppLog) << "Video receiver start failed";
_dispatch([this](){
if (--_connect > 0) {
qCDebug(AppLog) << "Restarting ...";
_dispatch([this](){
startStreaming();
});
} else {
qCDebug(AppLog) << "Closing...";
delete _receiver;
_app.exit();
}
});
} else {
qCDebug(AppLog) << "Video receiver started";
}
});
QObject::connect(_receiver, &VideoReceiver::onStopComplete, [this](VideoReceiver::STATUS ){
qCDebug(AppLog) << "Video receiver stopped";
_dispatch([this](){
if (--_connect > 0) {
qCDebug(AppLog) << "Restarting ...";
_dispatch([this](){
startStreaming();
});
} else {
qCDebug(AppLog) << "Closing...";
delete _receiver;
_app.exit();
}
});
});
return _app.exec();
}
......
......@@ -11,7 +11,7 @@ if(DEFINED ENV{QT_MKSPEC})
set(QT_MKSPEC $ENV{QT_MKSPEC})
endif()
if(UNIX AND NOT APPLE)
if(UNIX AND NOT APPLE AND NOT ANDROID)
set(LINUX TRUE)
endif()
......
......@@ -44,8 +44,8 @@ Item {
property real _labelFieldWidth: ScreenTools.defaultFontPixelWidth * 28
property real _editFieldWidth: ScreenTools.defaultFontPixelWidth * 30
property real _editFieldHeight: ScreenTools.defaultFontPixelHeight * 2
property var _videoReceiver: QGroundControl.videoManager.videoReceiver
property bool _recordingLocalVideo: _videoReceiver && _videoReceiver.recording
property var _videoManager: QGroundControl.videoManager
property bool _recordingLocalVideo: QGroundControl.videoManager.recording
property var _dynamicCameras: activeVehicle ? activeVehicle.dynamicCameras : null
property bool _isCamera: _dynamicCameras ? _dynamicCameras.cameras.count > 0 : false
......@@ -305,15 +305,15 @@ Item {
_camera.stopVideo()
//-- Local video as well
if (_recordingVideo) {
_videoReceiver.stopRecording()
_videoManager.stopRecording()
}
} else {
if(!_fullSD) {
_camera.startVideo()
}
//-- Local video as well
if(_videoReceiver) {
_videoReceiver.startRecording()
if(_videoManager) {
_videoManager.startRecording()
}
}
} else {
......
......@@ -29,12 +29,8 @@
QGC_LOGGING_CATEGORY(CustomLog, "CustomLog")
CustomVideoReceiver::CustomVideoReceiver(QObject* parent)
: VideoReceiver(parent)
: GstVideoReceiver(parent)
{
#if defined(QGC_GST_STREAMING)
//-- Shorter RTSP test interval
_restart_time_ms = 1000;
#endif
}
CustomVideoReceiver::~CustomVideoReceiver()
......
......@@ -14,7 +14,7 @@
#include "QGCCorePlugin.h"
#include "QGCOptions.h"
#include "QGCLoggingCategory.h"
#include "VideoReceiver.h"
#include "GstVideoReceiver.h"
#include "SettingsManager.h"
#include <QTranslator>
......@@ -25,7 +25,7 @@ class CustomSettings;
Q_DECLARE_LOGGING_CATEGORY(CustomLog)
//-- Our own, custom video receiver
class CustomVideoReceiver : public VideoReceiver
class CustomVideoReceiver : public GstVideoReceiver
{
Q_OBJECT
public:
......
......@@ -20,10 +20,10 @@ CustomVideoManager::CustomVideoManager(QGCApplication* app, QGCToolbox* toolbox)
//-----------------------------------------------------------------------------
void
CustomVideoManager::_updateSettings()
CustomVideoManager::_updateSettings(unsigned id)
{
if(!_videoSettings || !_videoReceiver)
return;
VideoManager::_updateSettings();
VideoManager::_updateSettings(id);
}
......@@ -23,6 +23,6 @@ public:
CustomVideoManager (QGCApplication* app, QGCToolbox* toolbox);
protected:
void _updateSettings ();
void _updateSettings (unsigned id);
};
......@@ -8595,7 +8595,8 @@ for current-based compensation [G/kA]</short_desc>
<values>
<value code="0">Disabled</value>
<value code="1">Throttle-based compensation</value>
<value code="2">Current-based compensation</value>
<value code="2">Current-based compensation (battery_status instance 0)</value>
<value code="3">Current-based compensation (battery_status instance 1)</value>
</values>
</parameter>
<parameter category="System" default="0" name="CAL_MAG_PRIME" type="INT32">
......@@ -10348,8 +10349,7 @@ How often the sensor is readout</short_desc>
</parameter>
<parameter default="0" name="TC_A_ENABLE" type="INT32">
<short_desc>Thermal compensation for accelerometer sensors</short_desc>
<min>0</min>
<max>1</max>
<reboot_required>true</reboot_required>
</parameter>
<parameter category="System" default="0" name="TC_B0_ID" type="INT32">
<short_desc>ID of Barometer that the calibration is for</short_desc>
......@@ -10452,8 +10452,7 @@ How often the sensor is readout</short_desc>
</parameter>
<parameter default="0" name="TC_B_ENABLE" type="INT32">
<short_desc>Thermal compensation for barometric pressure sensors</short_desc>
<min>0</min>
<max>1</max>
<reboot_required>true</reboot_required>
</parameter>
<parameter category="System" default="0" name="TC_G0_ID" type="INT32">
<short_desc>ID of Gyro that the calibration is for</short_desc>
......@@ -10628,8 +10627,7 @@ How often the sensor is readout</short_desc>
</parameter>
<parameter default="0" name="TC_G_ENABLE" type="INT32">
<short_desc>Thermal compensation for rate gyro sensors</short_desc>
<min>0</min>
<max>1</max>
<reboot_required>true</reboot_required>
</parameter>
</group>
<group name="UAVCAN">
......@@ -10804,9 +10802,9 @@ tailsitter, tiltrotor: main throttle</short_desc>
<increment>0.01</increment>
</parameter>
<parameter default="5.0" name="VT_DWN_PITCH_MAX" type="FLOAT">
<short_desc>Maximum allowed down-pitch the controller is able to demand. This prevents large, negative
lift values being created when facing strong winds. The vehicle will use the pusher motor
to accelerate forward if necessary</short_desc>
<short_desc>Maximum allowed angle the vehicle is allowed to pitch down to generate forward force
when fixed-wing forward actuation is active (seeVT_FW_TRHUST_EN).
If demanded down pitch exceeds this limmit, the fixed-wing forward actuators are used instead</short_desc>
<min>0.0</min>
<max>45.0</max>
</parameter>
......@@ -10814,9 +10812,24 @@ to accelerate forward if necessary</short_desc>
<short_desc>Lock elevons in multicopter mode</short_desc>
<long_desc>If set to 1 the elevons are locked in multicopter mode</long_desc>
</parameter>
<parameter default="0.0" name="VT_FWD_THRUST_SC" type="FLOAT">
<short_desc>Fixed wing thrust scale for hover forward flight</short_desc>
<long_desc>Scale applied to fixed wing thrust being used as source for forward acceleration in multirotor mode. This technique can be used to avoid the plane having to pitch down a lot in order to move forward. Setting this value to 0 (default) will disable this strategy.</long_desc>
<parameter default="0" name="VT_FWD_THRUST_EN" type="INT32">
<short_desc>Enable/disable usage of fixed-wing actuators in hover to generate forward force (instead of pitching down).
This technique can be used to avoid the plane having to pitch down in order to move forward.
This prevents large, negative lift values being created when facing strong winds.
Fixed-wing forward actuators refers to puller/pusher (standard VTOL), or forward-tilt (tiltrotor VTOL).
Only active if demaded down pitch is above VT_DWN_PITCH_MAX, and uses VT_FWD_THRUST_SC to get from
demanded down pitch to fixed-wing actuation</short_desc>
<values>
<value code="0">Disable FW forward actuation in hover.</value>
<value code="1">Enable FW forward actuation in hover in altitude, position and auto modes (except LANDING).</value>
<value code="2">Enable FW forward actuation in hover in altitude, position and auto modes if above MPC_LAND_ALT1.</value>
<value code="3">Enable FW forward actuation in hover in altitude, position and auto modes if above MPC_LAND_ALT2.</value>
<value code="4">Enable FW forward actuation in hover in altitude, position and auto modes.</value>
</values>
</parameter>
<parameter default="0.7" name="VT_FWD_THRUST_SC" type="FLOAT">
<short_desc>Fixed-wing actuator thrust scale for hover forward flight</short_desc>
<long_desc>Scale applied to the demanded down-pitch to get the fixed-wing forward actuation in hover mode. Only active if demaded down pitch is above VT_DWN_PITCH_MAX. Enabled via VT_FWD_THRUST_EN.</long_desc>
<min>0.0</min>
<max>2.0</max>
</parameter>
......
......@@ -25,7 +25,6 @@ Item {
clip: true
property double _ar: QGroundControl.videoManager.aspectRatio
property bool _showGrid: QGroundControl.settingsManager.videoSettings.gridLines.rawValue > 0
property var _videoReceiver: QGroundControl.videoManager.videoReceiver
property var _dynamicCameras: activeVehicle ? activeVehicle.dynamicCameras : null
property bool _connected: activeVehicle ? !activeVehicle.connectionLost : false
property int _curCameraIndex: _dynamicCameras ? _dynamicCameras.currentCamera : 0
......@@ -40,7 +39,7 @@ Item {
id: noVideo
anchors.fill: parent
color: Qt.rgba(0,0,0,0.75)
visible: !(_videoReceiver && _videoReceiver.decoding)
visible: !(QGroundControl.videoManager.decoding)
QGCLabel {
text: QGroundControl.settingsManager.videoSettings.streamEnabled.rawValue ? qsTr("WAITING FOR VIDEO") : qsTr("VIDEO DISABLED")
font.family: ScreenTools.demiboldFontFamily
......@@ -58,7 +57,7 @@ Item {
Rectangle {
anchors.fill: parent
color: "black"
visible: _videoReceiver && _videoReceiver.decoding
visible: QGroundControl.videoManager.decoding
function getWidth() {
//-- Fit Width or Stretch
if(_fitMode === 0 || _fitMode === 2) {
......@@ -80,10 +79,9 @@ Item {
QGCVideoBackground {
id: videoContent
objectName: "videoContent"
receiver: _videoReceiver
Connections {
target: _videoReceiver
target: QGroundControl.videoManager
onImageFileChanged: {
videoContent.grabToImage(function(result) {
if (!result.saveToFile(QGroundControl.videoManager.imageFile)) {
......@@ -130,7 +128,7 @@ Item {
height: parent.getHeight()
width: parent.getWidth()
anchors.centerIn: parent
visible: _videoReceiver && _videoReceiver.decoding
visible: QGroundControl.videoManager.decoding
sourceComponent: videoBackgroundComponent
property bool videoDisabled: QGroundControl.settingsManager.videoSettings.videoSource.rawValue === QGroundControl.settingsManager.videoSettings.disabledVideoSource
......
......@@ -38,6 +38,7 @@ MapQuickItem {
showGimbalYaw: !isNaN(missionItem.missionGimbalYaw)
highlightSelected: true
onClicked: _item.clicked()
opacity: _item.opacity
property bool _isCurrentItem: missionItem ? missionItem.isCurrentItem || missionItem.hasCurrentChildItem : false
}
......
......@@ -71,6 +71,7 @@ Rectangle {
drag.maximumX: itemDragger.parent.width - parent.width
drag.maximumY: itemDragger.parent.height - parent.height
preventStealing: true
enabled: itemDragger.visible
onClicked: {
focus = true
......
......@@ -31,9 +31,8 @@ Item {
anchors.centerIn: parent
property bool _communicationLost: activeVehicle ? activeVehicle.connectionLost : false
property var _videoReceiver: QGroundControl.videoManager.videoReceiver
property bool _recordingVideo: _videoReceiver && _videoReceiver.recording
property bool _decodingVideo: _videoReceiver && _videoReceiver.decoding
property bool _recordingVideo: QGroundControl.videoManager.recording
property bool _decodingVideo: QGroundControl.videoManager.decoding
property bool _streamingEnabled: QGroundControl.settingsManager.videoSettings.streamConfigured
property var _dynamicCameras: activeVehicle ? activeVehicle.dynamicCameras : null
property int _curCameraIndex: _dynamicCameras ? _dynamicCameras.currentCamera : 0
......@@ -70,10 +69,10 @@ Item {
onClicked: {
if(checked) {
QGroundControl.settingsManager.videoSettings.streamEnabled.rawValue = 1
_videoReceiver.start()
QGroundControl.videoManager.startVideo()
} else {
QGroundControl.settingsManager.videoSettings.streamEnabled.rawValue = 0
_videoReceiver.stop()
QGroundControl.videoManager.stopVideo()
}
}
}
......
......@@ -40,6 +40,8 @@ if(BUILD_TESTING)
SurveyComplexItemTest.h
TransectStyleComplexItemTest.cc
TransectStyleComplexItemTest.h
TransectStyleComplexItemTestBase.cc
TransectStyleComplexItemTestBase.h
VisualMissionItemTest.cc
VisualMissionItemTest.h
)
......
......@@ -301,7 +301,7 @@ Item {
sourceItem: SplitIndicator {
z: _zorderSplitHandle
onClicked: mapPolygon.splitPolygonSegment(mapQuickItem.vertexIndex)
onClicked: if(_root.interactive) mapPolygon.splitPolygonSegment(mapQuickItem.vertexIndex)
}
}
}
......@@ -366,7 +366,7 @@ Item {
}
}
onClicked: menu.popupVertex(polygonVertex)
onClicked: if(_root.interactive) menu.popupVertex(polygonVertex)
}
}
......@@ -574,7 +574,7 @@ Item {
z: QGroundControl.zOrderMapItems + 1 // Over item indicators
onClicked: {
if (mouse.button === Qt.LeftButton) {
if (mouse.button === Qt.LeftButton && _root.interactive) {
mapPolygon.appendVertex(mapControl.toCoordinate(Qt.point(mouse.x, mouse.y), false /* clipToViewPort */))
}
}
......@@ -596,7 +596,7 @@ Item {
height: width
radius: width / 2
color: "white"
opacity: .90
opacity: interiorOpacity * .90
}
}
}
......
......@@ -175,6 +175,7 @@ Item {
line.color: lineColor
path: mapPolyline.path
visible: _root.visible
opacity: _root.opacity
}
}
......@@ -186,6 +187,7 @@ Item {
anchorPoint.x: sourceItem.width / 2
anchorPoint.y: sourceItem.height / 2
z: _zorderSplitHandle
opacity: _root.opacity
property int vertexIndex
......@@ -205,6 +207,8 @@ Item {
property var _splitHandle
property var _vertices: mapPolyline.path
opacity: _root.opacity
function _setHandlePosition() {
var nextIndex = index + 1
var distance = _vertices[index].distanceTo(_vertices[nextIndex])
......@@ -238,6 +242,7 @@ Item {
mapControl: _root.mapControl
id: dragArea
z: _zorderDragHandle
opacity: _root.opacity
property int polylineVertex
......@@ -267,6 +272,7 @@ Item {
anchorPoint.x: dragHandle.width / 2
anchorPoint.y: dragHandle.height / 2
z: _zorderDragHandle
opacity: _root.opacity
property int polylineVertex
......@@ -292,6 +298,8 @@ Item {
delegate: Item {
property var _visuals: [ ]
opacity: _root.opacity
Component.onCompleted: {
var dragHandle = dragHandleComponent.createObject(mapControl)
dragHandle.coordinate = Qt.binding(function() { return object.coordinate })
......@@ -366,7 +374,7 @@ Item {
z: QGroundControl.zOrderMapItems + 1 // Over item indicators
onClicked: {
if (mouse.button === Qt.LeftButton) {
if (mouse.button === Qt.LeftButton && _root.interactive) {
mapPolyline.appendVertex(mapControl.toCoordinate(Qt.point(mouse.x, mouse.y), false /* clipToViewPort */))
}
}
......
......@@ -25,9 +25,10 @@ TransectStyleMapVisuals {
id: mapPolylineVisuals
mapControl: map
mapPolyline: object.corridorPolyline
interactive: _currentItem
interactive: _currentItem && parent.interactive
lineWidth: 3
lineColor: "#be781c"
visible: _currentItem
opacity: parent.opacity
}
}
......@@ -24,6 +24,7 @@ Item {
id: _root
property var map ///< Map control to place item in
property bool interactive: true
signal clicked(int sequenceNumber)
......@@ -178,6 +179,7 @@ Item {
MouseArea {
anchors.fill: map
z: QGroundControl.zOrderMapItems + 1 // Over item indicators
visible: _root.interactive
readonly property int _decimalPlaces: 8
......@@ -199,6 +201,7 @@ Item {
mapControl: _root.map
itemIndicator: _loiterPointObject
itemCoordinate: _missionItem.loiterCoordinate
visible: _root.interactive
property bool _preventReentrancy: false
......@@ -224,6 +227,7 @@ Item {
mapControl: _root.map
itemIndicator: _landingPointObject
itemCoordinate: _missionItem.landingCoordinate
visible: _root.interactive
onItemCoordinateChanged: _missionItem.moveLandingPosition(itemCoordinate)
}
......
......@@ -39,8 +39,8 @@ Item {
property int _borderWidthExclusion: 0
property color _interiorColorExclusion: "orange"
property color _interiorColorInclusion: "transparent"
property real _interiorOpacityExclusion: 0.2
property real _interiorOpacityInclusion: 1
property real _interiorOpacityExclusion: 0.2 * opacity
property real _interiorOpacityInclusion: 1 * opacity
function addPolygon(inclusionPolygon) {
// Initial polygon is inset to take 2/3rds space
......@@ -104,6 +104,7 @@ Item {
borderColor: _borderColor
interiorColor: object.inclusion ? _interiorColorInclusion : _interiorColorExclusion
interiorOpacity: object.inclusion ? _interiorOpacityInclusion : _interiorOpacityExclusion
interactive: _root.interactive && mapPolygon && mapPolygon.interactive
}
}
......@@ -118,6 +119,7 @@ Item {
borderColor: _borderColor
interiorColor: object.inclusion ? _interiorColorInclusion : _interiorColorExclusion
interiorOpacity: object.inclusion ? _interiorOpacityInclusion : _interiorOpacityExclusion
interactive: _root.interactive && mapCircle && mapCircle.interactive
}
}
......@@ -146,7 +148,7 @@ Item {
MissionItemIndicatorDrag {
mapControl: map
itemCoordinate: myGeoFenceController.breachReturnPoint
//visible: itemCoordinate.isValid
visible: _root.interactive
onItemCoordinateChanged: myGeoFenceController.breachReturnPoint = itemCoordinate
}
......@@ -162,6 +164,7 @@ Item {
anchorPoint.y: sourceItem.anchorPointY
z: QGroundControl.zOrderMapItems
coordinate: myGeoFenceController.breachReturnPoint
opacity: _root.opacity
sourceItem: MissionItemIndexLabel {
label: qsTr("B", "Breach Return Point item indicator")
......
......@@ -23,6 +23,7 @@ Item {
property var map ///< Map control to place item in
property var vehicle ///< Vehicle associated with this item
property var interactive: true ///< Vehicle associated with this item
signal clicked(int sequenceNumber)
......@@ -34,7 +35,7 @@ Item {
if (component.status === Component.Error) {
console.log("Error loading Qml: ", object.mapVisualQML, component.errorString())
}
_visualItem = component.createObject(map, { "map": _root.map, vehicle: _root.vehicle })
_visualItem = component.createObject(map, { "map": _root.map, vehicle: _root.vehicle, 'opacity': Qt.binding(function() { return _root.opacity }), 'interactive': Qt.binding(function() { return _root.interactive }) })
_visualItem.clicked.connect(_root.clicked)
}
}
......
......@@ -390,6 +390,7 @@ Item {
property real _leftToolWidth: toolStrip.x + toolStrip.width
property real _rightToolWidth: rightPanel.width + rightPanel.anchors.rightMargin
property real _nonInteractiveOpacity: 0.5
// Initial map position duplicates Fly view position
Component.onCompleted: editorMap.center = QGroundControl.flightMapPosition
......@@ -436,18 +437,20 @@ Item {
// Add the mission item visuals to the map
Repeater {
model: _editingLayer == _layerMission ? _missionController.visualItems : undefined
model: _missionController.visualItems
delegate: MissionItemMapVisual {
map: editorMap
onClicked: _missionController.setCurrentPlanViewSeqNum(sequenceNumber, false)
visible: _editingLayer == _layerMission
opacity: _editingLayer == _layerMission ? 1 : editorMap._nonInteractiveOpacity
interactive: _editingLayer == _layerMission
}
}
// Add lines between waypoints
MissionLineView {
showSpecialVisual: _missionController.isROIBeginCurrentItem
model: _editingLayer == _layerMission ? _missionController.simpleFlightPathSegments : undefined
model: _missionController.simpleFlightPathSegments
opacity: _editingLayer == _layerMission ? 1 : editorMap._nonInteractiveOpacity
}
// Direction arrows in waypoint lines
......@@ -464,13 +467,14 @@ Item {
// Incomplete segment lines
MapItemView {
model: _editingLayer == _layerMission ? _missionController.incompleteComplexItemLines : undefined
model: _missionController.incompleteComplexItemLines
delegate: MapPolyline {
path: [ object.coordinate1, object.coordinate2 ]
line.width: 1
line.color: "red"
z: QGroundControl.zOrderWaypointLines
opacity: _editingLayer == _layerMission ? 1 : editorMap._nonInteractiveOpacity
}
}
......@@ -513,8 +517,7 @@ Item {
// Add the vehicles to the map
MapItemView {
model: QGroundControl.multiVehicleManager.vehicles
delegate:
VehicleMapItem {
delegate: VehicleMapItem {
vehicle: object
coordinate: object.coordinate
map: editorMap
......@@ -529,6 +532,7 @@ Item {
interactive: _editingLayer == _layerGeoFence
homePosition: _missionController.plannedHomePosition
planView: true
opacity: _editingLayer != _layerGeoFence ? editorMap._nonInteractiveOpacity : 1
}
RallyPointMapVisuals {
......@@ -536,6 +540,7 @@ Item {
myRallyPointController: _rallyPointController
interactive: _editingLayer == _layerRallyPoints
planView: true
opacity: _editingLayer != _layerRallyPoints ? editorMap._nonInteractiveOpacity : 1
}
// Airspace overlap support
......@@ -851,6 +856,7 @@ Item {
flightMap: editorMap
visible: _editingLayer == _layerGeoFence
}
// Rally Point Editor
RallyPointEditorHeader {
id: rallyPointHeader
......
......@@ -47,7 +47,7 @@ Item {
MissionItemIndicatorDrag {
mapControl: _root.map
itemCoordinate: rallyPointObject.coordinate
visible: rallyPointObject === myRallyPointController.currentRallyPoint
visible: rallyPointObject === myRallyPointController.currentRallyPoint && _root.interactive
property var rallyPointObject
......@@ -63,6 +63,7 @@ Item {
anchorPoint.x: sourceItem.anchorPointX
anchorPoint.y: sourceItem.anchorPointY
z: QGroundControl.zOrderMapItems
opacity: _root.opacity
property var rallyPointObject
......@@ -84,6 +85,7 @@ Item {
model: _rallyPoints
delegate: Item {
opacity: _root.opacity
property var _visuals: [ ]
Component.onCompleted: {
......
......@@ -24,6 +24,7 @@ Item {
property var map ///< Map control to place item in
property var vehicle ///< Vehicle associated with this item
property bool interactive: true
property var _missionItem: object
property var _itemVisual
......@@ -95,6 +96,7 @@ Item {
mapControl: _root.map
itemIndicator: _itemVisual
itemCoordinate: _missionItem.coordinate
visible: _root.interactive
onItemCoordinateChanged: _missionItem.coordinate = itemCoordinate
}
......@@ -109,7 +111,8 @@ Item {
z: QGroundControl.zOrderMapItems
missionItem: _missionItem
sequenceNumber: _missionItem.sequenceNumber
onClicked: _root.clicked(_missionItem.sequenceNumber)
onClicked: if(_root.interactive) _root.clicked(_missionItem.sequenceNumber)
opacity: _root.opacity
}
}
}
......@@ -27,6 +27,7 @@ Item {
property var _missionItem: object
property var _structurePolygon: object.structurePolygon
property var _flightPolygon: object.flightPolygon
property bool interactive: parent.interactive
signal clicked(int sequenceNumber)
......@@ -43,12 +44,12 @@ Item {
QGCMapPolygonVisuals {
mapControl: map
mapPolygon: _structurePolygon
interactive: _missionItem.isCurrentItem
interactive: _missionItem.isCurrentItem && _root.interactive
borderWidth: 1
borderColor: "black"
interiorColor: "green"
altColor: "red"
interiorOpacity: 0.25
interiorOpacity: 0.5 * _root.opacity
}
QGCMapPolygonVisuals {
......@@ -57,6 +58,7 @@ Item {
interactive: false
borderWidth: 2
borderColor: "white"
interiorOpacity: _root.opacity
}
// Entry point
......@@ -68,7 +70,7 @@ Item {
anchorPoint.y: sourceItem.anchorPointY
z: QGroundControl.zOrderMapItems
coordinate: _missionItem.coordinate
visible: _missionItem.exitCoordinate.isValid
visible: _missionItem.exitCoordinate.isValid && _root.interactive
sourceItem: MissionItemIndexLabel {
index: _missionItem.sequenceNumber
......@@ -88,7 +90,7 @@ Item {
anchorPoint.y: sourceItem.anchorPointY
z: QGroundControl.zOrderMapItems
coordinate: _missionItem.exitCoordinate
visible: _missionItem.exitCoordinate.isValid
visible: _missionItem.exitCoordinate.isValid && _root.interactive
sourceItem: MissionItemIndexLabel {
index: _missionItem.lastSequenceNumber
......
......@@ -24,6 +24,7 @@ Item {
property var map ///< Map control to place item in
property var vehicle ///< Vehicle associated with this item
property bool interactive: true
property var _missionItem: object
property var _takeoffIndicatorItem
......@@ -78,6 +79,7 @@ Item {
mapControl: _root.map
itemIndicator: _takeoffIndicatorItem
itemCoordinate: _missionItem.specifiesCoordinate ? _missionItem.coordinate : _missionItem.launchCoordinate
visible: _root.interactive
onItemCoordinateChanged: {
if (_missionItem.specifiesCoordinate) {
......@@ -96,7 +98,7 @@ Item {
mapControl: _root.map
itemIndicator: _launchIndicatorItem
itemCoordinate: _missionItem.launchCoordinate
visible: !_missionItem.launchTakeoffAtSameLocation
visible: !_missionItem.launchTakeoffAtSameLocation && _root.interactive
onItemCoordinateChanged: _missionItem.launchCoordinate = itemCoordinate
}
......@@ -111,6 +113,7 @@ Item {
missionItem: _missionItem
sequenceNumber: _missionItem.sequenceNumber
onClicked: _root.clicked(_missionItem.sequenceNumber)
opacity: _root.opacity
}
}
......@@ -121,7 +124,7 @@ Item {
coordinate: _missionItem.launchCoordinate
anchorPoint.x: sourceItem.anchorPointX
anchorPoint.y: sourceItem.anchorPointY
visible: !_missionItem.launchTakeoffAtSameLocation
visible: !_missionItem.launchTakeoffAtSameLocation && _root.interactive
sourceItem:
MissionItemIndexLabel {
......@@ -129,6 +132,7 @@ Item {
label: qsTr("Launch")
highlightSelected: true
onClicked: _root.clicked(_missionItem.sequenceNumber)
visible: _root.interactive
}
}
}
......@@ -140,7 +144,7 @@ Item {
MouseArea {
anchors.fill: map
z: QGroundControl.zOrderMapItems + 1 // Over item indicators
visible: !_missionItem.launchCoordinate.isValid
visible: !_missionItem.launchCoordinate.isValid && _root.interactive
readonly property int _decimalPlaces: 8
......
......@@ -24,6 +24,7 @@ Item {
property var map ///< Map control to place item in
property bool polygonInteractive: true
property bool interactive: true
property var _missionItem: object
property var _mapPolygon: object.surveyAreaPolygon
......@@ -70,12 +71,12 @@ Item {
id: mapPolygonVisuals
mapControl: map
mapPolygon: _mapPolygon
interactive: polygonInteractive && _missionItem.isCurrentItem
interactive: polygonInteractive && _missionItem.isCurrentItem && _root.interactive
borderWidth: 1
borderColor: "black"
interiorColor: QGroundControl.globalPalette.surveyPolygonInterior
altColor: QGroundControl.globalPalette.surveyPolygonTerrainCollision
interiorOpacity: 0.5
interiorOpacity: 0.5 * _root.opacity
}
// Full set of transects lines. Shown when item is selected.
......@@ -87,6 +88,7 @@ Item {
line.width: 2
path: _transectPoints
visible: _currentItem
opacity: _root.opacity
}
}
......@@ -99,6 +101,7 @@ Item {
line.width: 2
path: _showPartialEntryExit ? [ _transectPoints[0], _transectPoints[1] ] : []
visible: _showPartialEntryExit
opacity: _root.opacity
}
}
Component {
......@@ -109,6 +112,7 @@ Item {
line.width: 2
path: _showPartialEntryExit ? [ _transectPoints[_lastPointIndex - 1], _transectPoints[_lastPointIndex] ] : []
visible: _showPartialEntryExit
opacity: _root.opacity
}
}
......@@ -122,11 +126,12 @@ Item {
z: QGroundControl.zOrderMapItems
coordinate: _missionItem.coordinate
visible: _missionItem.exitCoordinate.isValid
opacity: _root.opacity
sourceItem: MissionItemIndexLabel {
index: _missionItem.sequenceNumber
checked: _missionItem.isCurrentItem
onClicked: _root.clicked(_missionItem.sequenceNumber)
onClicked: if(_root.interactive) _root.clicked(_missionItem.sequenceNumber)
}
}
}
......@@ -139,6 +144,7 @@ Item {
toCoord: _transectPoints[_firstTrueTransectIndex + 1]
arrowPosition: 1
visible: _currentItem
opacity: _root.opacity
}
}
......@@ -150,6 +156,7 @@ Item {
toCoord: _transectPoints[nextTrueTransectIndex + 1]
arrowPosition: 1
visible: _currentItem && _transectCount > 3
opacity: _root.opacity
property int nextTrueTransectIndex: _firstTrueTransectIndex + (_hasTurnaround ? 4 : 2)
}
......@@ -163,6 +170,7 @@ Item {
toCoord: _transectPoints[_lastTrueTransectIndex]
arrowPosition: 3
visible: _currentItem
opacity: _root.opacity
}
}
......@@ -174,6 +182,7 @@ Item {
toCoord: _transectPoints[prevTrueTransectIndex]
arrowPosition: 13
visible: _currentItem && _transectCount > 3
opacity: _root.opacity
property int prevTrueTransectIndex: _lastTrueTransectIndex - (_hasTurnaround ? 4 : 2)
}
......@@ -189,11 +198,12 @@ Item {
z: QGroundControl.zOrderMapItems
coordinate: _missionItem.exitCoordinate
visible: _missionItem.exitCoordinate.isValid
opacity: _root.opacity
sourceItem: MissionItemIndexLabel {
index: _missionItem.lastSequenceNumber
checked: _missionItem.isCurrentItem
onClicked: _root.clicked(_missionItem.sequenceNumber)
onClicked: if(_root.interactive) _root.clicked(_missionItem.sequenceNumber)
}
}
}
......
......@@ -11,7 +11,6 @@
#include <QApplication>
#include <QTimer>
#include <QQmlApplicationEngine>
#include <QElapsedTimer>
#include <QMap>
#include <QSet>
......@@ -38,6 +37,7 @@
#endif
// Work around circular header includes
class QQmlApplicationEngine;
class QGCSingleton;
class QGCToolbox;
class QGCFileDownload;
......
......@@ -11,6 +11,7 @@ import QtQuick 2.3
import QtQuick.Controls 1.2
import QtQuick.Controls.Styles 1.4
import QtQuick.Dialogs 1.2
import QtQuick.Layouts 1.12
import QGroundControl 1.0
import QGroundControl.Palette 1.0
......@@ -30,30 +31,65 @@ Item {
QGCViewDialog {
QGCFlickable {
anchors.fill: parent
contentHeight: categoryColumn.height
clip: true
Column {
id: categoryColumn
ColumnLayout {
anchors.fill: parent
RowLayout {
spacing: ScreenTools.defaultFontPixelHeight / 2
Layout.alignment: Qt.AlignVCenter
Layout.fillHeight: true
Layout.fillWidth: true
QGCLabel {
text: qsTr("Search:")
}
QGCTextField {
id: searchText
text: ""
Layout.fillWidth: true
enabled: true
}
QGCButton {
text: qsTr("Clear All")
onClicked: {
var logCats = QGroundControl.loggingCategories()
for (var i=0; i<logCats.length; i++) {
QGroundControl.setCategoryLoggingOn(logCats[i], false)
text: qsTr("Clear")
onClicked: searchText.text = ""
}
QGroundControl.updateLoggingFilterRules()
categoryRepeater.model = undefined
categoryRepeater.model = QGroundControl.loggingCategories()
}
Row {
spacing: ScreenTools.defaultFontPixelHeight / 2
QGCButton {
text: qsTr("Clear All")
onClicked: categoryRepeater.setAllLogs(false)
}
}
Column {
id: categoryColumn
spacing: ScreenTools.defaultFontPixelHeight / 2
Repeater {
id: categoryRepeater
model: QGroundControl.loggingCategories()
function setAllLogs(value) {
var logCategories = QGroundControl.loggingCategories()
for (var category of logCategories) {
QGroundControl.setCategoryLoggingOn(category, value)
}
QGroundControl.updateLoggingFilterRules()
// Update model for repeater
categoryRepeater.model = undefined
categoryRepeater.model = QGroundControl.loggingCategories()
}
QGCCheckBox {
text: modelData
visible: searchText.text ? text.match(`(${searchText.text})`, "i") : true
checked: QGroundControl.categoryLoggingOn(modelData)
onClicked: {
QGroundControl.setCategoryLoggingOn(modelData, checked)
......@@ -65,6 +101,7 @@ Item {
}
}
}
}
Item {
id: panel
......
This diff is collapsed.
......@@ -49,8 +49,12 @@ public:
Q_PROPERTY(double hfov READ hfov NOTIFY aspectRatioChanged)
Q_PROPERTY(double thermalHfov READ thermalHfov NOTIFY aspectRatioChanged)
Q_PROPERTY(bool autoStreamConfigured READ autoStreamConfigured NOTIFY autoStreamConfiguredChanged)
Q_PROPERTY(bool hasThermal READ hasThermal NOTIFY aspectRatioChanged)
Q_PROPERTY(bool hasThermal READ hasThermal NOTIFY decodingChanged)
Q_PROPERTY(QString imageFile READ imageFile NOTIFY imageFileChanged)
Q_PROPERTY(bool streaming READ streaming NOTIFY streamingChanged)
Q_PROPERTY(bool decoding READ decoding NOTIFY decodingChanged)
Q_PROPERTY(bool recording READ recording NOTIFY recordingChanged)
Q_PROPERTY(QSize videoSize READ videoSize NOTIFY videoSizeChanged)
virtual bool hasVideo ();
virtual bool isGStreamer ();
......@@ -65,9 +69,27 @@ public:
virtual bool hasThermal ();
virtual QString imageFile ();
bool streaming(void) {
return _streaming;
}
virtual VideoReceiver* videoReceiver () { return _videoReceiver; }
virtual VideoReceiver* thermalVideoReceiver () { return _thermalVideoReceiver; }
bool decoding(void) {
return _decoding;
}
bool recording(void) {
return _recording;
}
QSize videoSize(void) {
const quint32 size = _videoSize;
return QSize((size >> 16) & 0xFFFF, size & 0xFFFF);
}
// FIXME: AV: they should be removed after finishing multiple video stream support
// new arcitecture does not assume direct access to video receiver from QML side, even if it works for now
virtual VideoReceiver* videoReceiver () { return _videoReceiver[0]; }
virtual VideoReceiver* thermalVideoReceiver () { return _videoReceiver[1]; }
#if defined(QGC_DISABLE_UVC)
virtual bool uvcEnabled () { return false; }
......@@ -99,6 +121,11 @@ signals:
void aspectRatioChanged ();
void autoStreamConfiguredChanged();
void imageFileChanged ();
void streamingChanged ();
void decodingChanged ();
void recordingChanged ();
void recordingStarted ();
void videoSizeChanged ();
protected slots:
void _videoSourceChanged ();
......@@ -115,28 +142,34 @@ protected:
friend class FinishVideoInitialization;
void _initVideo ();
void _updateSettings ();
void _setVideoUri (const QString& uri);
void _setThermalVideoUri (const QString& uri);
bool _updateSettings (unsigned id);
bool _updateVideoUri (unsigned id, const QString& uri);
void _cleanupOldVideos ();
void _restartVideo ();
void _streamingChanged ();
void _recordingStarted ();
void _recordingChanged ();
void _screenshotComplete ();
void _restartAllVideos ();
void _restartVideo (unsigned id);
void _startReceiver (unsigned id);
void _stopReceiver (unsigned id);
protected:
QString _videoFile;
QString _imageFile;
SubtitleWriter _subtitleWriter;
bool _isTaisync = false;
VideoReceiver* _videoReceiver = nullptr;
VideoReceiver* _thermalVideoReceiver = nullptr;
void* _videoSink = nullptr;
void* _thermalVideoSink = nullptr;
VideoReceiver* _videoReceiver[2] = { nullptr, nullptr };
void* _videoSink[2] = { nullptr, nullptr };
QString _videoUri[2];
// FIXME: AV: _videoStarted seems to be access from 3 different threads, from time to time
// 1) Video Receiver thread
// 2) Video Manager/main app thread
// 3) Qt rendering thread (during video sink creation process which should happen in this thread)
// It works for now but...
bool _videoStarted[2] = { false, false };
bool _lowLatencyStreaming[2] = { false, false };
QAtomicInteger<bool> _streaming = false;
QAtomicInteger<bool> _decoding = false;
QAtomicInteger<bool> _recording = false;
QAtomicInteger<quint32> _videoSize = 0;
VideoSettings* _videoSettings = nullptr;
QString _videoUri;
QString _thermalVideoUri;
QString _videoSourceID;
bool _fullScreen = false;
Vehicle* _activeVehicle = nullptr;
......
......@@ -105,9 +105,28 @@ static void qgcputenv(const QString& key, const QString& root, const QString& pa
}
#endif
static void
blacklist()
{
GstRegistry* reg;
if ((reg = gst_registry_get()) == nullptr) {
return;
}
GstPluginFeature* plugin;
if ((plugin = gst_registry_lookup_feature(reg, "bcmdec")) != nullptr) {
qCCritical(GStreamerLog) << "Disable bcmdec";
gst_plugin_feature_set_rank(plugin, GST_RANK_NONE);
}
}
void
GStreamer::initialize(int argc, char* argv[], int debuglevel)
{
qRegisterMetaType<VideoReceiver::STATUS>("STATUS");
#ifdef Q_OS_MAC
#ifdef QGC_INSTALL_RELEASE
QString currentDir = QCoreApplication::applicationDirPath();
......@@ -171,6 +190,8 @@ GStreamer::initialize(int argc, char* argv[], int debuglevel)
gst_ios_post_init();
#endif
blacklist();
/* the plugin must be loaded before loading the qml file to register the
* GstGLVideoItem qml item
* FIXME Add a QQmlExtensionPlugin into qmlglsink to register GstGLVideoItem
......
This diff is collapsed.
......@@ -89,7 +89,7 @@ public:
~GstVideoReceiver(void);
public slots:
virtual void start(const QString& uri, unsigned timeout);
virtual void start(const QString& uri, unsigned timeout, int buffer = 0);
virtual void stop(void);
virtual void startDecoding(void* sink);
virtual void stopDecoding(void);
......@@ -102,11 +102,6 @@ protected slots:
virtual void _handleEOS(void);
protected:
void _setVideoSize(const QSize& size) {
_videoSize = ((quint32)size.width() << 16) | (quint32)size.height();
emit videoSizeChanged();
}
virtual GstElement* _makeSource(const QString& uri);
virtual GstElement* _makeDecoder(GstCaps* caps, GstElement* videoSink);
virtual GstElement* _makeFileSink(const QString& videoFile, FILE_FORMAT format);
......@@ -118,16 +113,19 @@ protected:
virtual void _noteTeeFrame(void);
virtual void _noteVideoSinkFrame(void);
virtual void _noteEndOfStream(void);
virtual void _unlinkBranch(GstElement* from);
virtual bool _unlinkBranch(GstElement* from);
virtual void _shutdownDecodingBranch (void);
virtual void _shutdownRecordingBranch(void);
private:
bool _needDispatch(void);
void _dispatchSignal(std::function<void()> emitter);
static gboolean _onBusMessage(GstBus* bus, GstMessage* message, gpointer user_data);
static void _onNewPad(GstElement* element, GstPad* pad, gpointer data);
static void _wrapWithGhostPad(GstElement* element, GstPad* pad, gpointer data);
static void _linkPadWithOptionalBuffer(GstElement* element, GstPad* pad, gpointer data);
static void _linkPad(GstElement* element, GstPad* pad, gpointer data);
static gboolean _padProbe(GstElement* element, GstPad* pad, gpointer user_data);
static gboolean _filterParserCaps(GstElement* bin, GstPad* pad, GstElement* element, GstQuery* query, gpointer data);
static gboolean _autoplugQueryCaps(GstElement* bin, GstPad* pad, GstElement* element, GstQuery* query, gpointer data);
static gboolean _autoplugQueryContext(GstElement* bin, GstPad* pad, GstElement* element, GstQuery* query, gpointer data);
static gboolean _autoplugQuery(GstElement* bin, GstPad* pad, GstElement* element, GstQuery* query, gpointer data);
......@@ -136,6 +134,9 @@ private:
static GstPadProbeReturn _eosProbe(GstPad* pad, GstPadProbeInfo* info, gpointer user_data);
static GstPadProbeReturn _keyframeWatch(GstPad* pad, GstPadProbeInfo* info, gpointer user_data);
bool _streaming;
bool _decoding;
bool _recording;
bool _removingDecoder;
bool _removingRecorder;
GstElement* _source;
......@@ -157,10 +158,12 @@ private:
//-- RTSP UDP reconnect timeout
uint64_t _udpReconnect_us;
QString _uri;
unsigned _timeout;
int _buffer;
Worker _apiHandler;
Worker _notificationHandler;
Worker _slotHandler;
uint32_t _signalDepth;
bool _endOfStream;
......
......@@ -39,7 +39,7 @@ gst-launch-1.0 videotestsrc ! video/x-raw,width=640,height=480 ! videoconvert !
On the receiving end, if you want to test it from the command line, you can use something like:
```
gst-launch-1.0 udpsrc port=5600 caps='application/x-rtp, media=(string)video, clock-rate=(int)90000, encoding-name=(string)H264' ! rtph264depay ! h264parse ! avdec_h264 ! autovideosink fps-update-interval=1000 sync=false
gst-launch-1.0 udpsrc port=5600 caps='application/x-rtp, media=(string)video, clock-rate=(int)90000, encoding-name=(string)H264' ! rtpjitterbuffer ! rtph264depay ! h264parse ! avdec_h264 ! autovideosink fps-update-interval=1000 sync=false
```
### Additional Protocols
......
......@@ -17,9 +17,6 @@
#include <QObject>
#include <QSize>
#include <QQuickItem>
#include <atomic>
class VideoReceiver : public QObject
{
......@@ -28,10 +25,6 @@ class VideoReceiver : public QObject
public:
explicit VideoReceiver(QObject* parent = nullptr)
: QObject(parent)
, _streaming(false)
, _decoding(false)
, _recording(false)
, _videoSize(0)
{}
virtual ~VideoReceiver(void) {}
......@@ -44,50 +37,42 @@ public:
FILE_FORMAT_MAX
} FILE_FORMAT;
Q_PROPERTY(bool streaming READ streaming NOTIFY streamingChanged)
Q_PROPERTY(bool decoding READ decoding NOTIFY decodingChanged)
Q_PROPERTY(bool recording READ recording NOTIFY recordingChanged)
Q_PROPERTY(QSize videoSize READ videoSize NOTIFY videoSizeChanged)
bool streaming(void) {
return _streaming;
}
bool decoding(void) {
return _decoding;
}
bool recording(void) {
return _recording;
}
typedef enum {
STATUS_OK = 0,
STATUS_FAIL,
STATUS_INVALID_STATE,
STATUS_INVALID_URL,
STATUS_NOT_IMPLEMENTED
} STATUS;
QSize videoSize(void) {
const quint32 size = _videoSize;
return QSize((size >> 16) & 0xFFFF, size & 0xFFFF);
}
Q_ENUM(STATUS)
signals:
void timeout(void);
void streamingChanged(void);
void decodingChanged(void);
void recordingChanged(void);
void streamingChanged(bool active);
void decodingChanged(bool active);
void recordingChanged(bool active);
void recordingStarted(void);
void videoSizeChanged(void);
void screenshotComplete(void);
void videoSizeChanged(QSize size);
void onStartComplete(STATUS status);
void onStopComplete(STATUS status);
void onStartDecodingComplete(STATUS status);
void onStopDecodingComplete(STATUS status);
void onStartRecordingComplete(STATUS status);
void onStopRecordingComplete(STATUS status);
void onTakeScreenshotComplete(STATUS status);
public slots:
virtual void start(const QString& uri, unsigned timeout) = 0;
// buffer:
// -1 - disable buffer and video sync
// 0 - default buffer length
// N - buffer length, ms
virtual void start(const QString& uri, unsigned timeout, int buffer = 0) = 0;
virtual void stop(void) = 0;
virtual void startDecoding(void* sink) = 0;
virtual void stopDecoding(void) = 0;
virtual void startRecording(const QString& videoFile, FILE_FORMAT format) = 0;
virtual void stopRecording(void) = 0;
virtual void takeScreenshot(const QString& imageFile) = 0;
protected:
std::atomic<bool> _streaming;
std::atomic<bool> _decoding;
std::atomic<bool> _recording;
std::atomic<quint32>_videoSize;
};
......@@ -485,6 +485,15 @@ void* QGCCorePlugin::createVideoSink(QObject* parent, QQuickItem* widget)
#endif
}
void QGCCorePlugin::releaseVideoSink(void* sink)
{
#if defined(QGC_GST_STREAMING)
GStreamer::releaseVideoSink(sink);
#else
Q_UNUSED(sink)
#endif
}
bool QGCCorePlugin::guidedActionsControllerLogging() const
{
return GuidedActionsControllerLog().isDebugEnabled();
......
......@@ -119,6 +119,8 @@ public:
virtual VideoReceiver* createVideoReceiver(QObject* parent);
/// Allows the plugin to override the creation of VideoSink.
virtual void* createVideoSink(QObject* parent, QQuickItem* widget);
/// Allows the plugin to override the release of VideoSink.
virtual void releaseVideoSink(void* sink);
/// Allows the plugin to see all mavlink traffic to a vehicle
/// @return true: Allow vehicle to continue processing, false: Vehicle should not process message
......
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