VideoManager.cc 9.09 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)
Gus Grubba's avatar
Gus Grubba committed
37 38
    , _videoReceiver(nullptr)
    , _videoSettings(nullptr)
39
    , _fullScreen(false)
40
    , _activeVehicle(nullptr)
41 42 43 44 45 46
{
}

//-----------------------------------------------------------------------------
VideoManager::~VideoManager()
{
47 48 49
    if(_videoReceiver) {
        delete _videoReceiver;
    }
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 68 69
   connect(_videoSettings->aspectRatio(),   &Fact::rawValueChanged, this, &VideoManager::_aspectRatioChanged);
   MultiVehicleManager *manager = qgcApp()->toolbox()->multiVehicleManager();
   connect(manager, &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 81 82 83 84
    _updateSettings();
    if(isGStreamer()) {
        _videoReceiver->start();
    } else {
        _videoReceiver->stop();
85 86
    }

87
#endif
88 89
}

90 91 92 93 94 95 96 97 98 99 100 101 102
//-----------------------------------------------------------------------------
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
103 104 105 106 107 108 109 110 111 112 113 114 115 116 117 118 119 120
//-----------------------------------------------------------------------------
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
}

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

132 133 134
//-----------------------------------------------------------------------------
void
VideoManager::_udpPortChanged()
135 136
{
    _restartVideo();
137 138
}

139 140
//-----------------------------------------------------------------------------
void
141
VideoManager::_rtspUrlChanged()
142
{
143
    _restartVideo();
144 145
}

146 147 148 149 150 151 152
//-----------------------------------------------------------------------------
void
VideoManager::_tcpUrlChanged()
{
    _restartVideo();
}

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

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

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

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

198
//-----------------------------------------------------------------------------
199 200
void
VideoManager::_updateSettings()
201 202 203 204 205
{
    if(!_videoSettings || !_videoReceiver)
        return;
    if (_videoSettings->videoSource()->rawValue().toString() == VideoSettings::videoSourceUDP)
        _videoReceiver->setUri(QStringLiteral("udp://0.0.0.0:%1").arg(_videoSettings->udpPort()->rawValue().toInt()));
206
    else if (_videoSettings->videoSource()->rawValue().toString() == VideoSettings::videoSourceRTSP)
207
        _videoReceiver->setUri(_videoSettings->rtspUrl()->rawValue().toString());
208 209
    else if (_videoSettings->videoSource()->rawValue().toString() == VideoSettings::videoSourceTCP)
        _videoReceiver->setUri(QStringLiteral("tcp://%1").arg(_videoSettings->tcpUrl()->rawValue().toString()));
210 211
    else if (isAutoStream())
        _videoReceiver->setUri(QString(_streamInfo.uri));
212 213
}

214
//-----------------------------------------------------------------------------
215 216
void
VideoManager::_restartVideo()
217
{
218
#if defined(QGC_GST_STREAMING)
219 220 221 222 223 224 225
    if(!_videoReceiver)
        return;
    _videoReceiver->stop();
    _updateSettings();
    _videoReceiver->start();
#endif
}
226 227 228 229 230 231 232 233 234 235 236 237 238 239 240

//----------------------------------------------------------------------------------------
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);
241
        qCDebug(VideoManagerLog) << "Requesting video stream info";
242
        _activeVehicle->sendMavCommand(
243
            MAV_COMP_ID_ALL,                                      // Target component
244 245 246 247 248 249 250 251 252 253 254 255 256 257
            MAV_CMD_REQUEST_VIDEO_STREAM_INFORMATION,             // Command id
            false,                                                // ShowError
            1,                                                    // First camera only
            0);                                                   // Reserved (Set to 0)
    }
}

//----------------------------------------------------------------------------------------
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);
258
        qCDebug(VideoManagerLog) << "Received video stream info:" << _streamInfo.uri;
259 260 261 262 263 264 265 266 267 268 269
        _restartVideo();
        emit aspectRatioChanged();
    }
}

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