Commit 20bc3fa9 authored by Gus Grubba's avatar Gus Grubba

Adding mp4 and mov files types in addition to mkv

Adding mux GStreamer plugin libraries to Android (to enable video recording on Android)
Adding an option to limit the amount to disk used for saving videos
Adding an option to show/hide the REC button (allowing plugins to handle the recording in their own way)
Adding simple frame grab to file
parent b3fe4b6b
......@@ -359,7 +359,7 @@ QGCView {
anchors.right: _flightVideo.right
height: ScreenTools.defaultFontPixelHeight * 2
width: height
visible: QGroundControl.videoManager.videoRunning && QGroundControl.videoManager.recordingEnabled
visible: QGroundControl.videoManager.videoRunning && QGroundControl.settingsManager.videoSettings.showRecControl.rawValue
opacity: 0.75
Rectangle {
......
......@@ -23,9 +23,8 @@ import QGroundControl.Controllers 1.0
Item {
id: root
property double _ar: QGroundControl.settingsManager.videoSettings.aspectRatio.rawValue
property bool _showGrid: QGroundControl.settingsManager.videoSettings.gridLines.rawValue > 0
property double _ar: QGroundControl.settingsManager.videoSettings.aspectRatio.rawValue
property bool _showGrid: QGroundControl.settingsManager.videoSettings.gridLines.rawValue > 0
Rectangle {
id: noVideo
anchors.fill: parent
......@@ -44,12 +43,23 @@ Item {
color: "black"
visible: QGroundControl.videoManager.videoRunning
QGCVideoBackground {
id: videoContent
height: parent.height
width: _ar != 0.0 ? height * _ar : parent.width
anchors.centerIn: parent
display: QGroundControl.videoManager.videoSurface
receiver: QGroundControl.videoManager.videoReceiver
visible: QGroundControl.videoManager.videoRunning
Connections {
target: QGroundControl.videoManager
onImageFileChanged: {
videoContent.grabToImage(function(result) {
if (!result.saveToFile(QGroundControl.videoManager.imageFile)) {
console.error('Error capturing video frame');
}
});
}
}
Rectangle {
color: Qt.rgba(1,1,1,0.5)
height: parent.height
......
......@@ -37,6 +37,7 @@ VideoManager::VideoManager(QGCApplication* app, QGCToolbox* toolbox)
, _videoRunning(false)
, _init(false)
, _videoSettings(NULL)
, _showFullScreen(false)
{
}
......@@ -112,6 +113,14 @@ void VideoManager::_rtspUrlChanged(void)
_restartVideo();
}
//-----------------------------------------------------------------------------
void
VideoManager::grabImage(QString imageFile)
{
_imageFile = imageFile;
emit imageFileChanged();
}
//-----------------------------------------------------------------------------
bool
VideoManager::hasVideo()
......
......@@ -39,12 +39,15 @@ public:
Q_PROPERTY(bool uvcEnabled READ uvcEnabled CONSTANT)
Q_PROPERTY(VideoSurface* videoSurface MEMBER _videoSurface CONSTANT)
Q_PROPERTY(VideoReceiver* videoReceiver MEMBER _videoReceiver CONSTANT)
Q_PROPERTY(bool recordingEnabled READ recordingEnabled CONSTANT)
Q_PROPERTY(QString imageFile READ imageFile NOTIFY imageFileChanged)
Q_PROPERTY(bool showFullScreen READ showFullScreen WRITE setShowFullScreen NOTIFY showFullScreenChanged)
bool hasVideo ();
bool isGStreamer ();
bool videoRunning () { return _videoRunning; }
QString videoSourceID () { return _videoSourceID; }
QString imageFile () { return _imageFile; }
bool showFullScreen () { return _showFullScreen; }
#if defined(QGC_DISABLE_UVC)
bool uvcEnabled () { return false; }
......@@ -52,11 +55,8 @@ public:
bool uvcEnabled ();
#endif
#if defined(QGC_GST_STREAMING) && defined(QGC_ENABLE_VIDEORECORDING)
bool recordingEnabled () { return true; }
#else
bool recordingEnabled () { return false; }
#endif
void grabImage (QString imageFile);
void setShowFullScreen (bool show) { _showFullScreen = show; emit showFullScreenChanged(); }
// Override from QGCTool
void setToolbox (QGCToolbox *toolbox);
......@@ -66,13 +66,14 @@ signals:
void videoRunningChanged ();
void isGStreamerChanged ();
void videoSourceIDChanged ();
void imageFileChanged ();
void showFullScreenChanged ();
private slots:
void _videoSourceChanged(void);
void _udpPortChanged(void);
void _rtspUrlChanged(void);
private:
void _updateTimer ();
void _updateSettings ();
......@@ -89,6 +90,8 @@ private:
QString _videoSourceID;
bool _init;
VideoSettings* _videoSettings;
QString _imageFile;
bool _showFullScreen;
};
#endif
......@@ -44,5 +44,30 @@
"enumStrings": "Hide,Show",
"enumValues": "1,0",
"defaultValue": 0
},
{
"name": "ShowRecControl",
"shortDescription": "Show Video Record Control",
"longDescription": "Show recording control in the UI.",
"type": "bool",
"defaultValue": true
},
{
"name": "RecordingFormat",
"shortDescription": "Video Recording Format",
"longDescription": "Video recording file format.",
"type": "uint32",
"enumStrings": "mkv,mov,mp4",
"enumValues": "0,1,2",
"defaultValue": 0
},
{
"name": "MaxVideoSize",
"shortDescription": "Max Video Storage Usage",
"longDescription": "Maximum amount of disk space used by video recording.",
"type": "uint32",
"min": 100,
"units": "MB",
"defaultValue": 2024
}
]
......@@ -25,10 +25,13 @@ const char* VideoSettings::rtspUrlName = "VideoRTSPUrl";
const char* VideoSettings::videoSavePathName = "VideoSavePath";
const char* VideoSettings::videoAspectRatioName = "VideoAspectRatio";
const char* VideoSettings::videoGridLinesName = "VideoGridLines";
const char* VideoSettings::showRecControlName = "ShowRecControl";
const char* VideoSettings::recordingFormatName = "RecordingFormat";
const char* VideoSettings::maxVideoSizeName = "MaxVideoSize";
const char* VideoSettings::videoSourceNoVideo = "No Video Available";
const char* VideoSettings::videoSourceUDP = "UDP Video Stream";
const char* VideoSettings::videoSourceRTSP = "RTSP Video Stream";
const char* VideoSettings::videoSourceNoVideo = "No Video Available";
const char* VideoSettings::videoSourceUDP = "UDP Video Stream";
const char* VideoSettings::videoSourceRTSP = "RTSP Video Stream";
VideoSettings::VideoSettings(QObject* parent)
: SettingsGroup(videoSettingsGroupName, QString() /* root settings group */, parent)
......@@ -38,6 +41,9 @@ VideoSettings::VideoSettings(QObject* parent)
, _videoSavePathFact(NULL)
, _videoAspectRatioFact(NULL)
, _gridLinesFact(NULL)
, _showRecControlFact(NULL)
, _recordingFormatFact(NULL)
, _maxVideoSizeFact(NULL)
{
QQmlEngine::setObjectOwnership(this, QQmlEngine::CppOwnership);
qmlRegisterUncreatableType<VideoSettings>("QGroundControl.SettingsManager", 1, 0, "VideoSettings", "Reference only");
......@@ -126,3 +132,30 @@ Fact* VideoSettings::gridLines(void)
return _gridLinesFact;
}
Fact* VideoSettings::showRecControl(void)
{
if (!_showRecControlFact) {
_showRecControlFact = _createSettingsFact(showRecControlName);
}
return _showRecControlFact;
}
Fact* VideoSettings::recordingFormat(void)
{
if (!_recordingFormatFact) {
_recordingFormatFact = _createSettingsFact(recordingFormatName);
}
return _recordingFormatFact;
}
Fact* VideoSettings::maxVideoSize(void)
{
if (!_maxVideoSizeFact) {
_maxVideoSizeFact = _createSettingsFact(maxVideoSizeName);
}
return _maxVideoSizeFact;
}
......@@ -19,19 +19,25 @@ class VideoSettings : public SettingsGroup
public:
VideoSettings(QObject* parent = NULL);
Q_PROPERTY(Fact* videoSource READ videoSource CONSTANT)
Q_PROPERTY(Fact* udpPort READ udpPort CONSTANT)
Q_PROPERTY(Fact* rtspUrl READ rtspUrl CONSTANT)
Q_PROPERTY(Fact* videoSavePath READ videoSavePath CONSTANT)
Q_PROPERTY(Fact* aspectRatio READ aspectRatio CONSTANT)
Q_PROPERTY(Fact* gridLines READ gridLines CONSTANT)
Fact* videoSource (void);
Fact* udpPort (void);
Fact* rtspUrl (void);
Fact* videoSavePath (void);
Fact* aspectRatio (void);
Fact* gridLines (void);
Q_PROPERTY(Fact* videoSource READ videoSource CONSTANT)
Q_PROPERTY(Fact* udpPort READ udpPort CONSTANT)
Q_PROPERTY(Fact* rtspUrl READ rtspUrl CONSTANT)
Q_PROPERTY(Fact* videoSavePath READ videoSavePath CONSTANT)
Q_PROPERTY(Fact* aspectRatio READ aspectRatio CONSTANT)
Q_PROPERTY(Fact* gridLines READ gridLines CONSTANT)
Q_PROPERTY(Fact* showRecControl READ showRecControl CONSTANT)
Q_PROPERTY(Fact* recordingFormat READ recordingFormat CONSTANT)
Q_PROPERTY(Fact* maxVideoSize READ maxVideoSize CONSTANT)
Fact* videoSource (void);
Fact* udpPort (void);
Fact* rtspUrl (void);
Fact* videoSavePath (void);
Fact* aspectRatio (void);
Fact* gridLines (void);
Fact* showRecControl (void);
Fact* recordingFormat (void);
Fact* maxVideoSize (void);
static const char* videoSettingsGroupName;
......@@ -41,6 +47,9 @@ public:
static const char* videoSavePathName;
static const char* videoAspectRatioName;
static const char* videoGridLinesName;
static const char* showRecControlName;
static const char* recordingFormatName;
static const char* maxVideoSizeName;
static const char* videoSourceNoVideo;
static const char* videoSourceUDP;
......@@ -53,6 +62,9 @@ private:
SettingsFact* _videoSavePathFact;
SettingsFact* _videoAspectRatioFact;
SettingsFact* _gridLinesFact;
SettingsFact* _showRecControlFact;
SettingsFact* _recordingFormatFact;
SettingsFact* _maxVideoSizeFact;
};
#endif
......@@ -17,6 +17,7 @@
#include "VideoReceiver.h"
#include "SettingsManager.h"
#include "QGCApplication.h"
#include "VideoManager.h"
#include <QDebug>
#include <QUrl>
......@@ -26,6 +27,22 @@
QGC_LOGGING_CATEGORY(VideoReceiverLog, "VideoReceiverLog")
static const char* kVideoExtensions[] =
{
"mkv",
"mov",
"mp4"
};
static const char* kVideoMuxes[] =
{
"matroskamux",
"qtmux",
"mp4mux"
};
#define NUM_MUXES (sizeof(kVideoMuxes) / sizeof(char*))
VideoReceiver::VideoReceiver(QObject* parent)
: QObject(parent)
#if defined(QGC_GST_STREAMING)
......@@ -444,6 +461,39 @@ gboolean VideoReceiver::_onBusMessage(GstBus* bus, GstMessage* msg, gpointer dat
}
#endif
void VideoReceiver::_cleanupOldVideos()
{
QString savePath = qgcApp()->toolbox()->settingsManager()->videoSettings()->videoSavePath()->rawValue().toString();
QDir videoDir = QDir(savePath);
videoDir.setFilter(QDir::Files | QDir::Readable | QDir::NoSymLinks | QDir::Writable);
videoDir.setSorting(QDir::Time);
//-- All the movie extensions we support
QStringList nameFilters;
for(uint32_t i = 0; i < NUM_MUXES; i++) {
nameFilters << QString("*.") + QString(kVideoExtensions[i]);
}
videoDir.setNameFilters(nameFilters);
//-- get the list of videos stored
QFileInfoList vidList = videoDir.entryInfoList();
if(!vidList.isEmpty()) {
uint64_t total = 0;
//-- Settings are stored using MB
uint64_t maxSize = (qgcApp()->toolbox()->settingsManager()->videoSettings()->maxVideoSize()->rawValue().toUInt() * 1024 * 1024);
//-- Compute total used storage
for(int i = 0; i < vidList.size(); i++) {
total += vidList[i].size();
}
//-- Remove old movies until max size is satisfied.
while(total >= maxSize && !vidList.isEmpty()) {
total -= vidList.last().size();
qCDebug(VideoReceiverLog) << "Removing old video file:" << vidList.last().filePath();
QFile file (vidList.last().filePath());
file.remove();
vidList.removeLast();
}
}
}
// When we finish our pipeline will look like this:
//
// +-->queue-->decoder-->_videosink
......@@ -457,7 +507,7 @@ gboolean VideoReceiver::_onBusMessage(GstBus* bus, GstMessage* msg, gpointer dat
// +--------------------------------------+
void VideoReceiver::startRecording(void)
{
#if defined(QGC_GST_STREAMING) && defined(QGC_ENABLE_VIDEORECORDING)
#if defined(QGC_GST_STREAMING)
qCDebug(VideoReceiverLog) << "startRecording()";
// exit immediately if we are already recording
......@@ -468,36 +518,48 @@ void VideoReceiver::startRecording(void)
QString savePath = qgcApp()->toolbox()->settingsManager()->videoSettings()->videoSavePath()->rawValue().toString();
if(savePath.isEmpty()) {
qgcApp()->showMessage("Unabled to record video. Video save path must be specified in Settings.");
qgcApp()->showMessage(tr("Unabled to record video. Video save path must be specified in Settings."));
return;
}
uint32_t muxIdx = qgcApp()->toolbox()->settingsManager()->videoSettings()->recordingFormat()->rawValue().toUInt();
if(muxIdx >= NUM_MUXES) {
qgcApp()->showMessage(tr("Invalid video format defined."));
return;
}
//-- Disk usage maintenance
_cleanupOldVideos();
_sink = new Sink();
_sink->teepad = gst_element_get_request_pad(_tee, "src_%u");
_sink->queue = gst_element_factory_make("queue", NULL);
_sink->mux = gst_element_factory_make("matroskamux", NULL);
_sink->parse = gst_element_factory_make("h264parse", NULL);
_sink->mux = gst_element_factory_make(kVideoMuxes[muxIdx], NULL);
_sink->filesink = gst_element_factory_make("filesink", NULL);
_sink->removing = false;
if(!_sink->teepad || !_sink->queue || !_sink->mux || !_sink->filesink) {
if(!_sink->teepad || !_sink->queue || !_sink->mux || !_sink->filesink || !_sink->parse) {
qCritical() << "VideoReceiver::startRecording() failed to make _sink elements";
return;
}
QString videoFile;
videoFile = savePath + "/QGC-" + QDateTime::currentDateTime().toString("yyyy-MM-dd_hh.mm.ss") + ".mkv";
videoFile = savePath + "/" + QDateTime::currentDateTime().toString("yyyy-MM-dd_hh.mm.ss") + "." + kVideoExtensions[muxIdx];
g_object_set(G_OBJECT(_sink->filesink), "location", qPrintable(videoFile), NULL);
qCDebug(VideoReceiverLog) << "New video file:" << videoFile;
gst_object_ref(_sink->queue);
gst_object_ref(_sink->parse);
gst_object_ref(_sink->mux);
gst_object_ref(_sink->filesink);
gst_bin_add_many(GST_BIN(_pipeline), _sink->queue, _sink->mux, _sink->filesink, NULL);
gst_element_link_many(_sink->queue, _sink->mux, _sink->filesink, NULL);
gst_bin_add_many(GST_BIN(_pipeline), _sink->queue, _sink->parse, _sink->mux, _sink->filesink, NULL);
gst_element_link_many(_sink->queue, _sink->parse, _sink->mux, _sink->filesink, NULL);
gst_element_sync_state_with_parent(_sink->queue);
gst_element_sync_state_with_parent(_sink->parse);
gst_element_sync_state_with_parent(_sink->mux);
gst_element_sync_state_with_parent(_sink->filesink);
......@@ -513,7 +575,7 @@ void VideoReceiver::startRecording(void)
void VideoReceiver::stopRecording(void)
{
#if defined(QGC_GST_STREAMING) && defined(QGC_ENABLE_VIDEORECORDING)
#if defined(QGC_GST_STREAMING)
qCDebug(VideoReceiverLog) << "stopRecording()";
// exit immediately if we are not recording
if(_pipeline == NULL || !_recording) {
......@@ -534,6 +596,7 @@ void VideoReceiver::stopRecording(void)
void VideoReceiver::_shutdownRecordingBranch()
{
gst_bin_remove(GST_BIN(_pipelineStopRec), _sink->queue);
gst_bin_remove(GST_BIN(_pipelineStopRec), _sink->parse);
gst_bin_remove(GST_BIN(_pipelineStopRec), _sink->mux);
gst_bin_remove(GST_BIN(_pipelineStopRec), _sink->filesink);
......@@ -541,11 +604,13 @@ void VideoReceiver::_shutdownRecordingBranch()
gst_object_unref(_pipelineStopRec);
_pipelineStopRec = NULL;
gst_element_set_state(_sink->filesink, GST_STATE_NULL);
gst_element_set_state(_sink->mux, GST_STATE_NULL);
gst_element_set_state(_sink->queue, GST_STATE_NULL);
gst_element_set_state(_sink->filesink, GST_STATE_NULL);
gst_element_set_state(_sink->parse, GST_STATE_NULL);
gst_element_set_state(_sink->mux, GST_STATE_NULL);
gst_element_set_state(_sink->queue, GST_STATE_NULL);
gst_object_unref(_sink->queue);
gst_object_unref(_sink->parse);
gst_object_unref(_sink->mux);
gst_object_unref(_sink->filesink);
......@@ -568,7 +633,7 @@ void VideoReceiver::_detachRecordingBranch(GstPadProbeInfo* info)
Q_UNUSED(info)
// Also unlinks and unrefs
gst_bin_remove_many(GST_BIN(_pipeline), _sink->queue, _sink->mux, _sink->filesink, NULL);
gst_bin_remove_many(GST_BIN(_pipeline), _sink->queue, _sink->parse, _sink->mux, _sink->filesink, NULL);
// Give tee its pad back
gst_element_release_request_pad(_tee, _sink->teepad);
......@@ -578,8 +643,8 @@ void VideoReceiver::_detachRecordingBranch(GstPadProbeInfo* info)
_pipelineStopRec = gst_pipeline_new("pipeStopRec");
// Put our elements from the recording branch into the temporary pipeline
gst_bin_add_many(GST_BIN(_pipelineStopRec), _sink->queue, _sink->mux, _sink->filesink, NULL);
gst_element_link_many(_sink->queue, _sink->mux, _sink->filesink, NULL);
gst_bin_add_many(GST_BIN(_pipelineStopRec), _sink->queue, _sink->parse, _sink->mux, _sink->filesink, NULL);
gst_element_link_many(_sink->queue, _sink->parse, _sink->mux, _sink->filesink, NULL);
// Add handler for EOS event
GstBus* bus = gst_pipeline_get_bus(GST_PIPELINE(_pipelineStopRec));
......
......@@ -84,6 +84,7 @@ private:
GstElement* queue;
GstElement* mux;
GstElement* filesink;
GstElement* parse;
gboolean removing;
} Sink;
......@@ -100,6 +101,7 @@ private:
void _detachRecordingBranch(GstPadProbeInfo* info);
void _shutdownRecordingBranch();
void _shutdownPipeline();
void _cleanupOldVideos();
#endif
......
......@@ -42,6 +42,8 @@
GST_PLUGIN_STATIC_DECLARE(videoparsersbad);
GST_PLUGIN_STATIC_DECLARE(x264);
GST_PLUGIN_STATIC_DECLARE(rtpmanager);
GST_PLUGIN_STATIC_DECLARE(isomp4);
GST_PLUGIN_STATIC_DECLARE(matroska);
#endif
G_END_DECLS
#endif
......@@ -140,6 +142,8 @@ void initializeVideoStreaming(int &argc, char* argv[])
GST_PLUGIN_STATIC_REGISTER(videoparsersbad);
GST_PLUGIN_STATIC_REGISTER(x264);
GST_PLUGIN_STATIC_REGISTER(rtpmanager);
GST_PLUGIN_STATIC_REGISTER(isomp4);
GST_PLUGIN_STATIC_REGISTER(matroska);
#endif
#else
Q_UNUSED(argc);
......
......@@ -96,6 +96,8 @@ LinuxBuild {
-lgstvideoparsersbad \
-lgstrtpmanager \
-lgstrmdemux \
-lgstisomp4 \
-lgstmatroska \
# Rest of GStreamer dependencies
LIBS += -L$$GST_ROOT/lib \
......@@ -120,15 +122,6 @@ VideoEnabled {
message("Including support for video streaming")
contains (CONFIG, DISABLE_VIDEORECORDING) {
message("Skipping support for video recording (manual override from command line)")
# Otherwise the user can still disable this feature in the user_config.pri file.
} else:exists($$BASEDIR/user_config.pri):infile($$BASEDIR/user_config.pri, DEFINES, DISABLE_VIDEORECORDING) {
message("Skipping support for video recording (manual override from user_config.pri)")
} else {
DEFINES += QGC_ENABLE_VIDEORECORDING
}
DEFINES += \
QGC_GST_STREAMING \
GST_PLUGIN_BUILD_STATIC \
......
This diff is collapsed.
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