VideoManager.cc 14 KB
Newer Older
1 2
/****************************************************************************
 *
3
 *   (c) 2009-2019 QGROUNDCONTROL PROJECT <http://www.qgroundcontrol.org>
4 5 6 7 8 9 10 11 12 13
 *
 * 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
    if(_thermalVideoReceiver) {
        delete _thermalVideoReceiver;
    }
50 51 52 53 54 55 56 57
}

//-----------------------------------------------------------------------------
void
VideoManager::setToolbox(QGCToolbox *toolbox)
{
   QGCTool::setToolbox(toolbox);
   QQmlEngine::setObjectOwnership(this, QQmlEngine::CppOwnership);
58 59 60
   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");
61 62
   _videoSettings = toolbox->settingsManager()->videoSettings();
   QString videoSource = _videoSettings->videoSource()->rawValue().toString();
63 64 65
   connect(_videoSettings->videoSource(),   &Fact::rawValueChanged, this, &VideoManager::_videoSourceChanged);
   connect(_videoSettings->udpPort(),       &Fact::rawValueChanged, this, &VideoManager::_udpPortChanged);
   connect(_videoSettings->rtspUrl(),       &Fact::rawValueChanged, this, &VideoManager::_rtspUrlChanged);
66
   connect(_videoSettings->tcpUrl(),        &Fact::rawValueChanged, this, &VideoManager::_tcpUrlChanged);
67
   connect(_videoSettings->aspectRatio(),   &Fact::rawValueChanged, this, &VideoManager::_aspectRatioChanged);
68 69
   MultiVehicleManager *pVehicleMgr = qgcApp()->toolbox()->multiVehicleManager();
   connect(pVehicleMgr, &MultiVehicleManager::activeVehicleChanged, this, &VideoManager::_setActiveVehicle);
70

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

    emit isGStreamerChanged();
    qCDebug(VideoManagerLog) << "New Video Source:" << videoSource;
79
    _videoReceiver = toolbox->corePlugin()->createVideoReceiver(this);
80
    _thermalVideoReceiver = toolbox->corePlugin()->createVideoReceiver(this);
81 82
    _updateSettings();
    if(isGStreamer()) {
83
        startVideo();
84
        _subtitleWriter.setVideoReceiver(_videoReceiver);
85
    } else {
86
        stopVideo();
87 88
    }

89
#endif
90 91
}

92 93 94 95 96 97 98 99 100 101 102 103 104 105 106 107
//-----------------------------------------------------------------------------
void
VideoManager::startVideo()
{
    if(_videoReceiver) _videoReceiver->start();
    if(_thermalVideoReceiver) _thermalVideoReceiver->start();
}

//-----------------------------------------------------------------------------
void
VideoManager::stopVideo()
{
    if(_videoReceiver) _videoReceiver->stop();
    if(_thermalVideoReceiver) _thermalVideoReceiver->stop();
}

108 109 110
//-----------------------------------------------------------------------------
double VideoManager::aspectRatio()
{
111
    if(_activeVehicle && _activeVehicle->dynamicCameras()) {
112
        QGCVideoStreamInfo* pInfo = _activeVehicle->dynamicCameras()->currentStreamInstance();
113 114 115 116 117 118 119 120 121 122 123 124 125 126 127 128 129 130 131 132 133 134 135 136 137 138 139 140 141 142 143 144 145 146 147 148 149 150
        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();
151 152 153 154 155 156 157
        if(pInfo) {
            return pInfo->aspectRatio();
        }
    }
    return _videoSettings->aspectRatio()->rawValue().toDouble();
}

158 159 160 161 162 163 164 165 166 167 168 169 170
//-----------------------------------------------------------------------------
bool
VideoManager::hasThermal()
{
    if(_activeVehicle && _activeVehicle->dynamicCameras()) {
        QGCVideoStreamInfo* pInfo = _activeVehicle->dynamicCameras()->thermalStreamInstance();
        if(pInfo) {
            return true;
        }
    }
    return false;
}

171 172 173 174
//-----------------------------------------------------------------------------
bool
VideoManager::autoStreamConfigured()
{
Gus Grubba's avatar
Gus Grubba committed
175
#if defined(QGC_GST_STREAMING)
176
    if(_activeVehicle && _activeVehicle->dynamicCameras()) {
177 178 179
        QGCVideoStreamInfo* pInfo = _activeVehicle->dynamicCameras()->currentStreamInstance();
        if(pInfo) {
            return !pInfo->uri().isEmpty();
180 181
        }
    }
Gus Grubba's avatar
Gus Grubba committed
182
#endif
183
    return false;
184 185
}

Gus Grubba's avatar
Gus Grubba committed
186 187 188 189 190 191 192 193 194 195 196 197 198 199 200 201 202 203
//-----------------------------------------------------------------------------
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
}

204 205 206
//-----------------------------------------------------------------------------
void
VideoManager::_videoSourceChanged()
207
{
Gus Grubba's avatar
Gus Grubba committed
208
    _updateUVC();
209 210
    emit hasVideoChanged();
    emit isGStreamerChanged();
211
    emit isAutoStreamChanged();
212
    restartVideo();
213 214
}

215 216 217
//-----------------------------------------------------------------------------
void
VideoManager::_udpPortChanged()
218
{
219
    restartVideo();
220 221
}

222 223
//-----------------------------------------------------------------------------
void
224
VideoManager::_rtspUrlChanged()
225
{
226
    restartVideo();
227 228
}

229 230 231 232
//-----------------------------------------------------------------------------
void
VideoManager::_tcpUrlChanged()
{
233
    restartVideo();
234 235
}

236 237 238 239
//-----------------------------------------------------------------------------
bool
VideoManager::hasVideo()
{
240 241 242
    if(autoStreamConfigured()) {
        return true;
    }
243
    QString videoSource = _videoSettings->videoSource()->rawValue().toString();
244
    return !videoSource.isEmpty() && videoSource != VideoSettings::videoSourceNoVideo && videoSource != VideoSettings::videoDisabled;
245 246 247 248 249 250 251
}

//-----------------------------------------------------------------------------
bool
VideoManager::isGStreamer()
{
#if defined(QGC_GST_STREAMING)
252
    QString videoSource = _videoSettings->videoSource()->rawValue().toString();
253
    return
Gus Grubba's avatar
Gus Grubba committed
254 255
        videoSource == VideoSettings::videoSourceUDPH264 ||
        videoSource == VideoSettings::videoSourceUDPH265 ||
256
        videoSource == VideoSettings::videoSourceRTSP ||
257
        videoSource == VideoSettings::videoSourceTCP ||
258 259
        videoSource == VideoSettings::videoSourceMPEGTS ||
        autoStreamConfigured();
260 261 262 263 264
#else
    return false;
#endif
}

265 266 267 268 269 270 271 272 273
//-----------------------------------------------------------------------------
#ifndef QGC_DISABLE_UVC
bool
VideoManager::uvcEnabled()
{
    return QCameraInfo::availableCameras().count() > 0;
}
#endif

274
//-----------------------------------------------------------------------------
275 276
void
VideoManager::_updateSettings()
277 278 279
{
    if(!_videoSettings || !_videoReceiver)
        return;
280
    //-- Auto discovery
281
    if(_activeVehicle && _activeVehicle->dynamicCameras()) {
282 283 284 285 286 287 288 289
        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();
290
        if(pInfo) {
291
            qCDebug(VideoManagerLog) << "Configure primary stream: " << pInfo->uri();
292 293
            switch(pInfo->type()) {
                case VIDEO_STREAM_TYPE_RTSP:
294 295 296
                    _videoReceiver->setUri(pInfo->uri());
                    _toolbox->settingsManager()->videoSettings()->videoSource()->setRawValue(VideoSettings::videoSourceRTSP);
                    break;
297 298
                case VIDEO_STREAM_TYPE_TCP_MPEG:
                    _videoReceiver->setUri(pInfo->uri());
299
                    _toolbox->settingsManager()->videoSettings()->videoSource()->setRawValue(VideoSettings::videoSourceTCP);
300 301 302
                    break;
                case VIDEO_STREAM_TYPE_RTPUDP:
                    _videoReceiver->setUri(QStringLiteral("udp://0.0.0.0:%1").arg(pInfo->uri()));
303
                    _toolbox->settingsManager()->videoSettings()->videoSource()->setRawValue(VideoSettings::videoSourceUDPH264);
304 305 306
                    break;
                case VIDEO_STREAM_TYPE_MPEG_TS_H264:
                    _videoReceiver->setUri(QStringLiteral("mpegts://0.0.0.0:%1").arg(pInfo->uri()));
307
                    _toolbox->settingsManager()->videoSettings()->videoSource()->setRawValue(VideoSettings::videoSourceMPEGTS);
308 309 310 311 312
                    break;
                default:
                    _videoReceiver->setUri(pInfo->uri());
                    break;
            }
313 314 315 316 317 318 319 320 321 322 323 324 325 326 327 328 329 330 331 332
            //-- 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;
                }
            }
333 334 335
            return;
        }
    }
336
    QString source = _videoSettings->videoSource()->rawValue().toString();
Gus Grubba's avatar
Gus Grubba committed
337
    if (source == VideoSettings::videoSourceUDPH264)
338
        _videoReceiver->setUri(QStringLiteral("udp://0.0.0.0:%1").arg(_videoSettings->udpPort()->rawValue().toInt()));
Gus Grubba's avatar
Gus Grubba committed
339 340
    else if (source == VideoSettings::videoSourceUDPH265)
        _videoReceiver->setUri(QStringLiteral("udp265://0.0.0.0:%1").arg(_videoSettings->udpPort()->rawValue().toInt()));
341 342 343
    else if (source == VideoSettings::videoSourceMPEGTS)
        _videoReceiver->setUri(QStringLiteral("mpegts://0.0.0.0:%1").arg(_videoSettings->udpPort()->rawValue().toInt()));
    else if (source == VideoSettings::videoSourceRTSP)
344
        _videoReceiver->setUri(_videoSettings->rtspUrl()->rawValue().toString());
345
    else if (source == VideoSettings::videoSourceTCP)
346
        _videoReceiver->setUri(QStringLiteral("tcp://%1").arg(_videoSettings->tcpUrl()->rawValue().toString()));
347 348
}

349
//-----------------------------------------------------------------------------
350
void
351
VideoManager::restartVideo()
352
{
353
#if defined(QGC_GST_STREAMING)
354
    qCDebug(VideoManagerLog) << "Restart video streaming";
355
    stopVideo();
356
    _updateSettings();
357
    startVideo();
358
    emit aspectRatioChanged();
359 360
#endif
}
361 362 363 364 365 366

//----------------------------------------------------------------------------------------
void
VideoManager::_setActiveVehicle(Vehicle* vehicle)
{
    if(_activeVehicle) {
367 368 369 370 371
        if(_activeVehicle->dynamicCameras()) {
            QGCCameraControl* pCamera = _activeVehicle->dynamicCameras()->currentCameraInstance();
            if(pCamera) {
                pCamera->stopStream();
            }
372
            disconnect(_activeVehicle->dynamicCameras(), &QGCCameraManager::streamChanged, this, &VideoManager::restartVideo);
373
        }
374 375 376
    }
    _activeVehicle = vehicle;
    if(_activeVehicle) {
377
        if(_activeVehicle->dynamicCameras()) {
378
            connect(_activeVehicle->dynamicCameras(), &QGCCameraManager::streamChanged, this, &VideoManager::restartVideo);
379 380 381 382
            QGCCameraControl* pCamera = _activeVehicle->dynamicCameras()->currentCameraInstance();
            if(pCamera) {
                pCamera->resumeStream();
            }
383 384
        }
    }
385
    emit autoStreamConfiguredChanged();
386
    restartVideo();
387 388 389 390
}

//----------------------------------------------------------------------------------------
void
391
VideoManager::_aspectRatioChanged()
392
{
393
    emit aspectRatioChanged();
394
}