VideoManager.cc 13.1 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 "JoystickManager.h"
32 33 34 35

QGC_LOGGING_CATEGORY(VideoManagerLog, "VideoManagerLog")

//-----------------------------------------------------------------------------
36 37
VideoManager::VideoManager(QGCApplication* app, QGCToolbox* toolbox)
    : QGCTool(app, toolbox)
38
{
39
    _streamInfo = {};
40 41
    _lastZoomChange.start();
    _lastStreamChange.start();
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 70 71
   connect(_videoSettings->aspectRatio(),   &Fact::rawValueChanged, this, &VideoManager::_streamInfoChanged);
   MultiVehicleManager *pVehicleMgr = qgcApp()->toolbox()->multiVehicleManager();
   connect(pVehicleMgr, &MultiVehicleManager::activeVehicleChanged, this, &VideoManager::_setActiveVehicle);
   JoystickManager *pJoyMgr = qgcApp()->toolbox()->joystickManager();
   connect(pJoyMgr, &JoystickManager::activeJoystickChanged, this, &VideoManager::_activeJoystickChanged);
72

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

    emit isGStreamerChanged();
    qCDebug(VideoManagerLog) << "New Video Source:" << videoSource;
81
    _videoReceiver = toolbox->corePlugin()->createVideoReceiver(this);
82 83 84 85 86
    _updateSettings();
    if(isGStreamer()) {
        _videoReceiver->start();
    } else {
        _videoReceiver->stop();
87 88
    }

89
#endif
90 91
}

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

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

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

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

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

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

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

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

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

201
//-----------------------------------------------------------------------------
202 203
void
VideoManager::_updateSettings()
204 205 206
{
    if(!_videoSettings || !_videoReceiver)
        return;
207 208
    QString source = _videoSettings->videoSource()->rawValue().toString();
    if (source == VideoSettings::videoSourceUDP)
209
        _videoReceiver->setUri(QStringLiteral("udp://0.0.0.0:%1").arg(_videoSettings->udpPort()->rawValue().toInt()));
210 211 212
    else if (source == VideoSettings::videoSourceMPEGTS)
        _videoReceiver->setUri(QStringLiteral("mpegts://0.0.0.0:%1").arg(_videoSettings->udpPort()->rawValue().toInt()));
    else if (source == VideoSettings::videoSourceRTSP)
213
        _videoReceiver->setUri(_videoSettings->rtspUrl()->rawValue().toString());
214
    else if (source == VideoSettings::videoSourceTCP)
215
        _videoReceiver->setUri(QStringLiteral("tcp://%1").arg(_videoSettings->tcpUrl()->rawValue().toString()));
216 217 218 219 220 221 222 223 224 225 226 227 228 229 230 231 232 233
    //-- 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;
        }
    }
234 235
}

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

//----------------------------------------------------------------------------------------
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);
264
        qCDebug(VideoManagerLog) << "Requesting video stream info";
265
        _activeVehicle->sendMavCommand(
266
            MAV_COMP_ID_ALL,                                      // Target component
267 268 269
            MAV_CMD_REQUEST_VIDEO_STREAM_INFORMATION,             // Command id
            false,                                                // ShowError
            1,                                                    // First camera only
270
            1);                                                   // Request video stream information
271 272 273 274 275 276 277 278 279
    }
}

//----------------------------------------------------------------------------------------
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) {
280
        _videoStreamCompID = message.compid;
281
        mavlink_msg_video_stream_information_decode(&message, &_streamInfo);
282
        _hasAutoStream = true;
283
        qCDebug(VideoManagerLog) << "Received video stream info:" << _streamInfo.uri;
284
        _restartVideo();
285
        emit streamInfoChanged();
286 287 288 289 290
    }
}

//----------------------------------------------------------------------------------------
void
291
VideoManager::_activeJoystickChanged(Joystick* joystick)
292
{
293 294 295 296 297 298 299 300 301 302 303 304 305 306 307 308 309 310 311 312 313 314 315 316 317 318 319 320 321 322 323 324 325 326 327 328 329 330 331 332 333 334 335 336 337 338 339 340 341 342 343 344 345 346 347 348 349 350 351 352 353 354 355 356 357 358 359 360 361 362 363 364 365 366
    if(_activeJoystick) {
        disconnect(_activeJoystick, &Joystick::stepZoom,   this, &VideoManager::stepZoom);
        disconnect(_activeJoystick, &Joystick::stepStream, this, &VideoManager::stepStream);
    }
    _activeJoystick = joystick;
    if(_activeJoystick) {
        connect(_activeJoystick, &Joystick::stepZoom,   this, &VideoManager::stepZoom);
        connect(_activeJoystick, &Joystick::stepStream, this, &VideoManager::stepStream);
    }
}

//-----------------------------------------------------------------------------
void
VideoManager::stepZoom(int direction)
{
    if(_lastZoomChange.elapsed() > 250) {
        _lastZoomChange.start();
        qCDebug(VideoManagerLog) << "Step Stream Zoom" << direction;
        if(_activeVehicle && hasZoom()) {
            _activeVehicle->sendMavCommand(
                _videoStreamCompID,                     // Target component
                MAV_CMD_SET_CAMERA_ZOOM,                // Command id
                false,                                  // ShowError
                ZOOM_TYPE_STEP,                         // Zoom type
                direction);                             // Direction (-1 wide, 1 tele)
        }
    }
}

//-----------------------------------------------------------------------------
void
VideoManager::stepStream(int direction)
{
    if(_lastStreamChange.elapsed() > 250) {
        _lastStreamChange.start();
        int s = _currentStream + direction;
        if(s < 1) s = _streamInfo.count;
        if(s > _streamInfo.count) s = 1;
        setCurrentStream(s);
    }
}

//-----------------------------------------------------------------------------
void
VideoManager::setCurrentStream(int stream)
{
    qCDebug(VideoManagerLog) << "Set Stream" << stream;
    //-- TODO: Handle multiple streams
    if(_hasAutoStream && stream <= _streamInfo.count && stream > 0 && _activeVehicle) {
        if(_currentStream != stream) {
            //-- Stop current stream
            _activeVehicle->sendMavCommand(
                _videoStreamCompID,                     // Target component
                MAV_CMD_VIDEO_STOP_STREAMING,           // Command id
                false,                                  // ShowError
                _currentStream);                        // Stream ID
            //-- Start new stream
            _currentStream = stream;
            _activeVehicle->sendMavCommand(
                _videoStreamCompID,                     // Target component
                MAV_CMD_VIDEO_START_STREAMING,          // Command id
                false,                                  // ShowError
                _currentStream);                        // Stream ID
            _currentStream = stream;
            emit currentStreamChanged();
        }
    }
}

//----------------------------------------------------------------------------------------
void
VideoManager::_streamInfoChanged()
{
    emit streamInfoChanged();
367
}