VideoManager.cc 9.54 KB
Newer Older
1 2 3 4 5 6 7 8 9 10 11 12 13
/****************************************************************************
 *
 *   (c) 2009-2016 QGROUNDCONTROL PROJECT <http://www.qgroundcontrol.org>
 *
 * QGroundControl is licensed according to the terms in the file
 * COPYING.md in the root of the source code directory.
 *
 ****************************************************************************/


#include <QQmlContext>
#include <QQmlEngine>
#include <QSettings>
14
#include <QUrl>
15
#include <QDir>
16 17

#ifndef QGC_DISABLE_UVC
18
#include <QCameraInfo>
19
#endif
20 21 22 23 24

#include <VideoItem.h>

#include "ScreenToolsController.h"
#include "VideoManager.h"
25 26 27
#include "QGCToolbox.h"
#include "QGCCorePlugin.h"
#include "QGCOptions.h"
28
#include "MultiVehicleManager.h"
29
#include "Settings/SettingsManager.h"
30
#include "Vehicle.h"
31
#include "QGCCameraManager.h"
32 33 34 35

QGC_LOGGING_CATEGORY(VideoManagerLog, "VideoManagerLog")

//-----------------------------------------------------------------------------
36 37
VideoManager::VideoManager(QGCApplication* app, QGCToolbox* toolbox)
    : QGCTool(app, toolbox)
38 39 40 41 42 43
{
}

//-----------------------------------------------------------------------------
VideoManager::~VideoManager()
{
44 45 46
    if(_videoReceiver) {
        delete _videoReceiver;
    }
47 48 49 50 51 52 53 54
}

//-----------------------------------------------------------------------------
void
VideoManager::setToolbox(QGCToolbox *toolbox)
{
   QGCTool::setToolbox(toolbox);
   QQmlEngine::setObjectOwnership(this, QQmlEngine::CppOwnership);
55 56 57
   qmlRegisterUncreatableType<VideoManager> ("QGroundControl.VideoManager", 1, 0, "VideoManager", "Reference only");
   qmlRegisterUncreatableType<VideoReceiver>("QGroundControl",              1, 0, "VideoReceiver","Reference only");
   qmlRegisterUncreatableType<VideoSurface> ("QGroundControl",              1, 0, "VideoSurface", "Reference only");
58 59
   _videoSettings = toolbox->settingsManager()->videoSettings();
   QString videoSource = _videoSettings->videoSource()->rawValue().toString();
60 61 62
   connect(_videoSettings->videoSource(),   &Fact::rawValueChanged, this, &VideoManager::_videoSourceChanged);
   connect(_videoSettings->udpPort(),       &Fact::rawValueChanged, this, &VideoManager::_udpPortChanged);
   connect(_videoSettings->rtspUrl(),       &Fact::rawValueChanged, this, &VideoManager::_rtspUrlChanged);
63
   connect(_videoSettings->tcpUrl(),        &Fact::rawValueChanged, this, &VideoManager::_tcpUrlChanged);
64
   connect(_videoSettings->aspectRatio(),   &Fact::rawValueChanged, this, &VideoManager::_aspectRatioChanged);
65 66
   MultiVehicleManager *pVehicleMgr = qgcApp()->toolbox()->multiVehicleManager();
   connect(pVehicleMgr, &MultiVehicleManager::activeVehicleChanged, this, &VideoManager::_setActiveVehicle);
67

68
#if defined(QGC_GST_STREAMING)
69 70
#ifndef QGC_DISABLE_UVC
   // If we are using a UVC camera setup the device name
Gus Grubba's avatar
Gus Grubba committed
71
   _updateUVC();
72
#endif
73 74 75

    emit isGStreamerChanged();
    qCDebug(VideoManagerLog) << "New Video Source:" << videoSource;
76
    _videoReceiver = toolbox->corePlugin()->createVideoReceiver(this);
77 78 79 80 81
    _updateSettings();
    if(isGStreamer()) {
        _videoReceiver->start();
    } else {
        _videoReceiver->stop();
82 83
    }

84
#endif
85 86
}

