VideoManager.cc 8.98 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 39 40 41 42
{
}

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

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

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

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

83
#endif
84 85
}

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

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

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

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

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

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

//-----------------------------------------------------------------------------
bool
VideoManager::isGStreamer()
{
#if defined(QGC_GST_STREAMING)
162
    QString videoSource = _videoSettings->videoSource()->rawValue().toString();
163 164 165 166 167 168 169 170 171 172 173 174 175 176 177 178 179
    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;
180 181 182 183 184
#else
    return false;
#endif
}

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

194
//-----------------------------------------------------------------------------
195 196
void
VideoManager::_updateSettings()
197 198 199 200 201
{
    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()));
202
    else if (_videoSettings->videoSource()->rawValue().toString() == VideoSettings::videoSourceRTSP)
203
        _videoReceiver->setUri(_videoSettings->rtspUrl()->rawValue().toString());
204 205
    else if (_videoSettings->videoSource()->rawValue().toString() == VideoSettings::videoSourceTCP)
        _videoReceiver->setUri(QStringLiteral("tcp://%1").arg(_videoSettings->tcpUrl()->rawValue().toString()));
206 207
    else if (isAutoStream())
        _videoReceiver->setUri(QString(_streamInfo.uri));
208 209
}

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

//----------------------------------------------------------------------------------------
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);
237
        qCDebug(VideoManagerLog) << "Requesting video stream info";
238
        _activeVehicle->sendMavCommand(
239
            MAV_COMP_ID_ALL,                                      // Target component
240 241 242 243 244 245 246 247 248 249 250 251 252 253
            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);
254
        qCDebug(VideoManagerLog) << "Received video stream info:" << _streamInfo.uri;
255 256 257 258 259 260 261 262 263 264 265
        _restartVideo();
        emit aspectRatioChanged();
    }
}

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