Unverified Commit 151ce31f authored by Gus Grubba's avatar Gus Grubba Committed by GitHub

Merge pull request #7083 from mavlink/autoVideoStream

Auto video stream
parents 351cff6d b8ad6544
...@@ -58,6 +58,27 @@ static const char* kPhotoMode = "PhotoMode"; ...@@ -58,6 +58,27 @@ static const char* kPhotoMode = "PhotoMode";
static const char* kPhotoLapse = "PhotoLapse"; static const char* kPhotoLapse = "PhotoLapse";
static const char* kPhotoLapseCount = "PhotoLapseCount"; static const char* kPhotoLapseCount = "PhotoLapseCount";
//-----------------------------------------------------------------------------
QGCCameraOptionExclusion::QGCCameraOptionExclusion(QObject* parent, QString param_, QString value_, QStringList exclusions_)
: QObject(parent)
, param(param_)
, value(value_)
, exclusions(exclusions_)
{
}
//-----------------------------------------------------------------------------
QGCCameraOptionRange::QGCCameraOptionRange(QObject* parent, QString param_, QString value_, QString targetParam_, QString condition_, QStringList optNames_, QStringList optValues_)
: QObject(parent)
, param(param_)
, value(value_)
, targetParam(targetParam_)
, condition(condition_)
, optNames(optNames_)
, optValues(optValues_)
{
}
//----------------------------------------------------------------------------- //-----------------------------------------------------------------------------
static bool static bool
read_attribute(QDomNode& node, const char* tagName, bool& target) read_attribute(QDomNode& node, const char* tagName, bool& target)
...@@ -127,7 +148,7 @@ QGCCameraControl::QGCCameraControl(const mavlink_camera_information_t *info, Veh ...@@ -127,7 +148,7 @@ QGCCameraControl::QGCCameraControl(const mavlink_camera_information_t *info, Veh
, _cached(false) , _cached(false)
, _storageFree(0) , _storageFree(0)
, _storageTotal(0) , _storageTotal(0)
, _netManager(NULL) , _netManager(nullptr)
, _cameraMode(CAM_MODE_UNDEFINED) , _cameraMode(CAM_MODE_UNDEFINED)
, _photoMode(PHOTO_CAPTURE_SINGLE) , _photoMode(PHOTO_CAPTURE_SINGLE)
, _photoLapse(1.0) , _photoLapse(1.0)
...@@ -140,9 +161,9 @@ QGCCameraControl::QGCCameraControl(const mavlink_camera_information_t *info, Veh ...@@ -140,9 +161,9 @@ QGCCameraControl::QGCCameraControl(const mavlink_camera_information_t *info, Veh
QQmlEngine::setObjectOwnership(this, QQmlEngine::CppOwnership); QQmlEngine::setObjectOwnership(this, QQmlEngine::CppOwnership);
memcpy(&_info, info, sizeof(mavlink_camera_information_t)); memcpy(&_info, info, sizeof(mavlink_camera_information_t));
connect(this, &QGCCameraControl::dataReady, this, &QGCCameraControl::_dataReady); connect(this, &QGCCameraControl::dataReady, this, &QGCCameraControl::_dataReady);
_vendor = QString((const char*)(void*)&info->vendor_name[0]); _vendor = QString(reinterpret_cast<const char*>(info->vendor_name));
_modelName = QString((const char*)(void*)&info->model_name[0]); _modelName = QString(reinterpret_cast<const char*>(info->model_name));
int ver = (int)_info.cam_definition_version; int ver = static_cast<int>(_info.cam_definition_version);
_cacheFile.sprintf("%s/%s_%s_%03d.xml", _cacheFile.sprintf("%s/%s_%s_%03d.xml",
qgcApp()->toolbox()->settingsManager()->appSettings()->parameterSavePath().toStdString().c_str(), qgcApp()->toolbox()->settingsManager()->appSettings()->parameterSavePath().toStdString().c_str(),
_vendor.toStdString().c_str(), _vendor.toStdString().c_str(),
...@@ -155,7 +176,7 @@ QGCCameraControl::QGCCameraControl(const mavlink_camera_information_t *info, Veh ...@@ -155,7 +176,7 @@ QGCCameraControl::QGCCameraControl(const mavlink_camera_information_t *info, Veh
_initWhenReady(); _initWhenReady();
} }
QSettings settings; QSettings settings;
_photoMode = (PhotoMode)settings.value(kPhotoMode, (int)PHOTO_CAPTURE_SINGLE).toInt(); _photoMode = static_cast<PhotoMode>(settings.value(kPhotoMode, static_cast<int>(PHOTO_CAPTURE_SINGLE)).toInt());
_photoLapse = settings.value(kPhotoLapse, 1.0).toDouble(); _photoLapse = settings.value(kPhotoLapse, 1.0).toDouble();
_photoLapseCount = settings.value(kPhotoLapseCount, 0).toInt(); _photoLapseCount = settings.value(kPhotoLapseCount, 0).toInt();
} }
...@@ -189,7 +210,7 @@ QGCCameraControl::_initWhenReady() ...@@ -189,7 +210,7 @@ QGCCameraControl::_initWhenReady()
emit infoChanged(); emit infoChanged();
if(_netManager) { if(_netManager) {
delete _netManager; delete _netManager;
_netManager = NULL; _netManager = nullptr;
} }
} }
...@@ -223,7 +244,7 @@ QGCCameraControl::photoStatus() ...@@ -223,7 +244,7 @@ QGCCameraControl::photoStatus()
QString QString
QGCCameraControl::storageFreeStr() QGCCameraControl::storageFreeStr()
{ {
return QGCMapEngine::bigSizeToString((quint64)_storageFree * 1024 * 1024); return QGCMapEngine::bigSizeToString(static_cast<quint64>(_storageFree * 1024 * 1024));
} }
//----------------------------------------------------------------------------- //-----------------------------------------------------------------------------
...@@ -247,7 +268,7 @@ QGCCameraControl::setPhotoMode(PhotoMode mode) ...@@ -247,7 +268,7 @@ QGCCameraControl::setPhotoMode(PhotoMode mode)
{ {
_photoMode = mode; _photoMode = mode;
QSettings settings; QSettings settings;
settings.setValue(kPhotoMode, (int)mode); settings.setValue(kPhotoMode, static_cast<int>(mode));
emit photoModeChanged(); emit photoModeChanged();
} }
...@@ -316,7 +337,7 @@ QGCCameraControl::takePhoto() ...@@ -316,7 +337,7 @@ QGCCameraControl::takePhoto()
MAV_CMD_IMAGE_START_CAPTURE, // Command id MAV_CMD_IMAGE_START_CAPTURE, // Command id
false, // ShowError false, // ShowError
0, // Reserved (Set to 0) 0, // Reserved (Set to 0)
_photoMode == PHOTO_CAPTURE_SINGLE ? 0 : _photoLapse, // Duration between two consecutive pictures (in seconds--ignored if single image) static_cast<float>(_photoMode == PHOTO_CAPTURE_SINGLE ? 0 : _photoLapse), // Duration between two consecutive pictures (in seconds--ignored if single image)
_photoMode == PHOTO_CAPTURE_SINGLE ? 1 : _photoLapseCount); // Number of images to capture total - 0 for unlimited capture _photoMode == PHOTO_CAPTURE_SINGLE ? 1 : _photoLapseCount); // Number of images to capture total - 0 for unlimited capture
_setPhotoStatus(PHOTO_CAPTURE_IN_PROGRESS); _setPhotoStatus(PHOTO_CAPTURE_IN_PROGRESS);
_captureInfoRetries = 0; _captureInfoRetries = 0;
...@@ -944,12 +965,12 @@ QGCCameraControl::_requestAllParameters() ...@@ -944,12 +965,12 @@ QGCCameraControl::_requestAllParameters()
MAVLinkProtocol* mavlink = qgcApp()->toolbox()->mavlinkProtocol(); MAVLinkProtocol* mavlink = qgcApp()->toolbox()->mavlinkProtocol();
mavlink_message_t msg; mavlink_message_t msg;
mavlink_msg_param_ext_request_list_pack_chan( mavlink_msg_param_ext_request_list_pack_chan(
mavlink->getSystemId(), static_cast<uint8_t>(mavlink->getSystemId()),
mavlink->getComponentId(), static_cast<uint8_t>(mavlink->getComponentId()),
_vehicle->priorityLink()->mavlinkChannel(), _vehicle->priorityLink()->mavlinkChannel(),
&msg, &msg,
_vehicle->id(), static_cast<uint8_t>(_vehicle->id()),
compID()); static_cast<uint8_t>(compID()));
_vehicle->sendMessageOnLink(_vehicle->priorityLink(), msg); _vehicle->sendMessageOnLink(_vehicle->priorityLink(), msg);
qCDebug(CameraControlLogVerbose) << "Request all parameters"; qCDebug(CameraControlLogVerbose) << "Request all parameters";
} }
...@@ -1223,7 +1244,7 @@ void ...@@ -1223,7 +1244,7 @@ void
QGCCameraControl::handleSettings(const mavlink_camera_settings_t& settings) QGCCameraControl::handleSettings(const mavlink_camera_settings_t& settings)
{ {
qCDebug(CameraControlLog) << "handleSettings() Mode:" << settings.mode_id; qCDebug(CameraControlLog) << "handleSettings() Mode:" << settings.mode_id;
_setCameraMode((CameraMode)settings.mode_id); _setCameraMode(static_cast<CameraMode>(settings.mode_id));
} }
//----------------------------------------------------------------------------- //-----------------------------------------------------------------------------
...@@ -1231,13 +1252,15 @@ void ...@@ -1231,13 +1252,15 @@ void
QGCCameraControl::handleStorageInfo(const mavlink_storage_information_t& st) QGCCameraControl::handleStorageInfo(const mavlink_storage_information_t& st)
{ {
qCDebug(CameraControlLog) << "_handleStorageInfo:" << st.available_capacity << st.status << st.storage_count << st.storage_id << st.total_capacity << st.used_capacity; qCDebug(CameraControlLog) << "_handleStorageInfo:" << st.available_capacity << st.status << st.storage_count << st.storage_id << st.total_capacity << st.used_capacity;
if(_storageTotal != st.total_capacity) { uint32_t t = static_cast<uint32_t>(st.total_capacity);
_storageTotal = st.total_capacity; if(_storageTotal != t) {
_storageTotal = t;
} }
//-- Always emit this //-- Always emit this
emit storageTotalChanged(); emit storageTotalChanged();
if(_storageFree != st.available_capacity) { uint32_t a = static_cast<uint32_t>(st.available_capacity);
_storageFree = st.available_capacity; if(_storageFree != a) {
_storageFree = a;
emit storageFreeChanged(); emit storageFreeChanged();
} }
} }
...@@ -1249,15 +1272,16 @@ QGCCameraControl::handleCaptureStatus(const mavlink_camera_capture_status_t& cap ...@@ -1249,15 +1272,16 @@ QGCCameraControl::handleCaptureStatus(const mavlink_camera_capture_status_t& cap
//-- This is a response to MAV_CMD_REQUEST_CAMERA_CAPTURE_STATUS //-- This is a response to MAV_CMD_REQUEST_CAMERA_CAPTURE_STATUS
qCDebug(CameraControlLog) << "handleCaptureStatus:" << cap.available_capacity << cap.image_interval << cap.image_status << cap.recording_time_ms << cap.video_status; qCDebug(CameraControlLog) << "handleCaptureStatus:" << cap.available_capacity << cap.image_interval << cap.image_status << cap.recording_time_ms << cap.video_status;
//-- Disk Free Space //-- Disk Free Space
if(_storageFree != cap.available_capacity) { uint32_t a = static_cast<uint32_t>(cap.available_capacity);
_storageFree = cap.available_capacity; if(_storageFree != a) {
_storageFree = a;
emit storageFreeChanged(); emit storageFreeChanged();
} }
//-- Video/Image Capture Status //-- Video/Image Capture Status
uint8_t vs = cap.video_status < (uint8_t)VIDEO_CAPTURE_STATUS_LAST ? cap.video_status : (uint8_t)VIDEO_CAPTURE_STATUS_UNDEFINED; uint8_t vs = cap.video_status < static_cast<uint8_t>(VIDEO_CAPTURE_STATUS_LAST) ? cap.video_status : static_cast<uint8_t>(VIDEO_CAPTURE_STATUS_UNDEFINED);
uint8_t ps = cap.image_status < (uint8_t)PHOTO_CAPTURE_LAST ? cap.image_status : (uint8_t)PHOTO_CAPTURE_STATUS_UNDEFINED; uint8_t ps = cap.image_status < static_cast<uint8_t>(PHOTO_CAPTURE_LAST) ? cap.image_status : static_cast<uint8_t>(PHOTO_CAPTURE_STATUS_UNDEFINED);
_setVideoStatus((VideoStatus)vs); _setVideoStatus(static_cast<VideoStatus>(vs));
_setPhotoStatus((PhotoStatus)ps); _setPhotoStatus(static_cast<PhotoStatus>(ps));
//-- Keep asking for it once in a while when recording //-- Keep asking for it once in a while when recording
if(videoStatus() == VIDEO_CAPTURE_STATUS_RUNNING) { if(videoStatus() == VIDEO_CAPTURE_STATUS_RUNNING) {
_captureStatusTimer.start(5000); _captureStatusTimer.start(5000);
......
...@@ -21,13 +21,7 @@ Q_DECLARE_LOGGING_CATEGORY(CameraControlLogVerbose) ...@@ -21,13 +21,7 @@ Q_DECLARE_LOGGING_CATEGORY(CameraControlLogVerbose)
class QGCCameraOptionExclusion : public QObject class QGCCameraOptionExclusion : public QObject
{ {
public: public:
QGCCameraOptionExclusion(QObject* parent, QString param_, QString value_, QStringList exclusions_) QGCCameraOptionExclusion(QObject* parent, QString param_, QString value_, QStringList exclusions_);
: QObject(parent)
, param(param_)
, value(value_)
, exclusions(exclusions_)
{
}
QString param; QString param;
QString value; QString value;
QStringList exclusions; QStringList exclusions;
...@@ -37,16 +31,7 @@ public: ...@@ -37,16 +31,7 @@ public:
class QGCCameraOptionRange : public QObject class QGCCameraOptionRange : public QObject
{ {
public: public:
QGCCameraOptionRange(QObject* parent, QString param_, QString value_, QString targetParam_, QString condition_, QStringList optNames_, QStringList optValues_) QGCCameraOptionRange(QObject* parent, QString param_, QString value_, QString targetParam_, QString condition_, QStringList optNames_, QStringList optValues_);
: QObject(parent)
, param(param_)
, value(value_)
, targetParam(targetParam_)
, condition(condition_)
, optNames(optNames_)
, optValues(optValues_)
{
}
QString param; QString param;
QString value; QString value;
QString targetParam; QString targetParam;
...@@ -62,7 +47,7 @@ class QGCCameraControl : public FactGroup ...@@ -62,7 +47,7 @@ class QGCCameraControl : public FactGroup
Q_OBJECT Q_OBJECT
friend class QGCCameraParamIO; friend class QGCCameraParamIO;
public: public:
QGCCameraControl(const mavlink_camera_information_t* info, Vehicle* vehicle, int compID, QObject* parent = NULL); QGCCameraControl(const mavlink_camera_information_t* info, Vehicle* vehicle, int compID, QObject* parent = nullptr);
virtual ~QGCCameraControl(); virtual ~QGCCameraControl();
//-- cam_mode //-- cam_mode
...@@ -142,8 +127,8 @@ public: ...@@ -142,8 +127,8 @@ public:
virtual QString modelName () { return _modelName; } virtual QString modelName () { return _modelName; }
virtual QString vendor () { return _vendor; } virtual QString vendor () { return _vendor; }
virtual QString firmwareVersion (); virtual QString firmwareVersion ();
virtual qreal focalLength () { return (qreal)_info.focal_length; } virtual qreal focalLength () { return static_cast<qreal>(_info.focal_length); }
virtual QSizeF sensorSize () { return QSizeF(_info.sensor_size_h, _info.sensor_size_v); } virtual QSizeF sensorSize () { return QSizeF(static_cast<qreal>(_info.sensor_size_h), static_cast<qreal>(_info.sensor_size_v)); }
virtual QSize resolution () { return QSize(_info.resolution_h, _info.resolution_v); } virtual QSize resolution () { return QSize(_info.resolution_h, _info.resolution_v); }
virtual bool capturesVideo () { return _info.flags & CAMERA_CAP_FLAGS_CAPTURE_VIDEO; } virtual bool capturesVideo () { return _info.flags & CAMERA_CAP_FLAGS_CAPTURE_VIDEO; }
virtual bool capturesPhotos () { return _info.flags & CAMERA_CAP_FLAGS_CAPTURE_IMAGE; } virtual bool capturesPhotos () { return _info.flags & CAMERA_CAP_FLAGS_CAPTURE_IMAGE; }
......
...@@ -22,7 +22,7 @@ import QGroundControl.Controllers 1.0 ...@@ -22,7 +22,7 @@ import QGroundControl.Controllers 1.0
Item { Item {
id: root id: root
property double _ar: QGroundControl.settingsManager.videoSettings.aspectRatio.rawValue property double _ar: QGroundControl.videoManager.aspectRatio
property bool _showGrid: QGroundControl.settingsManager.videoSettings.gridLines.rawValue > 0 property bool _showGrid: QGroundControl.settingsManager.videoSettings.gridLines.rawValue > 0
property var _videoReceiver: QGroundControl.videoManager.videoReceiver property var _videoReceiver: QGroundControl.videoManager.videoReceiver
property var _activeVehicle: QGroundControl.multiVehicleManager.activeVehicle property var _activeVehicle: QGroundControl.multiVehicleManager.activeVehicle
......
...@@ -25,7 +25,9 @@ ...@@ -25,7 +25,9 @@
#include "QGCToolbox.h" #include "QGCToolbox.h"
#include "QGCCorePlugin.h" #include "QGCCorePlugin.h"
#include "QGCOptions.h" #include "QGCOptions.h"
#include "MultiVehicleManager.h"
#include "Settings/SettingsManager.h" #include "Settings/SettingsManager.h"
#include "Vehicle.h"
QGC_LOGGING_CATEGORY(VideoManagerLog, "VideoManagerLog") QGC_LOGGING_CATEGORY(VideoManagerLog, "VideoManagerLog")
...@@ -35,6 +37,7 @@ VideoManager::VideoManager(QGCApplication* app, QGCToolbox* toolbox) ...@@ -35,6 +37,7 @@ VideoManager::VideoManager(QGCApplication* app, QGCToolbox* toolbox)
, _videoReceiver(nullptr) , _videoReceiver(nullptr)
, _videoSettings(nullptr) , _videoSettings(nullptr)
, _fullScreen(false) , _fullScreen(false)
, _activeVehicle(nullptr)
{ {
} }
...@@ -61,6 +64,9 @@ VideoManager::setToolbox(QGCToolbox *toolbox) ...@@ -61,6 +64,9 @@ VideoManager::setToolbox(QGCToolbox *toolbox)
connect(_videoSettings->udpPort(), &Fact::rawValueChanged, this, &VideoManager::_udpPortChanged); connect(_videoSettings->udpPort(), &Fact::rawValueChanged, this, &VideoManager::_udpPortChanged);
connect(_videoSettings->rtspUrl(), &Fact::rawValueChanged, this, &VideoManager::_rtspUrlChanged); connect(_videoSettings->rtspUrl(), &Fact::rawValueChanged, this, &VideoManager::_rtspUrlChanged);
connect(_videoSettings->tcpUrl(), &Fact::rawValueChanged, this, &VideoManager::_tcpUrlChanged); connect(_videoSettings->tcpUrl(), &Fact::rawValueChanged, this, &VideoManager::_tcpUrlChanged);
connect(_videoSettings->aspectRatio(), &Fact::rawValueChanged, this, &VideoManager::_aspectRatioChanged);
MultiVehicleManager *manager = qgcApp()->toolbox()->multiVehicleManager();
connect(manager, &MultiVehicleManager::activeVehicleChanged, this, &VideoManager::_setActiveVehicle);
#if defined(QGC_GST_STREAMING) #if defined(QGC_GST_STREAMING)
#ifndef QGC_DISABLE_UVC #ifndef QGC_DISABLE_UVC
...@@ -81,6 +87,19 @@ VideoManager::setToolbox(QGCToolbox *toolbox) ...@@ -81,6 +87,19 @@ VideoManager::setToolbox(QGCToolbox *toolbox)
#endif #endif
} }
//-----------------------------------------------------------------------------
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();
}
}
//----------------------------------------------------------------------------- //-----------------------------------------------------------------------------
void void
VideoManager::_updateUVC() VideoManager::_updateUVC()
...@@ -106,6 +125,7 @@ VideoManager::_videoSourceChanged() ...@@ -106,6 +125,7 @@ VideoManager::_videoSourceChanged()
_updateUVC(); _updateUVC();
emit hasVideoChanged(); emit hasVideoChanged();
emit isGStreamerChanged(); emit isGStreamerChanged();
emit isAutoStreamChanged();
_restartVideo(); _restartVideo();
} }
...@@ -144,7 +164,23 @@ VideoManager::isGStreamer() ...@@ -144,7 +164,23 @@ VideoManager::isGStreamer()
{ {
#if defined(QGC_GST_STREAMING) #if defined(QGC_GST_STREAMING)
QString videoSource = _videoSettings->videoSource()->rawValue().toString(); QString videoSource = _videoSettings->videoSource()->rawValue().toString();
return videoSource == VideoSettings::videoSourceUDP || videoSource == VideoSettings::videoSourceRTSP || videoSource == VideoSettings::videoSourceTCP; 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;
#else #else
return false; return false;
#endif #endif
...@@ -171,6 +207,8 @@ VideoManager::_updateSettings() ...@@ -171,6 +207,8 @@ VideoManager::_updateSettings()
_videoReceiver->setUri(_videoSettings->rtspUrl()->rawValue().toString()); _videoReceiver->setUri(_videoSettings->rtspUrl()->rawValue().toString());
else if (_videoSettings->videoSource()->rawValue().toString() == VideoSettings::videoSourceTCP) else if (_videoSettings->videoSource()->rawValue().toString() == VideoSettings::videoSourceTCP)
_videoReceiver->setUri(QStringLiteral("tcp://%1").arg(_videoSettings->tcpUrl()->rawValue().toString())); _videoReceiver->setUri(QStringLiteral("tcp://%1").arg(_videoSettings->tcpUrl()->rawValue().toString()));
else if (isAutoStream())
_videoReceiver->setUri(QString(_streamInfo.uri));
} }
//----------------------------------------------------------------------------- //-----------------------------------------------------------------------------
...@@ -185,3 +223,47 @@ VideoManager::_restartVideo() ...@@ -185,3 +223,47 @@ VideoManager::_restartVideo()
_videoReceiver->start(); _videoReceiver->start();
#endif #endif
} }
//----------------------------------------------------------------------------------------
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);
qCDebug(VideoManagerLog) << "Requesting video stream info";
_activeVehicle->sendMavCommand(
MAV_COMP_ID_ALL, // Target component
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);
qCDebug(VideoManagerLog) << "Received video stream info:" << _streamInfo.uri;
_restartVideo();
emit aspectRatioChanged();
}
}
//----------------------------------------------------------------------------------------
void
VideoManager::_aspectRatioChanged()
{
emit aspectRatioChanged();
}
...@@ -15,6 +15,7 @@ ...@@ -15,6 +15,7 @@
#include <QTimer> #include <QTimer>
#include <QUrl> #include <QUrl>
#include "QGCMAVLink.h"
#include "QGCLoggingCategory.h" #include "QGCLoggingCategory.h"
#include "VideoReceiver.h" #include "VideoReceiver.h"
#include "QGCToolbox.h" #include "QGCToolbox.h"
...@@ -22,6 +23,7 @@ ...@@ -22,6 +23,7 @@
Q_DECLARE_LOGGING_CATEGORY(VideoManagerLog) Q_DECLARE_LOGGING_CATEGORY(VideoManagerLog)
class VideoSettings; class VideoSettings;
class Vehicle;
class VideoManager : public QGCTool class VideoManager : public QGCTool
{ {
...@@ -33,15 +35,20 @@ public: ...@@ -33,15 +35,20 @@ public:
Q_PROPERTY(bool hasVideo READ hasVideo NOTIFY hasVideoChanged) Q_PROPERTY(bool hasVideo READ hasVideo NOTIFY hasVideoChanged)
Q_PROPERTY(bool isGStreamer READ isGStreamer NOTIFY isGStreamerChanged) Q_PROPERTY(bool isGStreamer READ isGStreamer NOTIFY isGStreamerChanged)
Q_PROPERTY(bool isAutoStream READ isAutoStream NOTIFY isAutoStreamChanged)
Q_PROPERTY(QString videoSourceID READ videoSourceID NOTIFY videoSourceIDChanged) Q_PROPERTY(QString videoSourceID READ videoSourceID NOTIFY videoSourceIDChanged)
Q_PROPERTY(bool uvcEnabled READ uvcEnabled CONSTANT) Q_PROPERTY(bool uvcEnabled READ uvcEnabled CONSTANT)
Q_PROPERTY(bool fullScreen READ fullScreen WRITE setfullScreen NOTIFY fullScreenChanged) Q_PROPERTY(bool fullScreen READ fullScreen WRITE setfullScreen NOTIFY fullScreenChanged)
Q_PROPERTY(VideoReceiver* videoReceiver READ videoReceiver CONSTANT) Q_PROPERTY(VideoReceiver* videoReceiver READ videoReceiver CONSTANT)
Q_PROPERTY(double aspectRatio READ aspectRatio NOTIFY aspectRatioChanged)
bool hasVideo (); bool hasVideo ();
bool isGStreamer (); bool isGStreamer ();
bool isAutoStream ();
bool fullScreen () { return _fullScreen; } bool fullScreen () { return _fullScreen; }
QString videoSourceID () { return _videoSourceID; } QString videoSourceID () { return _videoSourceID; }
QString autoURL () { return QString(_streamInfo.uri); }
double aspectRatio ();
VideoReceiver* videoReceiver () { return _videoReceiver; } VideoReceiver* videoReceiver () { return _videoReceiver; }
...@@ -64,6 +71,8 @@ signals: ...@@ -64,6 +71,8 @@ signals:
void isGStreamerChanged (); void isGStreamerChanged ();
void videoSourceIDChanged (); void videoSourceIDChanged ();
void fullScreenChanged (); void fullScreenChanged ();
void isAutoStreamChanged ();
void aspectRatioChanged ();
private slots: private slots:
void _videoSourceChanged (); void _videoSourceChanged ();
...@@ -71,6 +80,9 @@ private slots: ...@@ -71,6 +80,9 @@ private slots:
void _rtspUrlChanged (); void _rtspUrlChanged ();
void _tcpUrlChanged (); void _tcpUrlChanged ();
void _updateUVC (); void _updateUVC ();
void _aspectRatioChanged ();
void _setActiveVehicle (Vehicle* vehicle);
void _vehicleMessageReceived (const mavlink_message_t& message);
private: private:
void _updateSettings (); void _updateSettings ();
...@@ -80,6 +92,8 @@ private: ...@@ -80,6 +92,8 @@ private:
VideoSettings* _videoSettings; VideoSettings* _videoSettings;
QString _videoSourceID; QString _videoSourceID;
bool _fullScreen; bool _fullScreen;
Vehicle* _activeVehicle;
mavlink_video_stream_information_t _streamInfo;
}; };
#endif #endif
...@@ -8,6 +8,8 @@ ...@@ -8,6 +8,8 @@
****************************************************************************/ ****************************************************************************/
#include "VideoSettings.h" #include "VideoSettings.h"
#include "QGCApplication.h"
#include "VideoManager.h"
#include <QQmlEngine> #include <QQmlEngine>
#include <QtQml> #include <QtQml>
...@@ -19,12 +21,10 @@ ...@@ -19,12 +21,10 @@
const char* VideoSettings::videoSourceNoVideo = "No Video Available"; const char* VideoSettings::videoSourceNoVideo = "No Video Available";
const char* VideoSettings::videoDisabled = "Video Stream Disabled"; const char* VideoSettings::videoDisabled = "Video Stream Disabled";
const char* VideoSettings::videoSourceUDP = "UDP Video Stream"; const char* VideoSettings::videoSourceAuto = "Automatic Video Stream";
const char* VideoSettings::videoSourceRTSP = "RTSP Video Stream"; const char* VideoSettings::videoSourceRTSP = "RTSP Video Stream";
const char* VideoSettings::videoSourceUDP = "UDP Video Stream";
const char* VideoSettings::videoSourceTCP = "TCP-MPEG2 Video Stream"; const char* VideoSettings::videoSourceTCP = "TCP-MPEG2 Video Stream";
#ifdef QGC_GST_TAISYNC_USB
const char* VideoSettings::videoSourceTaiSyncUSB = "Taisync USB";
#endif
DECLARE_SETTINGGROUP(Video, "Video") DECLARE_SETTINGGROUP(Video, "Video")
{ {
...@@ -34,14 +34,12 @@ DECLARE_SETTINGGROUP(Video, "Video") ...@@ -34,14 +34,12 @@ DECLARE_SETTINGGROUP(Video, "Video")
// Setup enum values for videoSource settings into meta data // Setup enum values for videoSource settings into meta data
QStringList videoSourceList; QStringList videoSourceList;
#ifdef QGC_GST_STREAMING #ifdef QGC_GST_STREAMING
videoSourceList.append(videoSourceAuto);
videoSourceList.append(videoSourceRTSP);
#ifndef NO_UDP_VIDEO #ifndef NO_UDP_VIDEO
videoSourceList.append(videoSourceUDP); videoSourceList.append(videoSourceUDP);
#endif #endif
videoSourceList.append(videoSourceRTSP);
videoSourceList.append(videoSourceTCP); videoSourceList.append(videoSourceTCP);
#ifdef QGC_GST_TAISYNC_USB
videoSourceList.append(videoSourceTaiSyncUSB);
#endif
#endif #endif
#ifndef QGC_DISABLE_UVC #ifndef QGC_DISABLE_UVC
QList<QCameraInfo> cameras = QCameraInfo::availableCameras(); QList<QCameraInfo> cameras = QCameraInfo::availableCameras();
...@@ -60,7 +58,6 @@ DECLARE_SETTINGGROUP(Video, "Video") ...@@ -60,7 +58,6 @@ DECLARE_SETTINGGROUP(Video, "Video")
videoSourceVarList.append(QVariant::fromValue(videoSource)); videoSourceVarList.append(QVariant::fromValue(videoSource));
} }
_nameToMetaDataMap[videoSourceName]->setEnumInfo(videoSourceList, videoSourceVarList); _nameToMetaDataMap[videoSourceName]->setEnumInfo(videoSourceList, videoSourceVarList);
// Set default value for videoSource // Set default value for videoSource
_setDefaults(); _setDefaults();
} }
...@@ -138,23 +135,26 @@ bool VideoSettings::streamConfigured(void) ...@@ -138,23 +135,26 @@ bool VideoSettings::streamConfigured(void)
if(vSource == videoSourceNoVideo || vSource == videoDisabled) { if(vSource == videoSourceNoVideo || vSource == videoDisabled) {
return false; return false;
} }
#ifdef QGC_GST_TAISYNC_USB
if(vSource == videoSourceTaiSyncUSB) {
return true;
}
#endif
//-- If UDP, check if port is set //-- If UDP, check if port is set
if(vSource == videoSourceUDP) { if(vSource == videoSourceUDP) {
qCDebug(VideoManagerLog) << "Testing configuration for UDP Stream:" << udpPort()->rawValue().toInt();
return udpPort()->rawValue().toInt() != 0; return udpPort()->rawValue().toInt() != 0;
} }
//-- If RTSP, check for URL //-- If RTSP, check for URL
if(vSource == videoSourceRTSP) { if(vSource == videoSourceRTSP) {
qCDebug(VideoManagerLog) << "Testing configuration for RTSP Stream:" << rtspUrl()->rawValue().toString();
return !rtspUrl()->rawValue().toString().isEmpty(); return !rtspUrl()->rawValue().toString().isEmpty();
} }
//-- If TCP, check for URL //-- If TCP, check for URL
if(vSource == videoSourceTCP) { if(vSource == videoSourceTCP) {
qCDebug(VideoManagerLog) << "Testing configuration for TCP Stream:" << tcpUrl()->rawValue().toString();
return !tcpUrl()->rawValue().toString().isEmpty(); return !tcpUrl()->rawValue().toString().isEmpty();
} }
//-- If Auto, check for received URL
if(vSource == videoSourceAuto) {
qCDebug(VideoManagerLog) << "Testing configuration for Auto Stream:" << qgcApp()->toolbox()->videoManager()->autoURL();
return !qgcApp()->toolbox()->videoManager()->autoURL().isEmpty();
}
return false; return false;
} }
......
...@@ -36,17 +36,23 @@ public: ...@@ -36,17 +36,23 @@ public:
DEFINE_SETTINGFACT(disableWhenDisarmed) DEFINE_SETTINGFACT(disableWhenDisarmed)
Q_PROPERTY(bool streamConfigured READ streamConfigured NOTIFY streamConfiguredChanged) Q_PROPERTY(bool streamConfigured READ streamConfigured NOTIFY streamConfiguredChanged)
Q_PROPERTY(QString autoVideoSource READ autoVideoSource CONSTANT)
Q_PROPERTY(QString rtspVideoSource READ rtspVideoSource CONSTANT)
Q_PROPERTY(QString udpVideoSource READ udpVideoSource CONSTANT)
Q_PROPERTY(QString tcpVideoSource READ tcpVideoSource CONSTANT)
bool streamConfigured (); bool streamConfigured ();
QString autoVideoSource () { return videoSourceAuto; }
QString rtspVideoSource () { return videoSourceRTSP; }
QString udpVideoSource () { return videoSourceUDP; }
QString tcpVideoSource () { return videoSourceTCP; }
static const char* videoSourceNoVideo; static const char* videoSourceNoVideo;
static const char* videoDisabled; static const char* videoDisabled;
static const char* videoSourceUDP; static const char* videoSourceUDP;
static const char* videoSourceRTSP; static const char* videoSourceRTSP;
static const char* videoSourceAuto;
static const char* videoSourceTCP; static const char* videoSourceTCP;
#ifdef QGC_GST_TAISYNC_USB
static const char* videoSourceTaiSyncUSB;
#endif
signals: signals:
void streamConfiguredChanged (); void streamConfiguredChanged ();
......
...@@ -501,7 +501,7 @@ public: ...@@ -501,7 +501,7 @@ public:
Vehicle(MAV_AUTOPILOT firmwareType, Vehicle(MAV_AUTOPILOT firmwareType,
MAV_TYPE vehicleType, MAV_TYPE vehicleType,
FirmwarePluginManager* firmwarePluginManager, FirmwarePluginManager* firmwarePluginManager,
QObject* parent = NULL); QObject* parent = nullptr);
~Vehicle(); ~Vehicle();
...@@ -892,9 +892,9 @@ public: ...@@ -892,9 +892,9 @@ public:
QString formatedMessages (); QString formatedMessages ();
QString formatedMessage () { return _formatedMessage; } QString formatedMessage () { return _formatedMessage; }
QString latestError () { return _latestError; } QString latestError () { return _latestError; }
float latitude () { return _coordinate.latitude(); } float latitude () { return static_cast<float>(_coordinate.latitude()); }
float longitude () { return _coordinate.longitude(); } float longitude () { return static_cast<float>(_coordinate.longitude()); }
bool mavPresent () { return _mav != NULL; } bool mavPresent () { return _mav != nullptr; }
int rcRSSI () { return _rcRSSI; } int rcRSSI () { return _rcRSSI; }
bool px4Firmware () const { return _firmwareType == MAV_AUTOPILOT_PX4; } bool px4Firmware () const { return _firmwareType == MAV_AUTOPILOT_PX4; }
bool apmFirmware () const { return _firmwareType == MAV_AUTOPILOT_ARDUPILOTMEGA; } bool apmFirmware () const { return _firmwareType == MAV_AUTOPILOT_ARDUPILOTMEGA; }
...@@ -990,8 +990,19 @@ public: ...@@ -990,8 +990,19 @@ public:
void sendMavCommandInt(int component, MAV_CMD command, MAV_FRAME frame, bool showError, float param1, float param2, float param3, float param4, double param5, double param6, float param7); void sendMavCommandInt(int component, MAV_CMD command, MAV_FRAME frame, bool showError, float param1, float param2, float param3, float param4, double param5, double param6, float param7);
/// Same as sendMavCommand but available from Qml. /// Same as sendMavCommand but available from Qml.
Q_INVOKABLE void sendCommand(int component, int command, bool showError, double param1 = 0.0f, double param2 = 0.0f, double param3 = 0.0f, double param4 = 0.0f, double param5 = 0.0f, double param6 = 0.0f, double param7 = 0.0f) Q_INVOKABLE void sendCommand(int component, int command, bool showError, double param1 = 0.0, double param2 = 0.0, double param3 = 0.0, double param4 = 0.0, double param5 = 0.0, double param6 = 0.0, double param7 = 0.0)
{ sendMavCommand(component, (MAV_CMD)command, showError, param1, param2, param3, param4, param5, param6, param7); } {
sendMavCommand(
component, static_cast<MAV_CMD>(command),
showError,
static_cast<float>(param1),
static_cast<float>(param2),
static_cast<float>(param3),
static_cast<float>(param4),
static_cast<float>(param5),
static_cast<float>(param6),
static_cast<float>(param7));
}
int firmwareMajorVersion(void) const { return _firmwareMajorVersion; } int firmwareMajorVersion(void) const { return _firmwareMajorVersion; }
int firmwareMinorVersion(void) const { return _firmwareMinorVersion; } int firmwareMinorVersion(void) const { return _firmwareMinorVersion; }
......
...@@ -45,6 +45,13 @@ QGCView { ...@@ -45,6 +45,13 @@ QGCView {
property real _panelWidth: _qgcView.width * _internalWidthRatio property real _panelWidth: _qgcView.width * _internalWidthRatio
property real _margins: ScreenTools.defaultFontPixelWidth property real _margins: ScreenTools.defaultFontPixelWidth
property string _videoSource: QGroundControl.settingsManager.videoSettings.videoSource.value
property bool _isGst: QGroundControl.videoManager.isGStreamer
property bool _isAutoStream: QGroundControl.videoManager.isAutoStream
property bool _isUDP: _isGst && _videoSource === QGroundControl.settingsManager.videoSettings.udpVideoSource
property bool _isRTSP: _isGst && _videoSource === QGroundControl.settingsManager.videoSettings.rtspVideoSource
property bool _isTCP: _isGst && _videoSource === QGroundControl.settingsManager.videoSettings.tcpVideoSource
readonly property real _internalWidthRatio: 0.8 readonly property real _internalWidthRatio: 0.8
QGCPalette { id: qgcPal } QGCPalette { id: qgcPal }
...@@ -715,52 +722,51 @@ QGCView { ...@@ -715,52 +722,51 @@ QGCView {
QGCLabel { QGCLabel {
text: qsTr("UDP Port") text: qsTr("UDP Port")
visible: QGroundControl.settingsManager.videoSettings.udpPort.visible && QGroundControl.videoManager.isGStreamer && videoSource.currentIndex === 1 visible: _isUDP && QGroundControl.settingsManager.videoSettings.udpPort.visible
} }
FactTextField { FactTextField {
Layout.preferredWidth: _comboFieldWidth Layout.preferredWidth: _comboFieldWidth
fact: QGroundControl.settingsManager.videoSettings.udpPort fact: QGroundControl.settingsManager.videoSettings.udpPort
visible: QGroundControl.settingsManager.videoSettings.udpPort.visible && QGroundControl.videoManager.isGStreamer && videoSource.currentIndex === 1 visible: _isUDP && QGroundControl.settingsManager.videoSettings.udpPort.visible
} }
QGCLabel { QGCLabel {
text: qsTr("RTSP URL") text: qsTr("RTSP URL")
visible: QGroundControl.settingsManager.videoSettings.rtspUrl.visible && QGroundControl.videoManager.isGStreamer && videoSource.currentIndex === 2 visible: _isRTSP && QGroundControl.settingsManager.videoSettings.rtspUrl.visible
} }
FactTextField { FactTextField {
Layout.preferredWidth: _comboFieldWidth Layout.preferredWidth: _comboFieldWidth
fact: QGroundControl.settingsManager.videoSettings.rtspUrl fact: QGroundControl.settingsManager.videoSettings.rtspUrl
visible: QGroundControl.settingsManager.videoSettings.rtspUrl.visible && QGroundControl.videoManager.isGStreamer && videoSource.currentIndex === 2 visible: _isRTSP && QGroundControl.settingsManager.videoSettings.rtspUrl.visible
} }
QGCLabel { QGCLabel {
text: qsTr("TCP URL") text: qsTr("TCP URL")
visible: QGroundControl.settingsManager.videoSettings.tcpUrl.visible && QGroundControl.videoManager.isGStreamer && videoSource.currentIndex === 3 visible: _isTCP && QGroundControl.settingsManager.videoSettings.tcpUrl.visible
} }
FactTextField { FactTextField {
Layout.preferredWidth: _comboFieldWidth Layout.preferredWidth: _comboFieldWidth
fact: QGroundControl.settingsManager.videoSettings.tcpUrl fact: QGroundControl.settingsManager.videoSettings.tcpUrl
visible: QGroundControl.settingsManager.videoSettings.tcpUrl.visible && QGroundControl.videoManager.isGStreamer && videoSource.currentIndex === 3 visible: _isTCP && QGroundControl.settingsManager.videoSettings.tcpUrl.visible
} }
QGCLabel { QGCLabel {
text: qsTr("Aspect Ratio") text: qsTr("Aspect Ratio")
visible: QGroundControl.videoManager.isGStreamer && videoSource.currentIndex && videoSource.currentIndex < 3 && QGroundControl.settingsManager.videoSettings.aspectRatio.visible visible: !_isAutoStream && _isGst && QGroundControl.settingsManager.videoSettings.aspectRatio.visible
} }
FactTextField { FactTextField {
Layout.preferredWidth: _comboFieldWidth Layout.preferredWidth: _comboFieldWidth
fact: QGroundControl.settingsManager.videoSettings.aspectRatio fact: QGroundControl.settingsManager.videoSettings.aspectRatio
visible: QGroundControl.videoManager.isGStreamer && videoSource.currentIndex && videoSource.currentIndex < 3 && QGroundControl.settingsManager.videoSettings.aspectRatio.visible visible: !_isAutoStream && _isGst && QGroundControl.settingsManager.videoSettings.aspectRatio.visible
} }
QGCLabel { QGCLabel {
text: qsTr("Disable When Disarmed") text: qsTr("Disable When Disarmed")
visible: QGroundControl.videoManager.isGStreamer && videoSource.currentIndex && videoSource.currentIndex < 3 && QGroundControl.settingsManager.videoSettings.gridLines.visible visible: _isGst && QGroundControl.settingsManager.videoSettings.disableWhenDisarmed.visible
} }
FactCheckBox { FactCheckBox {
text: "" text: ""
fact: QGroundControl.settingsManager.videoSettings.disableWhenDisarmed fact: QGroundControl.settingsManager.videoSettings.disableWhenDisarmed
visible: QGroundControl.videoManager.isGStreamer && videoSource.currentIndex && videoSource.currentIndex < 3 && QGroundControl.settingsManager.videoSettings.gridLines.visible visible: _isGst && QGroundControl.settingsManager.videoSettings.disableWhenDisarmed.visible
} }
} }
} }
...@@ -770,7 +776,7 @@ QGCView { ...@@ -770,7 +776,7 @@ QGCView {
QGCLabel { QGCLabel {
id: videoRecSectionLabel id: videoRecSectionLabel
text: qsTr("Video Recording") text: qsTr("Video Recording")
visible: QGroundControl.settingsManager.videoSettings.visible && QGroundControl.videoManager.isGStreamer && videoSource.currentIndex && videoSource.currentIndex < 4 visible: QGroundControl.settingsManager.videoSettings.visible && _isGst
} }
Rectangle { Rectangle {
Layout.preferredWidth: videoRecCol.width + (_margins * 2) Layout.preferredWidth: videoRecCol.width + (_margins * 2)
......
Markdown is supported
0% or
You are about to add 0 people to the discussion. Proceed with caution.
Finish editing this message first!
Please register or to comment