87 88 89
//-----------------------------------------------------------------------------
double VideoManager::aspectRatio()
{
90
    if(_activeVehicle && _activeVehicle->dynamicCameras()) {
91 92 93 94 95 96 97 98 99 100 101 102
        QGCVideoStreamInfo* pInfo = _activeVehicle->dynamicCameras()->currentStreamInstance();
        if(pInfo) {
            return pInfo->aspectRatio();
        }
    }
    return _videoSettings->aspectRatio()->rawValue().toDouble();
}

//-----------------------------------------------------------------------------
bool
VideoManager::autoStreamConfigured()
{
103
    if(_activeVehicle && _activeVehicle->dynamicCameras()) {
104 105 106
        QGCVideoStreamInfo* pInfo = _activeVehicle->dynamicCameras()->currentStreamInstance();
        if(pInfo) {
            return !pInfo->uri().isEmpty();
107 108
        }
    }
109
    return false;
110 111
}

Gus Grubba's avatar
Gus Grubba committed
112 113 114 115 116 117 118 119 120 121 122 123 124 125 126 127 128 129
//-----------------------------------------------------------------------------
void
VideoManager::_updateUVC()
{
#ifndef QGC_DISABLE_UVC
    QString videoSource = _videoSettings->videoSource()->rawValue().toString();
    QList<QCameraInfo> cameras = QCameraInfo::availableCameras();
    for (const QCameraInfo &cameraInfo: cameras) {
        if(cameraInfo.description() == videoSource) {
            _videoSourceID = cameraInfo.deviceName();
            emit videoSourceIDChanged();
            qCDebug(VideoManagerLog) << "Found USB source:" << _videoSourceID << " Name:" << videoSource;
            break;
        }
    }
#endif
}

130 131 132
//-----------------------------------------------------------------------------
void
VideoManager::_videoSourceChanged()
133
{
Gus Grubba's avatar
Gus Grubba committed
134
    _updateUVC();
135 136
    emit hasVideoChanged();
    emit isGStreamerChanged();
137
    emit isAutoStreamChanged();
138 139 140
    _restartVideo();
}

141 142 143
//-----------------------------------------------------------------------------
void
VideoManager::_udpPortChanged()
144 145
{
    _restartVideo();
146 147
}

148 149
//-----------------------------------------------------------------------------
void
150
VideoManager::_rtspUrlChanged()
151
{
152
    _restartVideo();
153 154
}

155 156 157 158 159 160 161
//-----------------------------------------------------------------------------
void
VideoManager::_tcpUrlChanged()
{
    _restartVideo();
}

162 163 164 165
//-----------------------------------------------------------------------------
bool
VideoManager::hasVideo()
{
166 167 168
    if(autoStreamConfigured()) {
        return true;
    }
169
    QString videoSource = _videoSettings->videoSource()->rawValue().toString();
170
    return !videoSource.isEmpty() && videoSource != VideoSettings::videoSourceNoVideo && videoSource != VideoSettings::videoDisabled;
171 172 173 174 175 176 177
}

//-----------------------------------------------------------------------------
bool
VideoManager::isGStreamer()
{
#if defined(QGC_GST_STREAMING)
178
    QString videoSource = _videoSettings->videoSource()->rawValue().toString();
179 180 181
    return
        videoSource == VideoSettings::videoSourceUDP ||
        videoSource == VideoSettings::videoSourceRTSP ||
182
        videoSource == VideoSettings::videoSourceTCP ||
183 184
        videoSource == VideoSettings::videoSourceMPEGTS ||
        autoStreamConfigured();
185 186 187 188 189
#else
    return false;
#endif
}

190 191 192 193 194 195 196 197 198
//-----------------------------------------------------------------------------
#ifndef QGC_DISABLE_UVC
bool
VideoManager::uvcEnabled()
{
    return QCameraInfo::availableCameras().count() > 0;
}
#endif

