VideoManager.cc 9.87 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 32 33 34

QGC_LOGGING_CATEGORY(VideoManagerLog, "VideoManagerLog")

//-----------------------------------------------------------------------------
35 36
VideoManager::VideoManager(QGCApplication* app, QGCToolbox* toolbox)
    : QGCTool(app, toolbox)
37
{
38
    _streamInfo = {};
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 65 66
   connect(_videoSettings->aspectRatio(),   &Fact::rawValueChanged, this, &VideoManager::_aspectRatioChanged);
   MultiVehicleManager *manager = qgcApp()->toolbox()->multiVehicleManager();
   connect(manager, &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 90 91 92 93 94 95 96 97 98 99
//-----------------------------------------------------------------------------
double VideoManager::aspectRatio()
{
    if(isAutoStream()) {
        if(_streamInfo.resolution_h && _streamInfo.resolution_v) {
            return static_cast<double>(_streamInfo.resolution_h) / static_cast<double>(_streamInfo.resolution_v);
        }
        return 1.0;
    } else {
        return _videoSettings->aspectRatio()->rawValue().toDouble();
    }
}

Gus Grubba's avatar
Gus Grubba committed
100 101 102 103 104 105 106 107 108 109 110 111 112 113 114 115 116 117
//-----------------------------------------------------------------------------
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
}

118 119 120
//-----------------------------------------------------------------------------
void
VideoManager::_videoSourceChanged()
121
{
Gus Grubba's avatar
Gus Grubba committed
122
    _updateUVC();
123 124
    emit hasVideoChanged();
    emit isGStreamerChanged();
125
    emit isAutoStreamChanged();
126 127 128
    _restartVideo();
}

129 130 131
//-----------------------------------------------------------------------------
void
VideoManager::_udpPortChanged()
132 133
{
    _restartVideo();
134 135
}

136 137
//-----------------------------------------------------------------------------
void
138
VideoManager::_rtspUrlChanged()
139
{
140
    _restartVideo();
141 142
}

143 144 145 146 147 148 149
//-----------------------------------------------------------------------------
void
VideoManager::_tcpUrlChanged()
{
    _restartVideo();
}

150 151 152 153
//-----------------------------------------------------------------------------
bool
VideoManager::hasVideo()
{
154
    QString videoSource = _videoSettings->videoSource()->rawValue().toString();
155
    return !videoSource.isEmpty() && videoSource != VideoSettings::videoSourceNoVideo && videoSource != VideoSettings::videoDisabled;
156 157 158 159 160 161 162
}

//-----------------------------------------------------------------------------
bool
VideoManager::isGStreamer()
{
#if defined(QGC_GST_STREAMING)
163
    QString videoSource = _videoSettings->videoSource()->rawValue().toString();
164 165 166 167
    return
        videoSource == VideoSettings::videoSourceUDP ||
        videoSource == VideoSettings::videoSourceRTSP ||
        videoSource == VideoSettings::videoSourceAuto ||
168 169
        videoSource == VideoSettings::videoSourceTCP ||
        videoSource == VideoSettings::videoSourceMPEGTS;
170 171 172 173 174 175 176 177 178 179 180 181
#else
    return false;
#endif
}

//-----------------------------------------------------------------------------
bool
VideoManager::isAutoStream()
{
#if defined(QGC_GST_STREAMING)
    QString videoSource = _videoSettings->videoSource()->rawValue().toString();
    return  videoSource == VideoSettings::videoSourceAuto;
182 183 184 185 186
#else
    return false;
#endif
}

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

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

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

//----------------------------------------------------------------------------------------
void
VideoManager::_setActiveVehicle(Vehicle* vehicle)
{
    if(_activeVehicle) {
        disconnect(_activeVehicle, &Vehicle::mavlinkMessageReceived, this, &VideoManager::_vehicleMessageReceived);
    }
    _activeVehicle = vehicle;
    if(_activeVehicle) {
        if(isAutoStream()) {
            _videoReceiver->stop();
        }
        //-- Video Stream Discovery
        connect(_activeVehicle, &Vehicle::mavlinkMessageReceived, this, &VideoManager::_vehicleMessageReceived);
259
        qCDebug(VideoManagerLog) << "Requesting video stream info";
260
        _activeVehicle->sendMavCommand(
261
            MAV_COMP_ID_ALL,                                      // Target component
262 263 264
            MAV_CMD_REQUEST_VIDEO_STREAM_INFORMATION,             // Command id
            false,                                                // ShowError
            1,                                                    // First camera only
265
            1);                                                   // Request video stream information
266 267 268 269 270 271 272 273 274 275
    }
}

//----------------------------------------------------------------------------------------
void
VideoManager::_vehicleMessageReceived(const mavlink_message_t& message)
{
    //-- For now we only handle one stream. There is no UI to pick different streams.
    if(message.msgid == MAVLINK_MSG_ID_VIDEO_STREAM_INFORMATION) {
        mavlink_msg_video_stream_information_decode(&message, &_streamInfo);
276
        qCDebug(VideoManagerLog) << "Received video stream info:" << _streamInfo.uri;
277 278 279 280 281 282 283 284 285 286 287
        _restartVideo();
        emit aspectRatioChanged();
    }
}

//----------------------------------------------------------------------------------------
void
VideoManager::_aspectRatioChanged()
{
    emit aspectRatioChanged();
}