Newer
Older
/****************************************************************************
*
* (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.
*
****************************************************************************/
#ifndef VideoManager_H
#define VideoManager_H
#include <QObject>
#include <QTimer>
#include "QGCLoggingCategory.h"
#include "VideoReceiver.h"
#include "QGCToolbox.h"
Q_DECLARE_LOGGING_CATEGORY(VideoManagerLog)
class VideoManager : public QGCTool
{
Q_OBJECT
public:
VideoManager (QGCApplication* app, QGCToolbox* toolbox);
Q_PROPERTY(bool hasVideo READ hasVideo NOTIFY hasVideoChanged)
Q_PROPERTY(bool isGStreamer READ isGStreamer NOTIFY isGStreamerChanged)
Q_PROPERTY(bool isAutoStream READ isAutoStream NOTIFY isAutoStreamChanged)
Q_PROPERTY(bool isTaisync READ isTaisync WRITE setIsTaisync NOTIFY isTaisyncChanged)
Q_PROPERTY(QString videoSourceID READ videoSourceID NOTIFY videoSourceIDChanged)
Q_PROPERTY(bool uvcEnabled READ uvcEnabled CONSTANT)
Q_PROPERTY(bool fullScreen READ fullScreen WRITE setfullScreen NOTIFY fullScreenChanged)
Q_PROPERTY(VideoReceiver* videoReceiver READ videoReceiver CONSTANT)
Q_PROPERTY(double aspectRatio READ aspectRatio NOTIFY aspectRatioChanged)
bool isTaisync () { return _isTaisync; }
QString videoSourceID () { return _videoSourceID; }
QString autoURL () { return QString(_streamInfo.uri); }
double aspectRatio ();
VideoReceiver* videoReceiver () { return _videoReceiver; }
#if defined(QGC_DISABLE_UVC)
bool uvcEnabled () { return false; }
#else
bool uvcEnabled ();
#endif
void setfullScreen (bool f) { _fullScreen = f; emit fullScreenChanged(); }
void setIsTaisync (bool t) { _isTaisync = t; emit isTaisyncChanged(); }
// Override from QGCTool
void setToolbox (QGCToolbox *toolbox);
Q_INVOKABLE void startVideo() {_videoReceiver->start();}
Q_INVOKABLE void stopVideo() {_videoReceiver->stop(); }
void hasVideoChanged ();
void isGStreamerChanged ();
void videoSourceIDChanged ();
void isAutoStreamChanged ();
void aspectRatioChanged ();
void isTaisyncChanged ();
void _videoSourceChanged ();
void _udpPortChanged ();
void _rtspUrlChanged ();
void _tcpUrlChanged ();
void _aspectRatioChanged ();
void _setActiveVehicle (Vehicle* vehicle);
void _vehicleMessageReceived (const mavlink_message_t& message);
void _updateSettings ();
void _restartVideo ();
private:
bool _isTaisync = false;
VideoReceiver* _videoReceiver = nullptr;
VideoSettings* _videoSettings = nullptr;
bool _fullScreen = false;
Vehicle* _activeVehicle = nullptr;
mavlink_video_stream_information_t _streamInfo;