199
//-----------------------------------------------------------------------------
200 201
void
VideoManager::_updateSettings()
202 203 204
{
    if(!_videoSettings || !_videoReceiver)
        return;
205
    //-- Auto discovery
206
    if(_activeVehicle && _activeVehicle->dynamicCameras()) {
207 208 209 210 211 212 213 214 215 216 217 218 219 220 221 222 223 224 225 226
        QGCVideoStreamInfo* pInfo = _activeVehicle->dynamicCameras()->currentStreamInstance();
        if(pInfo) {
            switch(pInfo->type()) {
                case VIDEO_STREAM_TYPE_RTSP:
                case VIDEO_STREAM_TYPE_TCP_MPEG:
                    _videoReceiver->setUri(pInfo->uri());
                    break;
                case VIDEO_STREAM_TYPE_RTPUDP:
                    _videoReceiver->setUri(QStringLiteral("udp://0.0.0.0:%1").arg(pInfo->uri()));
                    break;
                case VIDEO_STREAM_TYPE_MPEG_TS_H264:
                    _videoReceiver->setUri(QStringLiteral("mpegts://0.0.0.0:%1").arg(pInfo->uri()));
                    break;
                default:
                    _videoReceiver->setUri(pInfo->uri());
                    break;
            }
            return;
        }
    }
227 228
    QString source = _videoSettings->videoSource()->rawValue().toString();
    if (source == VideoSettings::videoSourceUDP)
229
        _videoReceiver->setUri(QStringLiteral("udp://0.0.0.0:%1").arg(_videoSettings->udpPort()->rawValue().toInt()));
230 231 232
    else if (source == VideoSettings::videoSourceMPEGTS)
        _videoReceiver->setUri(QStringLiteral("mpegts://0.0.0.0:%1").arg(_videoSettings->udpPort()->rawValue().toInt()));
    else if (source == VideoSettings::videoSourceRTSP)
233
        _videoReceiver->setUri(_videoSettings->rtspUrl()->rawValue().toString());
234
    else if (source == VideoSettings::videoSourceTCP)
235
        _videoReceiver->setUri(QStringLiteral("tcp://%1").arg(_videoSettings->tcpUrl()->rawValue().toString()));
236 237
}

238
//-----------------------------------------------------------------------------
239 240
void
VideoManager::_restartVideo()
241
{
242
#if defined(QGC_GST_STREAMING)
243
    qCDebug(VideoManagerLog) << "Restart video streaming";
244 245 246 247 248
    if(!_videoReceiver)
        return;
    _videoReceiver->stop();
    _updateSettings();
    _videoReceiver->start();
249
    emit aspectRatioChanged();
250 251
#endif
}
252 253 254 255 256 257

//----------------------------------------------------------------------------------------
void
VideoManager::_setActiveVehicle(Vehicle* vehicle)
{
    if(_activeVehicle) {
258 259 260 261 262 263 264
        if(_activeVehicle->dynamicCameras()) {
            QGCCameraControl* pCamera = _activeVehicle->dynamicCameras()->currentCameraInstance();
            if(pCamera) {
                pCamera->stopStream();
            }
            disconnect(_activeVehicle->dynamicCameras(), &QGCCameraManager::streamChanged, this, &VideoManager::_restartVideo);
        }
265 266 267
    }
    _activeVehicle = vehicle;
    if(_activeVehicle) {
268 269 270 271 272 273
        if(_activeVehicle->dynamicCameras()) {
            connect(_activeVehicle->dynamicCameras(), &QGCCameraManager::streamChanged, this, &VideoManager::_restartVideo);
            QGCCameraControl* pCamera = _activeVehicle->dynamicCameras()->currentCameraInstance();
            if(pCamera) {
                pCamera->resumeStream();
            }
274 275
        }
    }
276 277
    emit autoStreamConfiguredChanged();
    _restartVideo();
278 279 280 281
}

//----------------------------------------------------------------------------------------
void
282
VideoManager::_aspectRatioChanged()
283
{
284
    emit aspectRatioChanged();
285
}