VideoManager.cc 12.8 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
    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
    } else {
85
        stopVideo();
86 87
    }

88
#endif
89 90
}

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

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

107 108 109
//-----------------------------------------------------------------------------
double VideoManager::aspectRatio()
{
110
    if(_activeVehicle && _activeVehicle->dynamicCameras()) {
111
        QGCVideoStreamInfo* pInfo = _activeVehicle->dynamicCameras()->currentStreamInstance();
112 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
        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();
150 151 152 153 154 155 156
        if(pInfo) {
            return pInfo->aspectRatio();
        }
    }
    return _videoSettings->aspectRatio()->rawValue().toDouble();
}

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

170 171 172 173
//-----------------------------------------------------------------------------
bool
VideoManager::autoStreamConfigured()
{
174
    if(_activeVehicle && _activeVehicle->dynamicCameras()) {
175 176 177
        QGCVideoStreamInfo* pInfo = _activeVehicle->dynamicCameras()->currentStreamInstance();
        if(pInfo) {
            return !pInfo->uri().isEmpty();
178 179
        }
    }
180
    return false;
181 182
}

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

201 202 203
//-----------------------------------------------------------------------------
void
VideoManager::_videoSourceChanged()
204
{
Gus Grubba's avatar
Gus Grubba committed
205
    _updateUVC();
206 207
    emit hasVideoChanged();
    emit isGStreamerChanged();
208
    emit isAutoStreamChanged();
209 210 211
    _restartVideo();
}

212 213 214
//-----------------------------------------------------------------------------
void
VideoManager::_udpPortChanged()
215 216
{
    _restartVideo();
217 218
}

219 220
//-----------------------------------------------------------------------------
void
221
VideoManager::_rtspUrlChanged()
222
{
223
    _restartVideo();
224 225
}

226 227 228 229 230 231 232
//-----------------------------------------------------------------------------
void
VideoManager::_tcpUrlChanged()
{
    _restartVideo();
}

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

//-----------------------------------------------------------------------------
bool
VideoManager::isGStreamer()
{
#if defined(QGC_GST_STREAMING)
249
    QString videoSource = _videoSettings->videoSource()->rawValue().toString();
250 251 252
    return
        videoSource == VideoSettings::videoSourceUDP ||
        videoSource == VideoSettings::videoSourceRTSP ||
253
        videoSource == VideoSettings::videoSourceTCP ||
254 255
        videoSource == VideoSettings::videoSourceMPEGTS ||
        autoStreamConfigured();
256 257 258 259 260
#else
    return false;
#endif
}

261 262 263 264 265 266 267 268 269
//-----------------------------------------------------------------------------
#ifndef QGC_DISABLE_UVC
bool
VideoManager::uvcEnabled()
{
    return QCameraInfo::availableCameras().count() > 0;
}
#endif

270
//-----------------------------------------------------------------------------
271 272
void
VideoManager::_updateSettings()
273 274 275
{
    if(!_videoSettings || !_videoReceiver)
        return;
276
    //-- Auto discovery
277
    if(_activeVehicle && _activeVehicle->dynamicCameras()) {
278
        QGCVideoStreamInfo* pInfo  = _activeVehicle->dynamicCameras()->currentStreamInstance();
279
        if(pInfo) {
280
            qCDebug(VideoManagerLog) << "Configure primary stream: " << pInfo->uri();
281 282 283 284 285 286 287 288 289 290 291 292 293 294 295
            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;
            }
296 297 298 299 300 301 302 303 304 305 306 307 308 309 310 311 312 313 314 315
            //-- 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;
                }
            }
316 317 318
            return;
        }
    }
319 320
    QString source = _videoSettings->videoSource()->rawValue().toString();
    if (source == VideoSettings::videoSourceUDP)
321
        _videoReceiver->setUri(QStringLiteral("udp://0.0.0.0:%1").arg(_videoSettings->udpPort()->rawValue().toInt()));
322 323 324
    else if (source == VideoSettings::videoSourceMPEGTS)
        _videoReceiver->setUri(QStringLiteral("mpegts://0.0.0.0:%1").arg(_videoSettings->udpPort()->rawValue().toInt()));
    else if (source == VideoSettings::videoSourceRTSP)
325
        _videoReceiver->setUri(_videoSettings->rtspUrl()->rawValue().toString());
326
    else if (source == VideoSettings::videoSourceTCP)
327
        _videoReceiver->setUri(QStringLiteral("tcp://%1").arg(_videoSettings->tcpUrl()->rawValue().toString()));
328 329
}

330
//-----------------------------------------------------------------------------
331 332
void
VideoManager::_restartVideo()
333
{
334
#if defined(QGC_GST_STREAMING)
335
    qCDebug(VideoManagerLog) << "Restart video streaming";
336
    stopVideo();
337
    _updateSettings();
338
    startVideo();
339
    emit aspectRatioChanged();
340 341
#endif
}
342 343 344 345 346 347

//----------------------------------------------------------------------------------------
void
VideoManager::_setActiveVehicle(Vehicle* vehicle)
{
    if(_activeVehicle) {
348 349 350 351 352 353 354
        if(_activeVehicle->dynamicCameras()) {
            QGCCameraControl* pCamera = _activeVehicle->dynamicCameras()->currentCameraInstance();
            if(pCamera) {
                pCamera->stopStream();
            }
            disconnect(_activeVehicle->dynamicCameras(), &QGCCameraManager::streamChanged, this, &VideoManager::_restartVideo);
        }
355 356 357
    }
    _activeVehicle = vehicle;
    if(_activeVehicle) {
358 359 360 361 362 363
        if(_activeVehicle->dynamicCameras()) {
            connect(_activeVehicle->dynamicCameras(), &QGCCameraManager::streamChanged, this, &VideoManager::_restartVideo);
            QGCCameraControl* pCamera = _activeVehicle->dynamicCameras()->currentCameraInstance();
            if(pCamera) {
                pCamera->resumeStream();
            }
364 365
        }
    }
366 367
    emit autoStreamConfiguredChanged();
    _restartVideo();
368 369 370 371
}

//----------------------------------------------------------------------------------------
void
372
VideoManager::_aspectRatioChanged()
373
{
374
    emit aspectRatioChanged();
375
}