Commit 0e7f614d authored by Gus Grubba's avatar Gus Grubba

Initial secondary (thermal) video support

parent 11cc6ae2
...@@ -58,6 +58,8 @@ static const char* kVersion = "version"; ...@@ -58,6 +58,8 @@ static const char* kVersion = "version";
static const char* kPhotoMode = "PhotoMode"; static const char* kPhotoMode = "PhotoMode";
static const char* kPhotoLapse = "PhotoLapse"; static const char* kPhotoLapse = "PhotoLapse";
static const char* kPhotoLapseCount = "PhotoLapseCount"; static const char* kPhotoLapseCount = "PhotoLapseCount";
static const char* kThermalOpacity = "ThermalOpacity";
static const char* kThermalMode = "ThermalMode";
//----------------------------------------------------------------------------- //-----------------------------------------------------------------------------
// Known Parameters // Known Parameters
...@@ -174,9 +176,11 @@ QGCCameraControl::QGCCameraControl(const mavlink_camera_information_t *info, Veh ...@@ -174,9 +176,11 @@ QGCCameraControl::QGCCameraControl(const mavlink_camera_information_t *info, Veh
_initWhenReady(); _initWhenReady();
} }
QSettings settings; QSettings settings;
_photoMode = static_cast<PhotoMode>(settings.value(kPhotoMode, static_cast<int>(PHOTO_CAPTURE_SINGLE)).toInt()); _photoMode = static_cast<PhotoMode>(settings.value(kPhotoMode, static_cast<int>(PHOTO_CAPTURE_SINGLE)).toInt());
_photoLapse = settings.value(kPhotoLapse, 1.0).toDouble(); _photoLapse = settings.value(kPhotoLapse, 1.0).toDouble();
_photoLapseCount = settings.value(kPhotoLapseCount, 0).toInt(); _photoLapseCount = settings.value(kPhotoLapseCount, 0).toInt();
_thermalOpacity = settings.value(kThermalOpacity, 85.0).toDouble();
_thermalMode = static_cast<ThermalViewMode>(settings.value(kThermalMode, static_cast<uint32_t>(THERMAL_BLEND)).toUInt());
_recTimer.setSingleShot(false); _recTimer.setSingleShot(false);
_recTimer.setInterval(333); _recTimer.setInterval(333);
connect(&_recTimer, &QTimer::timeout, this, &QGCCameraControl::_recTimerHandler); connect(&_recTimer, &QTimer::timeout, this, &QGCCameraControl::_recTimerHandler);
...@@ -498,6 +502,30 @@ QGCCameraControl::setPhotoMode() ...@@ -498,6 +502,30 @@ QGCCameraControl::setPhotoMode()
} }
} }
//-----------------------------------------------------------------------------
void
QGCCameraControl::setThermalMode(ThermalViewMode mode)
{
QSettings settings;
settings.setValue(kThermalMode, static_cast<uint32_t>(mode));
_thermalMode = mode;
emit thermalModeChanged();
}
//-----------------------------------------------------------------------------
void
QGCCameraControl::setThermalOpacity(double val)
{
if(val < 0.0) val = 0.0;
if(val > 100.0) val = 100.0;
if(fabs(_thermalOpacity - val) > 0.1) {
_thermalOpacity = val;
QSettings settings;
settings.setValue(kThermalOpacity, val);
emit thermalOpacityChanged();
}
}
//----------------------------------------------------------------------------- //-----------------------------------------------------------------------------
void void
QGCCameraControl::setZoomLevel(qreal level) QGCCameraControl::setZoomLevel(qreal level)
...@@ -1496,10 +1524,14 @@ QGCCameraControl::handleVideoInfo(const mavlink_video_stream_information_t* vi) ...@@ -1496,10 +1524,14 @@ QGCCameraControl::handleVideoInfo(const mavlink_video_stream_information_t* vi)
QGCVideoStreamInfo* pStream = new QGCVideoStreamInfo(this, vi); QGCVideoStreamInfo* pStream = new QGCVideoStreamInfo(this, vi);
QQmlEngine::setObjectOwnership(pStream, QQmlEngine::CppOwnership); QQmlEngine::setObjectOwnership(pStream, QQmlEngine::CppOwnership);
_streams.append(pStream); _streams.append(pStream);
_streamLabels.append(pStream->name()); //-- Thermal is handled separately and not listed
emit streamsChanged(); if(!pStream->isThermal()) {
emit streamLabelsChanged(); _streamLabels.append(pStream->name());
qDebug() << _streamLabels; emit streamsChanged();
emit streamLabelsChanged();
} else {
emit thermalStreamChanged();
}
} }
//-- Check for missing count //-- Check for missing count
if(_streams.count() < _expectedCount) { if(_streams.count() < _expectedCount) {
...@@ -1531,7 +1563,7 @@ QGCCameraControl::handleVideoStatus(const mavlink_video_stream_status_t* vs) ...@@ -1531,7 +1563,7 @@ QGCCameraControl::handleVideoStatus(const mavlink_video_stream_status_t* vs)
void void
QGCCameraControl::setCurrentStream(int stream) QGCCameraControl::setCurrentStream(int stream)
{ {
if(stream != _currentStream && stream >= 0 && stream < _streams.count()) { if(stream != _currentStream && stream >= 0 && stream < _streamLabels.count()) {
if(_currentStream != stream) { if(_currentStream != stream) {
QGCVideoStreamInfo* pInfo = currentStreamInstance(); QGCVideoStreamInfo* pInfo = currentStreamInstance();
if(pInfo) { if(pInfo) {
...@@ -1606,13 +1638,31 @@ QGCCameraControl::autoStream() ...@@ -1606,13 +1638,31 @@ QGCCameraControl::autoStream()
QGCVideoStreamInfo* QGCVideoStreamInfo*
QGCCameraControl::currentStreamInstance() QGCCameraControl::currentStreamInstance()
{ {
if(_currentStream < _streams.count() && _streams.count()) { if(_currentStream < _streamLabels.count() && _streamLabels.count()) {
QGCVideoStreamInfo* pStream = qobject_cast<QGCVideoStreamInfo*>(_streams[_currentStream]); QGCVideoStreamInfo* pStream = _findStream(_streamLabels[_currentStream]);
return pStream; return pStream;
} }
return nullptr; return nullptr;
} }
//-----------------------------------------------------------------------------
QGCVideoStreamInfo*
QGCCameraControl::thermalStreamInstance()
{
//-- For now, it will return the first thermal listed (if any)
for(int i = 0; i < _streams.count(); i++) {
if(_streams[i]) {
QGCVideoStreamInfo* pStream = qobject_cast<QGCVideoStreamInfo*>(_streams[i]);
if(pStream) {
if(pStream->isThermal()) {
return pStream;
}
}
}
}
return nullptr;
}
//----------------------------------------------------------------------------- //-----------------------------------------------------------------------------
void void
QGCCameraControl::_requestStreamInfo(uint8_t streamID) QGCCameraControl::_requestStreamInfo(uint8_t streamID)
...@@ -1660,6 +1710,23 @@ QGCCameraControl::_findStream(uint8_t id, bool report) ...@@ -1660,6 +1710,23 @@ QGCCameraControl::_findStream(uint8_t id, bool report)
return nullptr; return nullptr;
} }
//-----------------------------------------------------------------------------
QGCVideoStreamInfo*
QGCCameraControl::_findStream(const QString name)
{
for(int i = 0; i < _streams.count(); i++) {
if(_streams[i]) {
QGCVideoStreamInfo* pStream = qobject_cast<QGCVideoStreamInfo*>(_streams[i]);
if(pStream) {
if(pStream->name() == name) {
return pStream;
}
}
}
}
return nullptr;
}
//----------------------------------------------------------------------------- //-----------------------------------------------------------------------------
void void
QGCCameraControl::_streamTimeout() QGCCameraControl::_streamTimeout()
......
...@@ -114,10 +114,18 @@ public: ...@@ -114,10 +114,18 @@ public:
PHOTO_CAPTURE_TIMELAPSE, PHOTO_CAPTURE_TIMELAPSE,
}; };
enum ThermalViewMode {
THERMAL_OFF = 0,
THERMAL_BLEND,
THERMAL_FULL,
THERMAL_PIP,
};
Q_ENUM(CameraMode) Q_ENUM(CameraMode)
Q_ENUM(VideoStatus) Q_ENUM(VideoStatus)
Q_ENUM(PhotoStatus) Q_ENUM(PhotoStatus)
Q_ENUM(PhotoMode) Q_ENUM(PhotoMode)
Q_ENUM(ThermalViewMode)
Q_PROPERTY(int version READ version NOTIFY infoChanged) Q_PROPERTY(int version READ version NOTIFY infoChanged)
Q_PROPERTY(QString modelName READ modelName NOTIFY infoChanged) Q_PROPERTY(QString modelName READ modelName NOTIFY infoChanged)
...@@ -162,9 +170,12 @@ public: ...@@ -162,9 +170,12 @@ public:
Q_PROPERTY(bool autoStream READ autoStream NOTIFY autoStreamChanged) Q_PROPERTY(bool autoStream READ autoStream NOTIFY autoStreamChanged)
Q_PROPERTY(QmlObjectListModel* streams READ streams NOTIFY streamsChanged) Q_PROPERTY(QmlObjectListModel* streams READ streams NOTIFY streamsChanged)
Q_PROPERTY(QGCVideoStreamInfo* currentStreamInstance READ currentStreamInstance NOTIFY currentStreamChanged) Q_PROPERTY(QGCVideoStreamInfo* currentStreamInstance READ currentStreamInstance NOTIFY currentStreamChanged)
Q_PROPERTY(QGCVideoStreamInfo* thermalStreamInstance READ thermalStreamInstance NOTIFY thermalStreamChanged)
Q_PROPERTY(quint32 recordTime READ recordTime NOTIFY recordTimeChanged) Q_PROPERTY(quint32 recordTime READ recordTime NOTIFY recordTimeChanged)
Q_PROPERTY(QString recordTimeStr READ recordTimeStr NOTIFY recordTimeChanged) Q_PROPERTY(QString recordTimeStr READ recordTimeStr NOTIFY recordTimeChanged)
Q_PROPERTY(QStringList streamLabels READ streamLabels NOTIFY streamLabelsChanged) Q_PROPERTY(QStringList streamLabels READ streamLabels NOTIFY streamLabelsChanged)
Q_PROPERTY(ThermalViewMode thermalMode READ thermalMode WRITE setThermalMode NOTIFY thermalModeChanged)
Q_PROPERTY(double thermalOpacity READ thermalOpacity WRITE setThermalOpacity NOTIFY thermalOpacityChanged)
Q_INVOKABLE virtual void setVideoMode (); Q_INVOKABLE virtual void setVideoMode ();
Q_INVOKABLE virtual void setPhotoMode (); Q_INVOKABLE virtual void setPhotoMode ();
...@@ -216,6 +227,7 @@ public: ...@@ -216,6 +227,7 @@ public:
virtual QmlObjectListModel* streams () { return &_streams; } virtual QmlObjectListModel* streams () { return &_streams; }
virtual QGCVideoStreamInfo* currentStreamInstance(); virtual QGCVideoStreamInfo* currentStreamInstance();
virtual QGCVideoStreamInfo* thermalStreamInstance();
virtual int currentStream () { return _currentStream; } virtual int currentStream () { return _currentStream; }
virtual void setCurrentStream (int stream); virtual void setCurrentStream (int stream);
virtual bool autoStream (); virtual bool autoStream ();
...@@ -231,7 +243,12 @@ public: ...@@ -231,7 +243,12 @@ public:
virtual Fact* mode (); virtual Fact* mode ();
//-- 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; }
virtual ThermalViewMode thermalMode () { return _thermalMode; }
virtual void setThermalMode (ThermalViewMode mode);
virtual double thermalOpacity () { return _thermalOpacity; }
virtual void setThermalOpacity (double val);
virtual void setZoomLevel (qreal level); virtual void setZoomLevel (qreal level);
virtual void setFocusLevel (qreal level); virtual void setFocusLevel (qreal level);
...@@ -282,9 +299,12 @@ signals: ...@@ -282,9 +299,12 @@ signals:
void focusLevelChanged (); void focusLevelChanged ();
void streamsChanged (); void streamsChanged ();
void currentStreamChanged (); void currentStreamChanged ();
void thermalStreamChanged ();
void autoStreamChanged (); void autoStreamChanged ();
void recordTimeChanged (); void recordTimeChanged ();
void streamLabelsChanged (); void streamLabelsChanged ();
void thermalModeChanged ();
void thermalOpacityChanged ();
protected: protected:
virtual void _setVideoStatus (VideoStatus status); virtual void _setVideoStatus (VideoStatus status);
...@@ -293,6 +313,7 @@ protected: ...@@ -293,6 +313,7 @@ protected:
virtual void _requestStreamInfo (uint8_t streamID); virtual void _requestStreamInfo (uint8_t streamID);
virtual void _requestStreamStatus (uint8_t streamID); virtual void _requestStreamStatus (uint8_t streamID);
virtual QGCVideoStreamInfo* _findStream (uint8_t streamID, bool report = true); virtual QGCVideoStreamInfo* _findStream (uint8_t streamID, bool report = true);
virtual QGCVideoStreamInfo* _findStream (const QString name);
protected slots: protected slots:
virtual void _initWhenReady (); virtual void _initWhenReady ();
...@@ -376,4 +397,6 @@ protected: ...@@ -376,4 +397,6 @@ protected:
QTimer _streamStatusTimer; QTimer _streamStatusTimer;
QmlObjectListModel _streams; QmlObjectListModel _streams;
QStringList _streamLabels; QStringList _streamLabels;
ThermalViewMode _thermalMode = THERMAL_BLEND;
double _thermalOpacity = 85.0;
}; };
...@@ -171,6 +171,18 @@ QGCCameraManager::currentStreamInstance() ...@@ -171,6 +171,18 @@ QGCCameraManager::currentStreamInstance()
return nullptr; return nullptr;
} }
//-----------------------------------------------------------------------------
QGCVideoStreamInfo*
QGCCameraManager::thermalStreamInstance()
{
QGCCameraControl* pCamera = currentCameraInstance();
if(pCamera) {
QGCVideoStreamInfo* pInfo = pCamera->thermalStreamInstance();
return pInfo;
}
return nullptr;
}
//----------------------------------------------------------------------------- //-----------------------------------------------------------------------------
QGCCameraControl* QGCCameraControl*
QGCCameraManager::_findCamera(int id) QGCCameraManager::_findCamera(int id)
......
...@@ -43,6 +43,8 @@ public: ...@@ -43,6 +43,8 @@ public:
virtual void setCurrentCamera (int sel); virtual void setCurrentCamera (int sel);
//-- Current stream //-- Current stream
virtual QGCVideoStreamInfo* currentStreamInstance(); virtual QGCVideoStreamInfo* currentStreamInstance();
//-- Current thermal stream
virtual QGCVideoStreamInfo* thermalStreamInstance();
signals: signals:
void camerasChanged (); void camerasChanged ();
......
...@@ -7,14 +7,13 @@ ...@@ -7,14 +7,13 @@
* *
****************************************************************************/ ****************************************************************************/
import QtQuick 2.11
import QtQuick.Controls 2.4
import QtQuick.Dialogs 1.3
import QtQuick.Layouts 1.11
import QtQuick 2.3
import QtQuick.Controls 1.2
import QtQuick.Controls.Styles 1.4
import QtQuick.Dialogs 1.2
import QtLocation 5.3 import QtLocation 5.3
import QtPositioning 5.3 import QtPositioning 5.3
import QtQuick.Layouts 1.2
import QtQuick.Window 2.2 import QtQuick.Window 2.2
import QtQml.Models 2.1 import QtQml.Models 2.1
......
...@@ -33,6 +33,9 @@ Item { ...@@ -33,6 +33,9 @@ Item {
property var _camera: _isCamera ? _dynamicCameras.cameras.get(_curCameraIndex) : null property var _camera: _isCamera ? _dynamicCameras.cameras.get(_curCameraIndex) : null
property bool _hasZoom: _camera && _camera.hasZoom property bool _hasZoom: _camera && _camera.hasZoom
property int _fitMode: QGroundControl.settingsManager.videoSettings.videoFit.rawValue property int _fitMode: QGroundControl.settingsManager.videoSettings.videoFit.rawValue
property double _thermalHeightFactor: 0.666 //-- TODO
Rectangle { Rectangle {
id: noVideo id: noVideo
anchors.fill: parent anchors.fill: parent
...@@ -72,6 +75,7 @@ Item { ...@@ -72,6 +75,7 @@ Item {
//-- Fit Width //-- Fit Width
return _ar != 0.0 ? parent.width * (1 / _ar) : parent.height return _ar != 0.0 ? parent.width * (1 / _ar) : parent.height
} }
//-- Main Video
QGCVideoBackground { QGCVideoBackground {
id: videoContent id: videoContent
height: parent.getHeight() height: parent.getHeight()
...@@ -119,12 +123,53 @@ Item { ...@@ -119,12 +123,53 @@ Item {
visible: _showGrid && !QGroundControl.videoManager.fullScreen visible: _showGrid && !QGroundControl.videoManager.fullScreen
} }
} }
//-- Thermal Image
Item {
id: thermalItem
width: height * QGroundControl.videoManager.thermalAspectRatio
height: _camera ? (_camera.thermalMode === QGCCameraControl.THERMAL_PIP ? ScreenTools.defaultFontPixelHeight * 12 : parent.height * _thermalHeightFactor) : 0
anchors.centerIn: parent
visible: QGroundControl.videoManager.hasThermal && _camera.thermalMode !== QGCCameraControl.THERMAL_OFF
function pipOrNot() {
if(_camera) {
if(_camera.thermalMode === QGCCameraControl.THERMAL_PIP) {
anchors.centerIn = undefined
anchors.top = parent.top
anchors.topMargin = mainWindow.header.height + (ScreenTools.defaultFontPixelHeight * 0.5)
anchors.left = parent.left
anchors.leftMargin = ScreenTools.defaultFontPixelWidth * 12
} else {
anchors.top = undefined
anchors.topMargin = undefined
anchors.left = undefined
anchors.leftMargin = undefined
anchors.centerIn = parent
}
}
}
Connections {
target: _camera
onThermalModeChanged: thermalItem.pipOrNot()
}
onVisibleChanged: {
thermalItem.pipOrNot()
}
QGCVideoBackground {
id: thermalVideo
anchors.fill: parent
receiver: QGroundControl.videoManager.thermalVideoReceiver
display: QGroundControl.videoManager.thermalVideoReceiver ? QGroundControl.videoManager.thermalVideoReceiver.videoSurface : null
opacity: _camera ? (_camera.thermalMode === QGCCameraControl.THERMAL_BLEND ? _camera.thermalOpacity / 100 : 1.0) : 0
}
}
//-- Full screen toggle
MouseArea { MouseArea {
anchors.fill: parent anchors.fill: parent
onDoubleClicked: { onDoubleClicked: {
QGroundControl.videoManager.fullScreen = !QGroundControl.videoManager.fullScreen QGroundControl.videoManager.fullScreen = !QGroundControl.videoManager.fullScreen
} }
} }
//-- Zoom
PinchArea { PinchArea {
id: pinchZoom id: pinchZoom
enabled: _hasZoom enabled: _hasZoom
......
...@@ -44,6 +44,9 @@ VideoManager::~VideoManager() ...@@ -44,6 +44,9 @@ VideoManager::~VideoManager()
if(_videoReceiver) { if(_videoReceiver) {
delete _videoReceiver; delete _videoReceiver;
} }
if(_thermalVideoReceiver) {
delete _thermalVideoReceiver;
}
} }
//----------------------------------------------------------------------------- //-----------------------------------------------------------------------------
...@@ -74,21 +77,76 @@ VideoManager::setToolbox(QGCToolbox *toolbox) ...@@ -74,21 +77,76 @@ VideoManager::setToolbox(QGCToolbox *toolbox)
emit isGStreamerChanged(); emit isGStreamerChanged();
qCDebug(VideoManagerLog) << "New Video Source:" << videoSource; qCDebug(VideoManagerLog) << "New Video Source:" << videoSource;
_videoReceiver = toolbox->corePlugin()->createVideoReceiver(this); _videoReceiver = toolbox->corePlugin()->createVideoReceiver(this);
_thermalVideoReceiver = toolbox->corePlugin()->createVideoReceiver(this);
_updateSettings(); _updateSettings();
if(isGStreamer()) { if(isGStreamer()) {
_videoReceiver->start(); startVideo();
} else { } else {
_videoReceiver->stop(); stopVideo();
} }
#endif #endif
} }
//-----------------------------------------------------------------------------
void
VideoManager::startVideo()
{
if(_videoReceiver) _videoReceiver->start();
if(_thermalVideoReceiver) _thermalVideoReceiver->start();
}
//-----------------------------------------------------------------------------
void
VideoManager::stopVideo()
{
if(_videoReceiver) _videoReceiver->stop();
if(_thermalVideoReceiver) _thermalVideoReceiver->stop();
}
//----------------------------------------------------------------------------- //-----------------------------------------------------------------------------
double VideoManager::aspectRatio() double VideoManager::aspectRatio()
{ {
if(_activeVehicle && _activeVehicle->dynamicCameras()) { if(_activeVehicle && _activeVehicle->dynamicCameras()) {
QGCVideoStreamInfo* pInfo = _activeVehicle->dynamicCameras()->currentStreamInstance(); QGCVideoStreamInfo* pInfo = _activeVehicle->dynamicCameras()->currentStreamInstance();
if(pInfo) {
qCDebug(VideoManagerLog) << "Primary AR: " << pInfo->aspectRatio();
return pInfo->aspectRatio();
}
}
return _videoSettings->aspectRatio()->rawValue().toDouble();
}
//-----------------------------------------------------------------------------
double VideoManager::thermalAspectRatio()
{
if(_activeVehicle && _activeVehicle->dynamicCameras()) {
QGCVideoStreamInfo* pInfo = _activeVehicle->dynamicCameras()->thermalStreamInstance();
if(pInfo) {
qCDebug(VideoManagerLog) << "Thermal AR: " << pInfo->aspectRatio();
return pInfo->aspectRatio();
}
}
return 1.0;
}
//-----------------------------------------------------------------------------
double VideoManager::hfov()
{
if(_activeVehicle && _activeVehicle->dynamicCameras()) {
QGCVideoStreamInfo* pInfo = _activeVehicle->dynamicCameras()->currentStreamInstance();
if(pInfo) {
return pInfo->hfov();
}
}
return 1.0;
}
//-----------------------------------------------------------------------------
double VideoManager::thermalHfov()
{
if(_activeVehicle && _activeVehicle->dynamicCameras()) {
QGCVideoStreamInfo* pInfo = _activeVehicle->dynamicCameras()->thermalStreamInstance();
if(pInfo) { if(pInfo) {
return pInfo->aspectRatio(); return pInfo->aspectRatio();
} }
...@@ -96,6 +154,19 @@ double VideoManager::aspectRatio() ...@@ -96,6 +154,19 @@ double VideoManager::aspectRatio()
return _videoSettings->aspectRatio()->rawValue().toDouble(); return _videoSettings->aspectRatio()->rawValue().toDouble();
} }
//-----------------------------------------------------------------------------
bool
VideoManager::hasThermal()
{
if(_activeVehicle && _activeVehicle->dynamicCameras()) {
QGCVideoStreamInfo* pInfo = _activeVehicle->dynamicCameras()->thermalStreamInstance();
if(pInfo) {
return true;
}
}
return false;
}
//----------------------------------------------------------------------------- //-----------------------------------------------------------------------------
bool bool
VideoManager::autoStreamConfigured() VideoManager::autoStreamConfigured()
...@@ -204,8 +275,9 @@ VideoManager::_updateSettings() ...@@ -204,8 +275,9 @@ VideoManager::_updateSettings()
return; return;
//-- Auto discovery //-- Auto discovery
if(_activeVehicle && _activeVehicle->dynamicCameras()) { if(_activeVehicle && _activeVehicle->dynamicCameras()) {
QGCVideoStreamInfo* pInfo = _activeVehicle->dynamicCameras()->currentStreamInstance(); QGCVideoStreamInfo* pInfo = _activeVehicle->dynamicCameras()->currentStreamInstance();
if(pInfo) { if(pInfo) {
qCDebug(VideoManagerLog) << "Configure primary stream: " << pInfo->uri();
switch(pInfo->type()) { switch(pInfo->type()) {
case VIDEO_STREAM_TYPE_RTSP: case VIDEO_STREAM_TYPE_RTSP:
case VIDEO_STREAM_TYPE_TCP_MPEG: case VIDEO_STREAM_TYPE_TCP_MPEG:
...@@ -221,6 +293,26 @@ VideoManager::_updateSettings() ...@@ -221,6 +293,26 @@ VideoManager::_updateSettings()
_videoReceiver->setUri(pInfo->uri()); _videoReceiver->setUri(pInfo->uri());
break; break;
} }
//-- Thermal stream (if any)
QGCVideoStreamInfo* pTinfo = _activeVehicle->dynamicCameras()->thermalStreamInstance();
if(pTinfo) {
qCDebug(VideoManagerLog) << "Configure secondary stream: " << pTinfo->uri();
switch(pTinfo->type()) {
case VIDEO_STREAM_TYPE_RTSP:
case VIDEO_STREAM_TYPE_TCP_MPEG:
_thermalVideoReceiver->setUri(pTinfo->uri());
break;
case VIDEO_STREAM_TYPE_RTPUDP:
_thermalVideoReceiver->setUri(QStringLiteral("udp://0.0.0.0:%1").arg(pTinfo->uri()));
break;
case VIDEO_STREAM_TYPE_MPEG_TS_H264:
_thermalVideoReceiver->setUri(QStringLiteral("mpegts://0.0.0.0:%1").arg(pTinfo->uri()));
break;
default:
_thermalVideoReceiver->setUri(pTinfo->uri());
break;
}
}
return; return;
} }
} }
...@@ -241,11 +333,9 @@ VideoManager::_restartVideo() ...@@ -241,11 +333,9 @@ VideoManager::_restartVideo()
{ {
#if defined(QGC_GST_STREAMING) #if defined(QGC_GST_STREAMING)
qCDebug(VideoManagerLog) << "Restart video streaming"; qCDebug(VideoManagerLog) << "Restart video streaming";
if(!_videoReceiver) stopVideo();
return;
_videoReceiver->stop();
_updateSettings(); _updateSettings();
_videoReceiver->start(); startVideo();
emit aspectRatioChanged(); emit aspectRatioChanged();
#endif #endif
} }
......
...@@ -42,8 +42,13 @@ public: ...@@ -42,8 +42,13 @@ public:
Q_PROPERTY(bool uvcEnabled READ uvcEnabled CONSTANT) Q_PROPERTY(bool uvcEnabled READ uvcEnabled CONSTANT)
Q_PROPERTY(bool fullScreen READ fullScreen WRITE setfullScreen NOTIFY fullScreenChanged) Q_PROPERTY(bool fullScreen READ fullScreen WRITE setfullScreen NOTIFY fullScreenChanged)
Q_PROPERTY(VideoReceiver* videoReceiver READ videoReceiver CONSTANT) Q_PROPERTY(VideoReceiver* videoReceiver READ videoReceiver CONSTANT)
Q_PROPERTY(VideoReceiver* thermalVideoReceiver READ thermalVideoReceiver CONSTANT)
Q_PROPERTY(double aspectRatio READ aspectRatio NOTIFY aspectRatioChanged) Q_PROPERTY(double aspectRatio READ aspectRatio NOTIFY aspectRatioChanged)
Q_PROPERTY(double thermalAspectRatio READ thermalAspectRatio NOTIFY aspectRatioChanged)
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 autoStreamConfigured READ autoStreamConfigured NOTIFY autoStreamConfiguredChanged)
Q_PROPERTY(bool hasThermal READ hasThermal NOTIFY aspectRatioChanged)
bool hasVideo (); bool hasVideo ();
bool isGStreamer (); bool isGStreamer ();
...@@ -52,9 +57,14 @@ public: ...@@ -52,9 +57,14 @@ public:
bool fullScreen () { return _fullScreen; } bool fullScreen () { return _fullScreen; }
QString videoSourceID () { return _videoSourceID; } QString videoSourceID () { return _videoSourceID; }
double aspectRatio (); double aspectRatio ();
double thermalAspectRatio ();
double hfov ();
double thermalHfov ();
bool autoStreamConfigured(); bool autoStreamConfigured();
bool hasThermal ();
VideoReceiver* videoReceiver () { return _videoReceiver; } VideoReceiver* videoReceiver () { return _videoReceiver; }
VideoReceiver* thermalVideoReceiver () { return _thermalVideoReceiver; }
#if defined(QGC_DISABLE_UVC) #if defined(QGC_DISABLE_UVC)
bool uvcEnabled () { return false; } bool uvcEnabled () { return false; }
...@@ -68,8 +78,8 @@ public: ...@@ -68,8 +78,8 @@ public:
// Override from QGCTool // Override from QGCTool
void setToolbox (QGCToolbox *toolbox); void setToolbox (QGCToolbox *toolbox);
Q_INVOKABLE void startVideo () { _videoReceiver->start(); } Q_INVOKABLE void startVideo ();
Q_INVOKABLE void stopVideo () { _videoReceiver->stop(); } Q_INVOKABLE void stopVideo ();
signals: signals:
void hasVideoChanged (); void hasVideoChanged ();
...@@ -95,12 +105,13 @@ private: ...@@ -95,12 +105,13 @@ private:
void _updateSettings (); void _updateSettings ();
private: private:
bool _isTaisync = false; bool _isTaisync = false;
VideoReceiver* _videoReceiver = nullptr; VideoReceiver* _videoReceiver = nullptr;
VideoSettings* _videoSettings = nullptr; VideoReceiver* _thermalVideoReceiver = nullptr;
VideoSettings* _videoSettings = nullptr;
QString _videoSourceID; QString _videoSourceID;
bool _fullScreen = false; bool _fullScreen = false;
Vehicle* _activeVehicle = nullptr; Vehicle* _activeVehicle = nullptr;
}; };
#endif #endif
...@@ -14,9 +14,9 @@ ...@@ -14,9 +14,9 @@
* @author Gus Grubba <mavlink@grubba.com> * @author Gus Grubba <mavlink@grubba.com>
*/ */
import QtQuick 2.3 import QtQuick 2.11
import QtQuick.Controls 1.2 import QtQuick.Controls 2.4
import QGroundControl.QgcQtGStreamer 1.0 import QGroundControl.QgcQtGStreamer 1.0
VideoItem { VideoItem {
id: videoBackground id: videoBackground
......
...@@ -205,8 +205,8 @@ Column { ...@@ -205,8 +205,8 @@ Column {
//------------------------------------------- //-------------------------------------------
//-- Camera Selector //-- Camera Selector
Row { Row {
visible: _isCamera spacing: ScreenTools.defaultFontPixelWidth
spacing: ScreenTools.defaultFontPixelWidth visible: _isCamera && _dynamicCameras.cameraLabels.length > 1
anchors.horizontalCenter: parent.horizontalCenter anchors.horizontalCenter: parent.horizontalCenter
QGCLabel { QGCLabel {
text: qsTr("Camera Selector:") text: qsTr("Camera Selector:")
...@@ -225,6 +225,7 @@ Column { ...@@ -225,6 +225,7 @@ Column {
//-- Stream Selector //-- Stream Selector
Row { Row {
spacing: ScreenTools.defaultFontPixelWidth spacing: ScreenTools.defaultFontPixelWidth
visible: _isCamera && _camera.streamLabels.length > 1
anchors.horizontalCenter: parent.horizontalCenter anchors.horizontalCenter: parent.horizontalCenter
QGCLabel { QGCLabel {
text: qsTr("Stream Selector:") text: qsTr("Stream Selector:")
...@@ -238,7 +239,47 @@ Column { ...@@ -238,7 +239,47 @@ Column {
currentIndex: _camera ? _camera.currentStream : 0 currentIndex: _camera ? _camera.currentStream : 0
} }
} }
//-------------------------------------------
//-- Thermal Modes
Row {
spacing: ScreenTools.defaultFontPixelWidth
anchors.horizontalCenter: parent.horizontalCenter
visible: QGroundControl.videoManager.hasThermal
property var thermalModes: [qsTr("Off"), qsTr("Blend"), qsTr("Full"), qsTr("Picture In Picture")]
QGCLabel {
text: qsTr("Thermal View Mode")
width: _labelFieldWidth
anchors.verticalCenter: parent.verticalCenter
}
QGCComboBox {
width: _editFieldWidth
model: parent.thermalModes
currentIndex: _camera ? _camera.thermalMode : 0
onActivated: _camera.thermalMode = index
}
}
//-------------------------------------------
//-- Thermal Video Opacity
Row {
spacing: ScreenTools.defaultFontPixelWidth
anchors.horizontalCenter: parent.horizontalCenter
visible: QGroundControl.videoManager.hasThermal && _camera.thermalMode === QGCCameraControl.THERMAL_BLEND
QGCLabel {
text: qsTr("Blend Opacity")
width: _labelFieldWidth
anchors.verticalCenter: parent.verticalCenter
}
Slider {
width: _editFieldWidth
maximumValue: 100
minimumValue: 0
value: _camera ? _camera.thermalOpacity : 0
updateValueWhileDragging: true
onValueChanged: {
_camera.thermalOpacity = value
}
}
}
//------------------------------------------- //-------------------------------------------
//-- Camera Settings //-- Camera Settings
Repeater { Repeater {
......
...@@ -567,7 +567,7 @@ void ...@@ -567,7 +567,7 @@ void
VideoReceiver::_handleStateChanged() { VideoReceiver::_handleStateChanged() {
if(_pipeline) { if(_pipeline) {
_streaming = GST_STATE(_pipeline) == GST_STATE_PLAYING; _streaming = GST_STATE(_pipeline) == GST_STATE_PLAYING;
qCDebug(VideoReceiverLog) << "State changed, _streaming:" << _streaming; //qCDebug(VideoReceiverLog) << "State changed, _streaming:" << _streaming;
} }
} }
#endif #endif
......
...@@ -7,7 +7,6 @@ ...@@ -7,7 +7,6 @@
* *
****************************************************************************/ ****************************************************************************/
/** /**
* @file * @file
* @brief QGC Video Receiver * @brief QGC Video Receiver
......
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