Commit 6895a5f6 authored by Don Gagne's avatar Don Gagne Committed by GitHub

Merge pull request #4438 from bluerobotics/video-recording

Video recording
parents ef3d5401 c333553d
...@@ -156,6 +156,7 @@ ...@@ -156,6 +156,7 @@
<file alias="Signal100.svg">src/ui/toolbar/Images/Signal100.svg</file> <file alias="Signal100.svg">src/ui/toolbar/Images/Signal100.svg</file>
<file alias="TelemRSSI.svg">src/ui/toolbar/Images/TelemRSSI.svg</file> <file alias="TelemRSSI.svg">src/ui/toolbar/Images/TelemRSSI.svg</file>
<file alias="Yield.svg">src/ui/toolbar/Images/Yield.svg</file> <file alias="Yield.svg">src/ui/toolbar/Images/Yield.svg</file>
<file alias="CameraIcon.svg">src/ui/toolbar/Images/CameraIcon.svg</file>
<file alias="CogWheel.svg">src/MissionManager/CogWheel.svg</file> <file alias="CogWheel.svg">src/MissionManager/CogWheel.svg</file>
<file alias="StationMode.svg">src/AutoPilotPlugins/Common/Images/StationMode.svg</file> <file alias="StationMode.svg">src/AutoPilotPlugins/Common/Images/StationMode.svg</file>
<file alias="APMode.svg">src/AutoPilotPlugins/Common/Images/APMode.svg</file> <file alias="APMode.svg">src/AutoPilotPlugins/Common/Images/APMode.svg</file>
......
...@@ -260,6 +260,42 @@ QGCView { ...@@ -260,6 +260,42 @@ QGCView {
visible: singleVehicleView.checked visible: singleVehicleView.checked
} }
// Button to start/stop video recording
Item {
z: _flightVideoPipControl.z + 1
anchors.margins: ScreenTools.defaultFontPixelHeight / 2
anchors.bottom: _flightVideo.bottom
anchors.right: _flightVideo.right
height: ScreenTools.defaultFontPixelHeight * 2
width: height
visible: QGroundControl.videoManager.videoRunning
opacity: 0.75
Rectangle {
anchors.top: parent.top
anchors.bottom: parent.bottom
width: height
radius: QGroundControl.videoManager.videoReceiver && QGroundControl.videoManager.videoReceiver.recording ? 0 : height
color: "red"
}
QGCColoredImage {
anchors.top: parent.top
anchors.bottom: parent.bottom
anchors.horizontalCenter: parent.horizontalCenter
width: height * 0.625
sourceSize.width: width
source: "/qmlimages/CameraIcon.svg"
fillMode: Image.PreserveAspectFit
color: "white"
}
MouseArea {
anchors.fill: parent
onClicked: QGroundControl.videoManager.videoReceiver && QGroundControl.videoManager.videoReceiver.recording ? QGroundControl.videoManager.videoReceiver.stopRecording() : QGroundControl.videoManager.videoReceiver.startRecording()
}
}
MultiVehicleList { MultiVehicleList {
anchors.margins: _margins anchors.margins: _margins
anchors.top: singleMultiSelector.bottom anchors.top: singleMultiSelector.bottom
......
...@@ -11,6 +11,8 @@ ...@@ -11,6 +11,8 @@
#include <QQmlContext> #include <QQmlContext>
#include <QQmlEngine> #include <QQmlEngine>
#include <QSettings> #include <QSettings>
#include <QUrl>
#include <QDir>
#ifndef QGC_DISABLE_UVC #ifndef QGC_DISABLE_UVC
#include <QCameraInfo> #include <QCameraInfo>
...@@ -27,6 +29,7 @@ ...@@ -27,6 +29,7 @@
static const char* kVideoSourceKey = "VideoSource"; static const char* kVideoSourceKey = "VideoSource";
static const char* kVideoUDPPortKey = "VideoUDPPort"; static const char* kVideoUDPPortKey = "VideoUDPPort";
static const char* kVideoRTSPUrlKey = "VideoRTSPUrl"; static const char* kVideoRTSPUrlKey = "VideoRTSPUrl";
static const char* kVideoSavePathKey = "VideoSavePath";
#if defined(QGC_GST_STREAMING) #if defined(QGC_GST_STREAMING)
static const char* kUDPStream = "UDP Video Stream"; static const char* kUDPStream = "UDP Video Stream";
static const char* kRTSPStream = "RTSP Video Stream"; static const char* kRTSPStream = "RTSP Video Stream";
...@@ -80,6 +83,7 @@ VideoManager::setToolbox(QGCToolbox *toolbox) ...@@ -80,6 +83,7 @@ VideoManager::setToolbox(QGCToolbox *toolbox)
setUdpPort(settings.value(kVideoUDPPortKey, 5600).toUInt()); setUdpPort(settings.value(kVideoUDPPortKey, 5600).toUInt());
setRtspURL(settings.value(kVideoRTSPUrlKey, "rtsp://192.168.42.1:554/live").toString()); //-- Example RTSP URL setRtspURL(settings.value(kVideoRTSPUrlKey, "rtsp://192.168.42.1:554/live").toString()); //-- Example RTSP URL
} }
setVideoSavePath(settings.value(kVideoSavePathKey, QDir::homePath()).toString());
#endif #endif
_init = true; _init = true;
#if defined(QGC_GST_STREAMING) #if defined(QGC_GST_STREAMING)
...@@ -186,6 +190,22 @@ VideoManager::setRtspURL(QString url) ...@@ -186,6 +190,22 @@ VideoManager::setRtspURL(QString url)
*/ */
} }
void
VideoManager::setVideoSavePathByUrl(QUrl url) {
setVideoSavePath(url.toLocalFile());
}
void
VideoManager::setVideoSavePath(QString path)
{
_videoSavePath = path;
QSettings settings;
settings.setValue(kVideoSavePathKey, path);
if(_videoReceiver)
_videoReceiver->setVideoSavePath(_videoSavePath);
emit videoSavePathChanged();
}
//----------------------------------------------------------------------------- //-----------------------------------------------------------------------------
QStringList QStringList
VideoManager::videoSourceList() VideoManager::videoSourceList()
...@@ -211,37 +231,37 @@ VideoManager::videoSourceList() ...@@ -211,37 +231,37 @@ VideoManager::videoSourceList()
void VideoManager::_updateTimer() void VideoManager::_updateTimer()
{ {
#if defined(QGC_GST_STREAMING) #if defined(QGC_GST_STREAMING)
if(_videoRunning) if(_videoReceiver && _videoSurface) {
{ if(_videoReceiver->stopping() || _videoReceiver->starting()) {
time_t elapsed = 0; return;
if(_videoSurface)
{
elapsed = time(0) - _videoSurface->lastFrame();
}
if(elapsed > 2 && _videoSurface)
{
_videoRunning = false;
_videoSurface->setLastFrame(0);
emit videoRunningChanged();
if(_videoReceiver) {
if(isGStreamer()) {
//-- Stop it
_videoReceiver->stop();
QThread::msleep(100);
//-- And start over
_videoReceiver->start();
}
}
} }
}
else if(_videoReceiver->streaming()) {
{ if(!_videoRunning) {
if(_videoSurface && _videoSurface->lastFrame()) { _videoSurface->setLastFrame(0);
if(!_videoRunning)
{
_videoRunning = true; _videoRunning = true;
emit videoRunningChanged(); emit videoRunningChanged();
} }
} else {
if(_videoRunning) {
_videoRunning = false;
emit videoRunningChanged();
}
}
if(_videoRunning) {
time_t elapsed = 0;
time_t lastFrame = _videoSurface->lastFrame();
if(lastFrame != 0) {
elapsed = time(0) - _videoSurface->lastFrame();
}
if(elapsed > 2 && _videoSurface) {
_videoReceiver->stop();
}
} else {
if(!_videoReceiver->running()) {
_videoReceiver->start();
}
} }
} }
#endif #endif
...@@ -263,6 +283,7 @@ void VideoManager::_updateVideo() ...@@ -263,6 +283,7 @@ void VideoManager::_updateVideo()
_videoReceiver->setUri(QStringLiteral("udp://0.0.0.0:%1").arg(_udpPort)); _videoReceiver->setUri(QStringLiteral("udp://0.0.0.0:%1").arg(_udpPort));
else else
_videoReceiver->setUri(_rtspURL); _videoReceiver->setUri(_rtspURL);
_videoReceiver->setVideoSavePath(_videoSavePath);
#endif #endif
_videoReceiver->start(); _videoReceiver->start();
} }
......
...@@ -13,6 +13,7 @@ ...@@ -13,6 +13,7 @@
#include <QObject> #include <QObject>
#include <QTimer> #include <QTimer>
#include <QUrl>
#include "QGCLoggingCategory.h" #include "QGCLoggingCategory.h"
#include "VideoSurface.h" #include "VideoSurface.h"
...@@ -29,17 +30,20 @@ public: ...@@ -29,17 +30,20 @@ public:
VideoManager (QGCApplication* app); VideoManager (QGCApplication* app);
~VideoManager (); ~VideoManager ();
Q_PROPERTY(bool hasVideo READ hasVideo NOTIFY hasVideoChanged) Q_PROPERTY(bool hasVideo READ hasVideo NOTIFY hasVideoChanged)
Q_PROPERTY(bool isGStreamer READ isGStreamer NOTIFY isGStreamerChanged) Q_PROPERTY(bool isGStreamer READ isGStreamer NOTIFY isGStreamerChanged)
Q_PROPERTY(QString videoSourceID READ videoSourceID NOTIFY videoSourceIDChanged) Q_PROPERTY(QString videoSourceID READ videoSourceID NOTIFY videoSourceIDChanged)
Q_PROPERTY(QString videoSource READ videoSource WRITE setVideoSource NOTIFY videoSourceChanged) Q_PROPERTY(QString videoSource READ videoSource WRITE setVideoSource NOTIFY videoSourceChanged)
Q_PROPERTY(QStringList videoSourceList READ videoSourceList NOTIFY videoSourceListChanged) Q_PROPERTY(QStringList videoSourceList READ videoSourceList NOTIFY videoSourceListChanged)
Q_PROPERTY(bool videoRunning READ videoRunning NOTIFY videoRunningChanged) Q_PROPERTY(bool videoRunning READ videoRunning NOTIFY videoRunningChanged)
Q_PROPERTY(quint16 udpPort READ udpPort WRITE setUdpPort NOTIFY udpPortChanged) Q_PROPERTY(quint16 udpPort READ udpPort WRITE setUdpPort NOTIFY udpPortChanged)
Q_PROPERTY(QString rtspURL READ rtspURL WRITE setRtspURL NOTIFY rtspURLChanged) Q_PROPERTY(QString rtspURL READ rtspURL WRITE setRtspURL NOTIFY rtspURLChanged)
Q_PROPERTY(bool uvcEnabled READ uvcEnabled CONSTANT) Q_PROPERTY(QString videoSavePath READ videoSavePath NOTIFY videoSavePathChanged)
Q_PROPERTY(VideoSurface* videoSurface MEMBER _videoSurface CONSTANT) Q_PROPERTY(bool uvcEnabled READ uvcEnabled CONSTANT)
Q_PROPERTY(VideoReceiver* videoReceiver MEMBER _videoReceiver CONSTANT) Q_PROPERTY(VideoSurface* videoSurface MEMBER _videoSurface CONSTANT)
Q_PROPERTY(VideoReceiver* videoReceiver MEMBER _videoReceiver CONSTANT)
Q_INVOKABLE void setVideoSavePathByUrl (QUrl url);
bool hasVideo (); bool hasVideo ();
bool isGStreamer (); bool isGStreamer ();
...@@ -49,6 +53,7 @@ public: ...@@ -49,6 +53,7 @@ public:
QStringList videoSourceList (); QStringList videoSourceList ();
quint16 udpPort () { return _udpPort; } quint16 udpPort () { return _udpPort; }
QString rtspURL () { return _rtspURL; } QString rtspURL () { return _rtspURL; }
QString videoSavePath () { return _videoSavePath; }
#if defined(QGC_DISABLE_UVC) #if defined(QGC_DISABLE_UVC)
bool uvcEnabled () { return false; } bool uvcEnabled () { return false; }
...@@ -56,9 +61,10 @@ public: ...@@ -56,9 +61,10 @@ public:
bool uvcEnabled (); bool uvcEnabled ();
#endif #endif
void setVideoSource (QString vSource); void setVideoSource (QString vSource);
void setUdpPort (quint16 port); void setUdpPort (quint16 port);
void setRtspURL (QString url); void setRtspURL (QString url);
void setVideoSavePath (QString path);
// Override from QGCTool // Override from QGCTool
void setToolbox (QGCToolbox *toolbox); void setToolbox (QGCToolbox *toolbox);
...@@ -72,6 +78,7 @@ signals: ...@@ -72,6 +78,7 @@ signals:
void videoSourceIDChanged (); void videoSourceIDChanged ();
void udpPortChanged (); void udpPortChanged ();
void rtspURLChanged (); void rtspURLChanged ();
void videoSavePathChanged ();
private: private:
void _updateTimer (); void _updateTimer ();
...@@ -89,6 +96,7 @@ private: ...@@ -89,6 +96,7 @@ private:
QStringList _videoSourceList; QStringList _videoSourceList;
quint16 _udpPort; quint16 _udpPort;
QString _rtspURL; QString _rtspURL;
QString _videoSavePath;
bool _init; bool _init;
}; };
......
...@@ -79,7 +79,7 @@ private: ...@@ -79,7 +79,7 @@ private:
MAVLinkProtocol* _mavlinkProtocol; MAVLinkProtocol* _mavlinkProtocol;
MissionCommandTree* _missionCommandTree; MissionCommandTree* _missionCommandTree;
MultiVehicleManager* _multiVehicleManager; MultiVehicleManager* _multiVehicleManager;
QGCMapEngineManager* _mapEngineManager; QGCMapEngineManager* _mapEngineManager;
UASMessageHandler* _uasMessageHandler; UASMessageHandler* _uasMessageHandler;
FollowMe* _followMe; FollowMe* _followMe;
QGCPositionManager* _qgcPositionManager; QGCPositionManager* _qgcPositionManager;
......
This diff is collapsed.
...@@ -17,6 +17,7 @@ ...@@ -17,6 +17,7 @@
#ifndef VIDEORECEIVER_H #ifndef VIDEORECEIVER_H
#define VIDEORECEIVER_H #define VIDEORECEIVER_H
#include "QGCLoggingCategory.h"
#include <QObject> #include <QObject>
#include <QTimer> #include <QTimer>
#include <QTcpSocket> #include <QTcpSocket>
...@@ -25,41 +26,91 @@ ...@@ -25,41 +26,91 @@
#include <gst/gst.h> #include <gst/gst.h>
#endif #endif
Q_DECLARE_LOGGING_CATEGORY(VideoReceiverLog)
class VideoReceiver : public QObject class VideoReceiver : public QObject
{ {
Q_OBJECT Q_OBJECT
public: public:
#if defined(QGC_GST_STREAMING)
Q_PROPERTY(bool recording READ recording NOTIFY recordingChanged)
#endif
explicit VideoReceiver(QObject* parent = 0); explicit VideoReceiver(QObject* parent = 0);
~VideoReceiver(); ~VideoReceiver();
#if defined(QGC_GST_STREAMING) #if defined(QGC_GST_STREAMING)
void setVideoSink(GstElement* sink); void setVideoSink(GstElement* sink);
bool running() { return _running; }
bool recording() { return _recording; }
bool streaming() { return _streaming; }
bool starting() { return _starting; }
bool stopping() { return _stopping; }
#endif
signals:
#if defined(QGC_GST_STREAMING)
void recordingChanged();
void msgErrorReceived();
void msgEOSReceived();
void msgStateChangedReceived();
#endif #endif
public slots: public slots:
void start (); void start ();
void stop (); void stop ();
void setUri (const QString& uri); void setUri (const QString& uri);
void setVideoSavePath (const QString& path);
void stopRecording ();
void startRecording ();
private slots: private slots:
#if defined(QGC_GST_STREAMING) #if defined(QGC_GST_STREAMING)
void _timeout (); void _timeout ();
void _connected (); void _connected ();
void _socketError (QAbstractSocket::SocketError socketError); void _socketError (QAbstractSocket::SocketError socketError);
void _handleError();
void _handleEOS();
void _handleStateChanged();
#endif #endif
private: private:
#if defined(QGC_GST_STREAMING) #if defined(QGC_GST_STREAMING)
void _onBusMessage(GstMessage* message); typedef struct
static gboolean _onBusMessage(GstBus* bus, GstMessage* msg, gpointer data); {
GstPad* teepad;
GstElement* queue;
GstElement* mux;
GstElement* filesink;
gboolean removing;
} Sink;
bool _running;
bool _recording;
bool _streaming;
bool _starting;
bool _stopping;
Sink* _sink;
GstElement* _tee;
static gboolean _onBusMessage(GstBus* bus, GstMessage* message, gpointer user_data);
static GstPadProbeReturn _unlinkCallBack(GstPad* pad, GstPadProbeInfo* info, gpointer user_data);
void _detachRecordingBranch(GstPadProbeInfo* info);
void _shutdownRecordingBranch();
void _shutdownPipeline();
#endif #endif
QString _uri; QString _uri;
QString _path;
#if defined(QGC_GST_STREAMING) #if defined(QGC_GST_STREAMING)
GstElement* _pipeline; GstElement* _pipeline;
GstElement* _videoSink; GstElement* _pipelineStopRec;
GstElement* _videoSink;
#endif #endif
//-- Wait for Video Server to show up before starting //-- Wait for Video Server to show up before starting
......
...@@ -39,6 +39,14 @@ QGCView { ...@@ -39,6 +39,14 @@ QGCView {
QGCPalette { id: qgcPal } QGCPalette { id: qgcPal }
FileDialog {
id: fileDialog
title: "Choose a location to save video files."
folder: shortcuts.home
selectFolder: true
onAccepted: QGroundControl.videoManager.setVideoSavePathByUrl(fileDialog.fileUrl)
}
QGCViewPanel { QGCViewPanel {
id: panel id: panel
anchors.fill: parent anchors.fill: parent
...@@ -525,6 +533,25 @@ QGCView { ...@@ -525,6 +533,25 @@ QGCView {
} }
} }
} }
Row {
spacing: ScreenTools.defaultFontPixelWidth
visible: QGroundControl.videoManager.isGStreamer
QGCLabel {
anchors.baseline: pathField.baseline
text: qsTr("Save Path:")
width: _labelWidth
}
QGCTextField {
id: pathField
width: _editFieldWidth
readOnly: true
text: QGroundControl.videoManager.videoSavePath
}
Button {
text: "Browse"
onClicked: fileDialog.visible = true
}
}
} }
} }
......
<?xml version="1.0" encoding="UTF-8" standalone="no"?>
<!-- Created with Inkscape (http://www.inkscape.org/) -->
<svg
xmlns:dc="http://purl.org/dc/elements/1.1/"
xmlns:cc="http://creativecommons.org/ns#"
xmlns:rdf="http://www.w3.org/1999/02/22-rdf-syntax-ns#"
xmlns:svg="http://www.w3.org/2000/svg"
xmlns="http://www.w3.org/2000/svg"
version="1.1"
width="250"
height="160"
id="svg4009">
<defs
id="defs4011" />
<metadata
id="metadata4014">
<rdf:RDF>
<cc:Work
rdf:about="">
<dc:format>image/svg+xml</dc:format>
<dc:type
rdf:resource="http://purl.org/dc/dcmitype/StillImage" />
<dc:title></dc:title>
</cc:Work>
</rdf:RDF>
</metadata>
<g
transform="translate(0,-892.36218)"
id="layer1">
<rect
width="190"
height="160"
ry="36.792519"
x="0"
y="892.36218"
id="rect4017"
style="fill:#000000;fill-opacity:0.49803922;fill-rule:nonzero" />
<path
d="m 190,998.43327 0,-52.1422 60,-46.92889 0,146.00002 z"
id="path4028"
style="fill:#000000;fill-opacity:0.49803922;stroke:#000000;stroke-width:0;stroke-linecap:butt;stroke-linejoin:miter;stroke-miterlimit:4;stroke-opacity:0.49803922;stroke-dasharray:none" />
</g>
</svg>
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