Unverified Commit ace5e73b authored by Gus Grubba's avatar Gus Grubba Committed by GitHub

Merge pull request #7435 from MatejFranceskin/pr-restart-video-stream-after-change

Restart video stream after change
parents a6a161ca f8182edd
...@@ -70,6 +70,9 @@ const char* QGCCameraControl::kCAM_SHUTTERSPD = "CAM_SHUTTERSPD"; ...@@ -70,6 +70,9 @@ const char* QGCCameraControl::kCAM_SHUTTERSPD = "CAM_SHUTTERSPD";
const char* QGCCameraControl::kCAM_APERTURE = "CAM_APERTURE"; const char* QGCCameraControl::kCAM_APERTURE = "CAM_APERTURE";
const char* QGCCameraControl::kCAM_WBMODE = "CAM_WBMODE"; const char* QGCCameraControl::kCAM_WBMODE = "CAM_WBMODE";
const char* QGCCameraControl::kCAM_MODE = "CAM_MODE"; const char* QGCCameraControl::kCAM_MODE = "CAM_MODE";
const char* QGCCameraControl::kCAM_BITRATE = "CAM_BITRATE";
const char* QGCCameraControl::kCAM_FPS = "CAM_FPS";
const char* QGCCameraControl::kCAM_ENC = "CAM_ENC";
//----------------------------------------------------------------------------- //-----------------------------------------------------------------------------
QGCCameraOptionExclusion::QGCCameraOptionExclusion(QObject* parent, QString param_, QString value_, QStringList exclusions_) QGCCameraOptionExclusion::QGCCameraOptionExclusion(QObject* parent, QString param_, QString value_, QStringList exclusions_)
...@@ -2105,6 +2108,27 @@ QGCCameraControl::mode() ...@@ -2105,6 +2108,27 @@ QGCCameraControl::mode()
return _paramComplete ? getFact(kCAM_MODE) : nullptr; return _paramComplete ? getFact(kCAM_MODE) : nullptr;
} }
//-----------------------------------------------------------------------------
Fact*
QGCCameraControl::bitRate()
{
return _paramComplete ? getFact(kCAM_BITRATE) : nullptr;
}
//-----------------------------------------------------------------------------
Fact*
QGCCameraControl::frameRate()
{
return _paramComplete ? getFact(kCAM_FPS) : nullptr;
}
//-----------------------------------------------------------------------------
Fact*
QGCCameraControl::videoEncoding()
{
return _paramComplete ? getFact(kCAM_ENC) : nullptr;
}
//----------------------------------------------------------------------------- //-----------------------------------------------------------------------------
QGCVideoStreamInfo::QGCVideoStreamInfo(QObject* parent, const mavlink_video_stream_information_t *si) QGCVideoStreamInfo::QGCVideoStreamInfo(QObject* parent, const mavlink_video_stream_information_t *si)
: QObject(parent) : QObject(parent)
......
...@@ -167,6 +167,9 @@ public: ...@@ -167,6 +167,9 @@ public:
Q_PROPERTY(Fact* aperture READ aperture NOTIFY parametersReady) Q_PROPERTY(Fact* aperture READ aperture NOTIFY parametersReady)
Q_PROPERTY(Fact* wb READ wb NOTIFY parametersReady) Q_PROPERTY(Fact* wb READ wb NOTIFY parametersReady)
Q_PROPERTY(Fact* mode READ mode NOTIFY parametersReady) Q_PROPERTY(Fact* mode READ mode NOTIFY parametersReady)
Q_PROPERTY(Fact* bitRate READ bitRate NOTIFY parametersReady)
Q_PROPERTY(Fact* frameRate READ frameRate NOTIFY parametersReady)
Q_PROPERTY(Fact* videoEncoding READ videoEncoding NOTIFY parametersReady)
Q_PROPERTY(QStringList activeSettings READ activeSettings NOTIFY activeSettingsChanged) Q_PROPERTY(QStringList activeSettings READ activeSettings NOTIFY activeSettingsChanged)
Q_PROPERTY(VideoStatus videoStatus READ videoStatus NOTIFY videoStatusChanged) Q_PROPERTY(VideoStatus videoStatus READ videoStatus NOTIFY videoStatusChanged)
...@@ -252,6 +255,9 @@ public: ...@@ -252,6 +255,9 @@ public:
virtual Fact* aperture (); virtual Fact* aperture ();
virtual Fact* wb (); virtual Fact* wb ();
virtual Fact* mode (); virtual Fact* mode ();
virtual Fact* bitRate ();
virtual Fact* frameRate ();
virtual Fact* videoEncoding ();
//-- Stream names to show the user (for selection) //-- Stream names to show the user (for selection)
virtual QStringList streamLabels () { return _streamLabels; } virtual QStringList streamLabels () { return _streamLabels; }
...@@ -292,6 +298,9 @@ public: ...@@ -292,6 +298,9 @@ public:
static const char* kCAM_APERTURE; static const char* kCAM_APERTURE;
static const char* kCAM_WBMODE; static const char* kCAM_WBMODE;
static const char* kCAM_MODE; static const char* kCAM_MODE;
static const char* kCAM_BITRATE;
static const char* kCAM_FPS;
static const char* kCAM_ENC;
signals: signals:
void infoChanged (); void infoChanged ();
......
/**************************************************************************** /****************************************************************************
* *
* (c) 2009-2016 QGROUNDCONTROL PROJECT <http://www.qgroundcontrol.org> * (c) 2009-2019 QGROUNDCONTROL PROJECT <http://www.qgroundcontrol.org>
* *
* QGroundControl is licensed according to the terms in the file * QGroundControl is licensed according to the terms in the file
* COPYING.md in the root of the source code directory. * COPYING.md in the root of the source code directory.
...@@ -206,28 +206,28 @@ VideoManager::_videoSourceChanged() ...@@ -206,28 +206,28 @@ VideoManager::_videoSourceChanged()
emit hasVideoChanged(); emit hasVideoChanged();
emit isGStreamerChanged(); emit isGStreamerChanged();
emit isAutoStreamChanged(); emit isAutoStreamChanged();
_restartVideo(); restartVideo();
} }
//----------------------------------------------------------------------------- //-----------------------------------------------------------------------------
void void
VideoManager::_udpPortChanged() VideoManager::_udpPortChanged()
{ {
_restartVideo(); restartVideo();
} }
//----------------------------------------------------------------------------- //-----------------------------------------------------------------------------
void void
VideoManager::_rtspUrlChanged() VideoManager::_rtspUrlChanged()
{ {
_restartVideo(); restartVideo();
} }
//----------------------------------------------------------------------------- //-----------------------------------------------------------------------------
void void
VideoManager::_tcpUrlChanged() VideoManager::_tcpUrlChanged()
{ {
_restartVideo(); restartVideo();
} }
//----------------------------------------------------------------------------- //-----------------------------------------------------------------------------
...@@ -275,6 +275,13 @@ VideoManager::_updateSettings() ...@@ -275,6 +275,13 @@ VideoManager::_updateSettings()
return; return;
//-- Auto discovery //-- Auto discovery
if(_activeVehicle && _activeVehicle->dynamicCameras()) { if(_activeVehicle && _activeVehicle->dynamicCameras()) {
QGCCameraControl* pCamera = _activeVehicle->dynamicCameras()->currentCameraInstance();
if(pCamera) {
Fact *fact = pCamera->videoEncoding();
if (fact) {
_videoReceiver->setVideoDecoder(static_cast<VideoReceiver::VideoEncoding>(fact->rawValue().toInt()));
}
}
QGCVideoStreamInfo* pInfo = _activeVehicle->dynamicCameras()->currentStreamInstance(); QGCVideoStreamInfo* pInfo = _activeVehicle->dynamicCameras()->currentStreamInstance();
if(pInfo) { if(pInfo) {
qCDebug(VideoManagerLog) << "Configure primary stream: " << pInfo->uri(); qCDebug(VideoManagerLog) << "Configure primary stream: " << pInfo->uri();
...@@ -329,7 +336,7 @@ VideoManager::_updateSettings() ...@@ -329,7 +336,7 @@ VideoManager::_updateSettings()
//----------------------------------------------------------------------------- //-----------------------------------------------------------------------------
void void
VideoManager::_restartVideo() VideoManager::restartVideo()
{ {
#if defined(QGC_GST_STREAMING) #if defined(QGC_GST_STREAMING)
qCDebug(VideoManagerLog) << "Restart video streaming"; qCDebug(VideoManagerLog) << "Restart video streaming";
...@@ -350,13 +357,13 @@ VideoManager::_setActiveVehicle(Vehicle* vehicle) ...@@ -350,13 +357,13 @@ VideoManager::_setActiveVehicle(Vehicle* vehicle)
if(pCamera) { if(pCamera) {
pCamera->stopStream(); pCamera->stopStream();
} }
disconnect(_activeVehicle->dynamicCameras(), &QGCCameraManager::streamChanged, this, &VideoManager::_restartVideo); disconnect(_activeVehicle->dynamicCameras(), &QGCCameraManager::streamChanged, this, &VideoManager::restartVideo);
} }
} }
_activeVehicle = vehicle; _activeVehicle = vehicle;
if(_activeVehicle) { if(_activeVehicle) {
if(_activeVehicle->dynamicCameras()) { if(_activeVehicle->dynamicCameras()) {
connect(_activeVehicle->dynamicCameras(), &QGCCameraManager::streamChanged, this, &VideoManager::_restartVideo); connect(_activeVehicle->dynamicCameras(), &QGCCameraManager::streamChanged, this, &VideoManager::restartVideo);
QGCCameraControl* pCamera = _activeVehicle->dynamicCameras()->currentCameraInstance(); QGCCameraControl* pCamera = _activeVehicle->dynamicCameras()->currentCameraInstance();
if(pCamera) { if(pCamera) {
pCamera->resumeStream(); pCamera->resumeStream();
...@@ -364,7 +371,7 @@ VideoManager::_setActiveVehicle(Vehicle* vehicle) ...@@ -364,7 +371,7 @@ VideoManager::_setActiveVehicle(Vehicle* vehicle)
} }
} }
emit autoStreamConfiguredChanged(); emit autoStreamConfiguredChanged();
_restartVideo(); restartVideo();
} }
//---------------------------------------------------------------------------------------- //----------------------------------------------------------------------------------------
......
/**************************************************************************** /****************************************************************************
* *
* (c) 2009-2016 QGROUNDCONTROL PROJECT <http://www.qgroundcontrol.org> * (c) 2009-2019 QGROUNDCONTROL PROJECT <http://www.qgroundcontrol.org>
* *
* QGroundControl is licensed according to the terms in the file * QGroundControl is licensed according to the terms in the file
* COPYING.md in the root of the source code directory. * COPYING.md in the root of the source code directory.
...@@ -62,6 +62,7 @@ public: ...@@ -62,6 +62,7 @@ public:
double thermalHfov (); double thermalHfov ();
bool autoStreamConfigured(); bool autoStreamConfigured();
bool hasThermal (); bool hasThermal ();
void restartVideo ();
VideoReceiver* videoReceiver () { return _videoReceiver; } VideoReceiver* videoReceiver () { return _videoReceiver; }
VideoReceiver* thermalVideoReceiver () { return _thermalVideoReceiver; } VideoReceiver* thermalVideoReceiver () { return _thermalVideoReceiver; }
...@@ -99,7 +100,6 @@ private slots: ...@@ -99,7 +100,6 @@ private slots:
void _updateUVC (); void _updateUVC ();
void _setActiveVehicle (Vehicle* vehicle); void _setActiveVehicle (Vehicle* vehicle);
void _aspectRatioChanged (); void _aspectRatioChanged ();
void _restartVideo ();
private: private:
void _updateSettings (); void _updateSettings ();
......
This diff is collapsed.
/**************************************************************************** /****************************************************************************
* *
* (c) 2009-2018 QGROUNDCONTROL PROJECT <http://www.qgroundcontrol.org> * (c) 2009-2019 QGROUNDCONTROL PROJECT <http://www.qgroundcontrol.org>
* *
* QGroundControl is licensed according to the terms in the file * QGroundControl is licensed according to the terms in the file
* COPYING.md in the root of the source code directory. * COPYING.md in the root of the source code directory.
...@@ -34,6 +34,13 @@ class VideoReceiver : public QObject ...@@ -34,6 +34,13 @@ class VideoReceiver : public QObject
{ {
Q_OBJECT Q_OBJECT
public: public:
enum VideoEncoding {
H264_SW = 1,
H264_HW = 2,
H265_SW = 3,
H265_HW = 4
};
#if defined(QGC_GST_STREAMING) #if defined(QGC_GST_STREAMING)
Q_PROPERTY(bool recording READ recording NOTIFY recordingChanged) Q_PROPERTY(bool recording READ recording NOTIFY recordingChanged)
#endif #endif
...@@ -47,11 +54,7 @@ public: ...@@ -47,11 +54,7 @@ public:
~VideoReceiver(); ~VideoReceiver();
#if defined(QGC_GST_STREAMING) #if defined(QGC_GST_STREAMING)
virtual bool running () { return _running; }
virtual bool recording () { return _recording; } virtual bool recording () { return _recording; }
virtual bool streaming () { return _streaming; }
virtual bool starting () { return _starting; }
virtual bool stopping () { return _stopping; }
#endif #endif
virtual VideoSurface* videoSurface () { return _videoSurface; } virtual VideoSurface* videoSurface () { return _videoSurface; }
...@@ -64,6 +67,8 @@ public: ...@@ -64,6 +67,8 @@ public:
virtual void setShowFullScreen (bool show) { _showFullScreen = show; emit showFullScreenChanged(); } virtual void setShowFullScreen (bool show) { _showFullScreen = show; emit showFullScreenChanged(); }
void setVideoDecoder (VideoEncoding encoding);
signals: signals:
void videoRunningChanged (); void videoRunningChanged ();
void imageFileChanged (); void imageFileChanged ();
...@@ -86,9 +91,7 @@ public slots: ...@@ -86,9 +91,7 @@ public slots:
protected slots: protected slots:
virtual void _updateTimer (); virtual void _updateTimer ();
#if defined(QGC_GST_STREAMING) #if defined(QGC_GST_STREAMING)
virtual void _timeout (); virtual void _restart_timeout ();
virtual void _connected ();
virtual void _socketError (QAbstractSocket::SocketError socketError);
virtual void _handleError (); virtual void _handleError ();
virtual void _handleEOS (); virtual void _handleEOS ();
virtual void _handleStateChanged (); virtual void _handleStateChanged ();
...@@ -132,14 +135,11 @@ protected: ...@@ -132,14 +135,11 @@ protected:
//-- Wait for Video Server to show up before starting //-- Wait for Video Server to show up before starting
QTimer _frameTimer; QTimer _frameTimer;
QTimer _timer; QTimer _restart_timer;
QTcpSocket* _socket; int _restart_time_ms;
bool _serverPresent;
int _rtspTestInterval_ms;
//-- RTSP UDP reconnect timeout //-- RTSP UDP reconnect timeout
uint64_t _udpReconnect_us; uint64_t _udpReconnect_us;
#endif #endif
QString _uri; QString _uri;
...@@ -149,5 +149,8 @@ protected: ...@@ -149,5 +149,8 @@ protected:
bool _videoRunning; bool _videoRunning;
bool _showFullScreen; bool _showFullScreen;
VideoSettings* _videoSettings; VideoSettings* _videoSettings;
const char* _depayName;
const char* _parserName;
const char* _decoderName;
}; };
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