Unverified Commit 6c8477f8 authored by Gus Grubba's avatar Gus Grubba Committed by GitHub

Merge pull request #7146 from mavlink/cameraAndVideo

Camera and Video Streams
parents 93d38743 80a12fd1
Subproject commit 90d9b285e01fe8bfa3b4e8868ca71c5537d43302
Subproject commit c847642263deefa584691eebade8b29a25264442
......@@ -10,6 +10,7 @@
#include "SettingsManager.h"
#include "VideoManager.h"
#include "QGCMapEngine.h"
#include "QGCCameraManager.h"
#include <QDir>
#include <QStandardPaths>
......@@ -66,6 +67,7 @@ static const char *kCAM_ISO = "CAM_ISO";
static const char* kCAM_SHUTTER = "CAM_SHUTTER";
static const char* kCAM_APERTURE = "CAM_APERTURE";
static const char* kCAM_WBMODE = "CAM_WBMODE";
static const char* kCAM_MODE = "CAM_MODE";
//-----------------------------------------------------------------------------
QGCCameraOptionExclusion::QGCCameraOptionExclusion(QObject* parent, QString param_, QString value_, QStringList exclusions_)
......@@ -153,21 +155,6 @@ QGCCameraControl::QGCCameraControl(const mavlink_camera_information_t *info, Veh
: FactGroup(0, parent)
, _vehicle(vehicle)
, _compID(compID)
, _version(0)
, _cached(false)
, _paramComplete(false)
, _storageFree(0)
, _storageTotal(0)
, _netManager(nullptr)
, _cameraMode(CAM_MODE_UNDEFINED)
, _photoMode(PHOTO_CAPTURE_SINGLE)
, _photoLapse(1.0)
, _photoLapseCount(0)
, _video_status(VIDEO_CAPTURE_STATUS_UNDEFINED)
, _photo_status(PHOTO_CAPTURE_STATUS_UNDEFINED)
, _storageInfoRetries(0)
, _captureInfoRetries(0)
, _resetting(false)
{
QQmlEngine::setObjectOwnership(this, QQmlEngine::CppOwnership);
memcpy(&_info, info, sizeof(mavlink_camera_information_t));
......@@ -190,6 +177,9 @@ QGCCameraControl::QGCCameraControl(const mavlink_camera_information_t *info, Veh
_photoMode = static_cast<PhotoMode>(settings.value(kPhotoMode, static_cast<int>(PHOTO_CAPTURE_SINGLE)).toInt());
_photoLapse = settings.value(kPhotoLapse, 1.0).toDouble();
_photoLapseCount = settings.value(kPhotoLapseCount, 0).toInt();
_recTimer.setSingleShot(false);
_recTimer.setInterval(333);
connect(&_recTimer, &QTimer::timeout, this, &QGCCameraControl::_recTimerHandler);
}
//-----------------------------------------------------------------------------
......@@ -208,6 +198,7 @@ QGCCameraControl::_initWhenReady()
if(isBasic()) {
qCDebug(CameraControlLog) << "Basic, MAVLink only messages.";
_requestCameraSettings();
QTimer::singleShot(250, this, &QGCCameraControl::_checkForVideoStreams);
} else {
_requestAllParameters();
//-- Give some time to load the parameters before going after the camera settings
......@@ -237,6 +228,13 @@ QGCCameraControl::firmwareVersion()
return ver;
}
//-----------------------------------------------------------------------------
QString
QGCCameraControl::recordTimeStr()
{
return QTime(0, 0).addMSecs(static_cast<int>(recordTime())).toString("hh:mm:ss");
}
//-----------------------------------------------------------------------------
QGCCameraControl::VideoStatus
QGCCameraControl::videoStatus()
......@@ -270,7 +268,6 @@ QGCCameraControl::setCameraMode(CameraMode mode)
setPhotoMode();
} else {
qCDebug(CameraControlLog) << "setCameraMode() Invalid mode:" << mode;
return;
}
}
}
......@@ -311,8 +308,12 @@ QGCCameraControl::setPhotoLapseCount(int count)
void
QGCCameraControl::_setCameraMode(CameraMode mode)
{
_cameraMode = mode;
emit cameraModeChanged();
if(_cameraMode != mode) {
_cameraMode = mode;
emit cameraModeChanged();
//-- Update stream status
_streamStatusTimer.start(1000);
}
}
//-----------------------------------------------------------------------------
......@@ -410,7 +411,7 @@ QGCCameraControl::startVideo()
_vehicle->sendMavCommand(
_compID, // Target component
MAV_CMD_VIDEO_START_CAPTURE, // Command id
true, // ShowError
false, // Don't Show Error (handle locally)
0, // Reserved (Set to 0)
0); // CAMERA_CAPTURE_STATUS Frequency
return true;
......@@ -429,7 +430,7 @@ QGCCameraControl::stopVideo()
_vehicle->sendMavCommand(
_compID, // Target component
MAV_CMD_VIDEO_STOP_CAPTURE, // Command id
true, // ShowError
false, // Don't Show Error (handle locally)
0); // Reserved (Set to 0)
return true;
}
......@@ -441,17 +442,27 @@ QGCCameraControl::stopVideo()
void
QGCCameraControl::setVideoMode()
{
if(!_resetting) {
if(hasModes() && _cameraMode != CAM_MODE_VIDEO) {
qCDebug(CameraControlLog) << "setVideoMode()";
//-- Use basic MAVLink message
_vehicle->sendMavCommand(
_compID, // Target component
MAV_CMD_SET_CAMERA_MODE, // Command id
true, // ShowError
0, // Reserved (Set to 0)
CAM_MODE_VIDEO); // Camera mode (0: photo, 1: video)
_setCameraMode(CAM_MODE_VIDEO);
if(!_resetting && hasModes()) {
qCDebug(CameraControlLog) << "setVideoMode()";
//-- Does it have a mode parameter?
Fact* pMode = mode();
if(pMode) {
if(cameraMode() != CAM_MODE_VIDEO) {
pMode->setRawValue(CAM_MODE_VIDEO);
_setCameraMode(CAM_MODE_VIDEO);
}
} else {
//-- Use MAVLink Command
if(_cameraMode != CAM_MODE_VIDEO) {
//-- Use basic MAVLink message
_vehicle->sendMavCommand(
_compID, // Target component
MAV_CMD_SET_CAMERA_MODE, // Command id
true, // ShowError
0, // Reserved (Set to 0)
CAM_MODE_VIDEO); // Camera mode (0: photo, 1: video)
_setCameraMode(CAM_MODE_VIDEO);
}
}
}
}
......@@ -460,17 +471,27 @@ QGCCameraControl::setVideoMode()
void
QGCCameraControl::setPhotoMode()
{
if(!_resetting) {
if(hasModes() && _cameraMode != CAM_MODE_PHOTO) {
qCDebug(CameraControlLog) << "setPhotoMode()";
//-- Use basic MAVLink message
_vehicle->sendMavCommand(
_compID, // Target component
MAV_CMD_SET_CAMERA_MODE, // Command id
true, // ShowError
0, // Reserved (Set to 0)
CAM_MODE_PHOTO); // Camera mode (0: photo, 1: video)
_setCameraMode(CAM_MODE_PHOTO);
if(!_resetting && hasModes()) {
qCDebug(CameraControlLog) << "setPhotoMode()";
//-- Does it have a mode parameter?
Fact* pMode = mode();
if(pMode) {
if(cameraMode() != CAM_MODE_PHOTO) {
pMode->setRawValue(CAM_MODE_PHOTO);
_setCameraMode(CAM_MODE_PHOTO);
}
} else {
//-- Use MAVLink Command
if(_cameraMode != CAM_MODE_PHOTO) {
//-- Use basic MAVLink message
_vehicle->sendMavCommand(
_compID, // Target component
MAV_CMD_SET_CAMERA_MODE, // Command id
true, // ShowError
0, // Reserved (Set to 0)
CAM_MODE_PHOTO); // Camera mode (0: photo, 1: video)
_setCameraMode(CAM_MODE_PHOTO);
}
}
}
}
......@@ -693,9 +714,26 @@ QGCCameraControl::_setVideoStatus(VideoStatus status)
if(_video_status != status) {
_video_status = status;
emit videoStatusChanged();
if(status == VIDEO_CAPTURE_STATUS_RUNNING) {
_recordTime = 0;
_recTime.start();
_recTimer.start();
} else {
_recTimer.stop();
_recordTime = 0;
emit recordTimeChanged();
}
}
}
//-----------------------------------------------------------------------------
void
QGCCameraControl::_recTimerHandler()
{
_recordTime = static_cast<uint32_t>(_recTime.elapsed());
emit recordTimeChanged();
}
//-----------------------------------------------------------------------------
void
QGCCameraControl::_setPhotoStatus(PhotoStatus status)
......@@ -1386,7 +1424,7 @@ QGCCameraControl::handleSettings(const mavlink_camera_settings_t& settings)
void
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;
uint32_t t = static_cast<uint32_t>(st.total_capacity);
if(_storageTotal != t) {
_storageTotal = t;
......@@ -1412,6 +1450,12 @@ QGCCameraControl::handleCaptureStatus(const mavlink_camera_capture_status_t& cap
_storageFree = a;
emit storageFreeChanged();
}
//-- Do we have recording time?
if(cap.recording_time_ms) {
_recordTime = cap.recording_time_ms;
_recTime = _recTime.addMSecs(_recTime.elapsed() - static_cast<int>(cap.recording_time_ms));
emit recordTimeChanged();
}
//-- Video/Image Capture Status
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 < static_cast<uint8_t>(PHOTO_CAPTURE_LAST) ? cap.image_status : static_cast<uint8_t>(PHOTO_CAPTURE_STATUS_UNDEFINED);
......@@ -1434,6 +1478,209 @@ QGCCameraControl::handleCaptureStatus(const mavlink_camera_capture_status_t& cap
}
}
//-----------------------------------------------------------------------------
void
QGCCameraControl::handleVideoInfo(const mavlink_video_stream_information_t* vi)
{
qCDebug(CameraControlLog) << "handleVideoInfo:" << vi->stream_id << vi->uri;
_expectedCount = vi->count;
if(!_findStream(vi->stream_id)) {
qCDebug(CameraControlLog) << "Create stream handler for stream ID:" << vi->stream_id;
QGCVideoStreamInfo* pStream = new QGCVideoStreamInfo(this, vi);
QQmlEngine::setObjectOwnership(pStream, QQmlEngine::CppOwnership);
_streams.append(pStream);
emit streamsChanged();
}
//-- Check for missing count
if(_streams.count() < _expectedCount) {
_streamInfoTimer.start(1000);
} else {
//-- Done
qCDebug(CameraControlLog) << "All stream handlers done";
_streamInfoTimer.stop();
emit autoStreamChanged();
emit _vehicle->dynamicCameras()->streamChanged();
}
}
//-----------------------------------------------------------------------------
void
QGCCameraControl::handleVideoStatus(const mavlink_video_stream_status_t* vs)
{
_streamStatusTimer.stop();
qCDebug(CameraControlLog) << "handleVideoStatus:" << vs->stream_id;
QGCVideoStreamInfo* pInfo = _findStream(vs->stream_id);
if(pInfo) {
if(pInfo->update(vs)) {
emit _vehicle->dynamicCameras()->streamChanged();
}
}
}
//-----------------------------------------------------------------------------
void
QGCCameraControl::setCurrentStream(int stream)
{
if(stream != _currentStream && stream >= 0 && stream < _streams.count()) {
if(_currentStream != stream) {
QGCVideoStreamInfo* pInfo = currentStreamInstance();
if(pInfo) {
//-- Stop current stream
_vehicle->sendMavCommand(
_compID, // Target component
MAV_CMD_VIDEO_STOP_STREAMING, // Command id
false, // ShowError
pInfo->streamID()); // Stream ID
}
_currentStream = stream;
pInfo = currentStreamInstance();
if(pInfo) {
//-- Start new stream
_vehicle->sendMavCommand(
_compID, // Target component
MAV_CMD_VIDEO_START_STREAMING, // Command id
false, // ShowError
pInfo->streamID()); // Stream ID
//-- Update stream status
_requestStreamStatus(static_cast<uint8_t>(pInfo->streamID()));
}
emit currentStreamChanged();
emit _vehicle->dynamicCameras()->streamChanged();
}
}
}
//-----------------------------------------------------------------------------
void
QGCCameraControl::stopStream()
{
QGCVideoStreamInfo* pInfo = currentStreamInstance();
if(pInfo) {
//-- Stop current stream
_vehicle->sendMavCommand(
_compID, // Target component
MAV_CMD_VIDEO_STOP_STREAMING, // Command id
false, // ShowError
pInfo->streamID()); // Stream ID
}
}
//-----------------------------------------------------------------------------
void
QGCCameraControl::resumeStream()
{
QGCVideoStreamInfo* pInfo = currentStreamInstance();
if(pInfo) {
//-- Start new stream
_vehicle->sendMavCommand(
_compID, // Target component
MAV_CMD_VIDEO_START_STREAMING, // Command id
false, // ShowError
pInfo->streamID()); // Stream ID
}
}
//-----------------------------------------------------------------------------
bool
QGCCameraControl::autoStream()
{
if(hasVideoStream()) {
return _streams.count() > 0;
}
return false;
}
//-----------------------------------------------------------------------------
QGCVideoStreamInfo*
QGCCameraControl::currentStreamInstance()
{
if(_currentStream < _streams.count() && _streams.count()) {
QGCVideoStreamInfo* pStream = qobject_cast<QGCVideoStreamInfo*>(_streams[_currentStream]);
return pStream;
}
return nullptr;
}
//-----------------------------------------------------------------------------
void
QGCCameraControl::_requestStreamInfo(uint8_t streamID)
{
qCDebug(CameraControlLog) << "Requesting video stream info for:" << streamID;
_vehicle->sendMavCommand(
_compID, // Target component
MAV_CMD_REQUEST_VIDEO_STREAM_INFORMATION, // Command id
false, // ShowError
streamID); // Stream ID
}
//-----------------------------------------------------------------------------
void
QGCCameraControl::_requestStreamStatus(uint8_t streamID)
{
qCDebug(CameraControlLog) << "Requesting video stream status for:" << streamID;
_vehicle->sendMavCommand(
_compID, // Target component
MAV_CMD_REQUEST_VIDEO_STREAM_STATUS, // Command id
false, // ShowError
streamID); // Stream ID
_streamStatusTimer.start(1000); // Wait up to a second for it
}
//-----------------------------------------------------------------------------
QGCVideoStreamInfo*
QGCCameraControl::_findStream(uint8_t id)
{
for(int i = 0; i < _streams.count(); i++) {
if(_streams[i]) {
QGCVideoStreamInfo* pStream = qobject_cast<QGCVideoStreamInfo*>(_streams[i]);
if(pStream) {
if(pStream->streamID() == id) {
return pStream;
}
} else {
qCritical() << "Null QGCVideoStreamInfo instance";
}
}
}
qWarning() << "Stream id not found:" << id;
return nullptr;
}
//-----------------------------------------------------------------------------
void
QGCCameraControl::_streamTimeout()
{
_requestCount++;
int count = _expectedCount * 3;
if(_requestCount > count) {
qCWarning(CameraControlLog) << "Giving up requesting video stream info";
_streamInfoTimer.stop();
//-- If we have at least one stream, work with what we have.
if(_streams.count()) {
emit autoStreamChanged();
emit _vehicle->dynamicCameras()->streamChanged();
}
return;
}
for(uint8_t i = 0; i < _expectedCount; i++) {
//-- Stream ID starts at 1
if(!_findStream(i+1)) {
_requestStreamInfo(i+1);
return;
}
}
}
//-----------------------------------------------------------------------------
void
QGCCameraControl::_streamStatusTimeout()
{
QGCVideoStreamInfo* pStream = currentStreamInstance();
if(pStream) {
_requestStreamStatus(static_cast<uint8_t>(pStream->streamID()));
}
}
//-----------------------------------------------------------------------------
QStringList
QGCCameraControl::_loadExclusions(QDomNode option)
......@@ -1672,6 +1919,23 @@ QGCCameraControl::_paramDone()
//-- All parameters loaded (or timed out)
_paramComplete = true;
emit parametersReady();
//-- Check for video streaming
_checkForVideoStreams();
}
//-----------------------------------------------------------------------------
void
QGCCameraControl::_checkForVideoStreams()
{
if(_info.flags & CAMERA_CAP_FLAGS_HAS_VIDEO_STREAM) {
connect(&_streamInfoTimer, &QTimer::timeout, this, &QGCCameraControl::_streamTimeout);
_streamInfoTimer.setSingleShot(false);
connect(&_streamStatusTimer, &QTimer::timeout, this, &QGCCameraControl::_streamStatusTimeout);
_streamStatusTimer.setSingleShot(true);
//-- Request all streams
_requestStreamInfo(0);
_streamInfoTimer.start(2000);
}
}
//-----------------------------------------------------------------------------
......@@ -1741,3 +2005,66 @@ QGCCameraControl::wb()
{
return (_paramComplete && _activeSettings.contains(kCAM_WBMODE)) ? getFact(kCAM_WBMODE) : nullptr;
}
//-----------------------------------------------------------------------------
Fact*
QGCCameraControl::mode()
{
return _paramComplete ? getFact(kCAM_MODE) : nullptr;
}
//-----------------------------------------------------------------------------
QGCVideoStreamInfo::QGCVideoStreamInfo(QObject* parent, const mavlink_video_stream_information_t *si)
: QObject(parent)
{
memcpy(&_streamInfo, si, sizeof(mavlink_video_stream_information_t));
}
//-----------------------------------------------------------------------------
qreal
QGCVideoStreamInfo::aspectRatio()
{
if(_streamInfo.resolution_h && _streamInfo.resolution_v) {
return static_cast<double>(_streamInfo.resolution_h) / static_cast<double>(_streamInfo.resolution_v);
}
return 1.0;
}
//-----------------------------------------------------------------------------
bool
QGCVideoStreamInfo::update(const mavlink_video_stream_status_t* vs)
{
bool changed = false;
if(_streamInfo.hfov != vs->hfov) {
changed = true;
_streamInfo.hfov = vs->hfov;
}
if(_streamInfo.flags != vs->flags) {
changed = true;
_streamInfo.flags = vs->flags;
}
if(_streamInfo.bitrate != vs->bitrate) {
changed = true;
_streamInfo.bitrate = vs->bitrate;
}
if(_streamInfo.rotation != vs->rotation) {
changed = true;
_streamInfo.rotation = vs->rotation;
}
if(_streamInfo.framerate != vs->framerate) {
changed = true;
_streamInfo.framerate = vs->framerate;
}
if(_streamInfo.resolution_h != vs->resolution_h) {
changed = true;
_streamInfo.resolution_h = vs->resolution_h;
}
if(_streamInfo.resolution_v != vs->resolution_v) {
changed = true;
_streamInfo.resolution_v = vs->resolution_v;
}
if(changed) {
emit infoChanged();
}
return changed;
}
......@@ -17,6 +17,36 @@ class QGCCameraParamIO;
Q_DECLARE_LOGGING_CATEGORY(CameraControlLog)
Q_DECLARE_LOGGING_CATEGORY(CameraControlLogVerbose)
//-----------------------------------------------------------------------------
class QGCVideoStreamInfo : public QObject
{
Q_OBJECT
public:
QGCVideoStreamInfo(QObject* parent, const mavlink_video_stream_information_t* si);
Q_PROPERTY(QString uri READ uri NOTIFY infoChanged)
Q_PROPERTY(int streamID READ streamID NOTIFY infoChanged)
Q_PROPERTY(int type READ type NOTIFY infoChanged)
Q_PROPERTY(qreal aspectRatio READ aspectRatio NOTIFY infoChanged)
Q_PROPERTY(qreal hfov READ hfov NOTIFY infoChanged)
Q_PROPERTY(bool isThermal READ isThermal NOTIFY infoChanged)
QString uri () { return QString(_streamInfo.uri); }
qreal aspectRatio ();
qreal hfov () { return _streamInfo.hfov; }
int type () { return _streamInfo.type; }
int streamID () { return _streamInfo.stream_id; }
bool isThermal () { return _streamInfo.flags & VIDEO_STREAM_STATUS_FLAGS_THERMAL; }
bool update (const mavlink_video_stream_status_t* vs);
signals:
void infoChanged ();
private:
mavlink_video_stream_information_t _streamInfo;
};
//-----------------------------------------------------------------------------
class QGCCameraOptionExclusion : public QObject
{
......@@ -99,6 +129,7 @@ public:
Q_PROPERTY(bool hasModes READ hasModes NOTIFY infoChanged)
Q_PROPERTY(bool hasZoom READ hasZoom NOTIFY infoChanged)
Q_PROPERTY(bool hasFocus READ hasFocus NOTIFY infoChanged)
Q_PROPERTY(bool hasVideoStream READ hasVideoStream NOTIFY infoChanged)
Q_PROPERTY(bool photosInVideoMode READ photosInVideoMode NOTIFY infoChanged)
Q_PROPERTY(bool videoInPhotoMode READ videoInPhotoMode NOTIFY infoChanged)
Q_PROPERTY(bool isBasic READ isBasic NOTIFY infoChanged)
......@@ -116,6 +147,7 @@ public:
Q_PROPERTY(Fact* shutter READ shutter NOTIFY parametersReady)
Q_PROPERTY(Fact* aperture READ aperture NOTIFY parametersReady)
Q_PROPERTY(Fact* wb READ wb NOTIFY parametersReady)
Q_PROPERTY(Fact* mode READ mode NOTIFY parametersReady)
Q_PROPERTY(QStringList activeSettings READ activeSettings NOTIFY activeSettingsChanged)
Q_PROPERTY(VideoStatus videoStatus READ videoStatus NOTIFY videoStatusChanged)
......@@ -124,6 +156,12 @@ public:
Q_PROPERTY(qreal photoLapse READ photoLapse WRITE setPhotoLapse NOTIFY photoLapseChanged)
Q_PROPERTY(int photoLapseCount READ photoLapseCount WRITE setPhotoLapseCount NOTIFY photoLapseCountChanged)
Q_PROPERTY(PhotoMode photoMode READ photoMode WRITE setPhotoMode NOTIFY photoModeChanged)
Q_PROPERTY(int currentStream READ currentStream WRITE setCurrentStream NOTIFY currentStreamChanged)
Q_PROPERTY(bool autoStream READ autoStream NOTIFY autoStreamChanged)
Q_PROPERTY(QmlObjectListModel* streams READ streams NOTIFY streamsChanged)
Q_PROPERTY(QGCVideoStreamInfo* currentStreamInstance READ currentStreamInstance NOTIFY currentStreamChanged)
Q_PROPERTY(quint32 recordTime READ recordTime NOTIFY recordTimeChanged)
Q_PROPERTY(QString recordTimeStr READ recordTimeStr NOTIFY recordTimeChanged)
Q_INVOKABLE virtual void setVideoMode ();
Q_INVOKABLE virtual void setPhotoMode ();
......@@ -138,6 +176,8 @@ public:
Q_INVOKABLE virtual void stepZoom (int direction);
Q_INVOKABLE virtual void startZoom (int direction);
Q_INVOKABLE virtual void stopZoom ();
Q_INVOKABLE virtual void stopStream ();
Q_INVOKABLE virtual void resumeStream ();
virtual int version () { return _version; }
virtual QString modelName () { return _modelName; }
......@@ -151,6 +191,7 @@ public:
virtual bool hasModes () { return _info.flags & CAMERA_CAP_FLAGS_HAS_MODES; }
virtual bool hasZoom () { return _info.flags & CAMERA_CAP_FLAGS_HAS_BASIC_ZOOM; }
virtual bool hasFocus () { return _info.flags & CAMERA_CAP_FLAGS_HAS_BASIC_FOCUS; }
virtual bool hasVideoStream () { return _info.flags & CAMERA_CAP_FLAGS_HAS_VIDEO_STREAM; }
virtual bool photosInVideoMode () { return _info.flags & CAMERA_CAP_FLAGS_CAN_CAPTURE_IMAGE_IN_VIDEO_MODE; }
virtual bool videoInPhotoMode () { return _info.flags & CAMERA_CAP_FLAGS_CAN_CAPTURE_VIDEO_IN_IMAGE_MODE; }
......@@ -170,12 +211,21 @@ public:
virtual qreal zoomLevel () { return _zoomLevel; }
virtual qreal focusLevel () { return _focusLevel; }
virtual QmlObjectListModel* streams () { return &_streams; }
virtual QGCVideoStreamInfo* currentStreamInstance();
virtual int currentStream () { return _currentStream; }
virtual void setCurrentStream (int stream);
virtual bool autoStream ();
virtual quint32 recordTime () { return _recordTime; }
virtual QString recordTimeStr ();
virtual Fact* exposureMode ();
virtual Fact* ev ();
virtual Fact* iso ();
virtual Fact* shutter ();
virtual Fact* aperture ();
virtual Fact* wb ();
virtual Fact* mode ();
virtual void setZoomLevel (qreal level);
virtual void setFocusLevel (qreal level);
......@@ -189,6 +239,8 @@ public:
virtual void handleParamAck (const mavlink_param_ext_ack_t& ack);
virtual void handleParamValue (const mavlink_param_ext_value_t& value);
virtual void handleStorageInfo (const mavlink_storage_information_t& st);
virtual void handleVideoInfo (const mavlink_video_stream_information_t *vi);
virtual void handleVideoStatus (const mavlink_video_stream_status_t *vs);
//-- Notify controller a parameter has changed
virtual void factChanged (Fact* pFact);
......@@ -212,11 +264,18 @@ signals:
void parametersReady ();
void zoomLevelChanged ();
void focusLevelChanged ();
void streamsChanged ();
void currentStreamChanged ();
void autoStreamChanged ();
void recordTimeChanged ();
protected:
virtual void _setVideoStatus (VideoStatus status);
virtual void _setPhotoStatus (PhotoStatus status);
virtual void _setCameraMode (CameraMode mode);
virtual void _requestStreamInfo (uint8_t streamID);
virtual void _requestStreamStatus (uint8_t streamID);
virtual QGCVideoStreamInfo* _findStream (uint8_t streamID);
protected slots:
virtual void _initWhenReady ();
......@@ -229,7 +288,10 @@ protected slots:
virtual void _mavCommandResult (int vehicleId, int component, int command, int result, bool noReponseFromVehicle);
virtual void _dataReady (QByteArray data);
virtual void _paramDone ();
virtual void _streamTimeout ();
virtual void _streamStatusTimeout ();
virtual void _recTimerHandler ();
virtual void _checkForVideoStreams ();
private:
bool _handleLocalization (QByteArray& bytes);
......@@ -252,26 +314,26 @@ private:
QString _getParamName (const char* param_id);
protected:
Vehicle* _vehicle;
int _compID;
Vehicle* _vehicle = nullptr;
int _compID = 0;
mavlink_camera_information_t _info;
int _version;
bool _cached;
bool _paramComplete;
qreal _zoomLevel;
qreal _focusLevel;
uint32_t _storageFree;
uint32_t _storageTotal;
QNetworkAccessManager* _netManager;
int _version = 0;
bool _cached = false;
bool _paramComplete = false;
qreal _zoomLevel = 0.0;
qreal _focusLevel = 0.0;
uint32_t _storageFree = 0;
uint32_t _storageTotal = 0;
QNetworkAccessManager* _netManager = nullptr;
QString _modelName;
QString _vendor;
QString _cacheFile;
CameraMode _cameraMode;
PhotoMode _photoMode;
qreal _photoLapse;
int _photoLapseCount;
VideoStatus _video_status;
PhotoStatus _photo_status;
CameraMode _cameraMode = CAM_MODE_UNDEFINED;
PhotoMode _photoMode = PHOTO_CAPTURE_SINGLE;
qreal _photoLapse = 1.0;
int _photoLapseCount = 0;
VideoStatus _video_status = VIDEO_CAPTURE_STATUS_UNDEFINED;
PhotoStatus _photo_status = PHOTO_CAPTURE_STATUS_UNDEFINED;
QStringList _activeSettings;
QStringList _settings;
QTimer _captureStatusTimer;
......@@ -280,10 +342,20 @@ protected:
QMap<QString, QStringList> _originalOptNames;
QMap<QString, QVariantList> _originalOptValues;
QMap<QString, QGCCameraParamIO*> _paramIO;
int _storageInfoRetries;
int _captureInfoRetries;
bool _resetting;
int _storageInfoRetries = 0;
int _captureInfoRetries = 0;
bool _resetting = false;
QTimer _recTimer;
QTime _recTime;
uint32_t _recordTime = 0;
//-- Parameters that require a full update
QMap<QString, QStringList> _requestUpdates;
QStringList _updatesToRequest;
//-- Video Streams
int _requestCount = 0;
int _currentStream = 0;
int _expectedCount = 1;
QTimer _streamInfoTimer;
QTimer _streamStatusTimer;
QmlObjectListModel _streams;
};
......@@ -11,6 +11,12 @@
QGC_LOGGING_CATEGORY(CameraManagerLog, "CameraManagerLog")
//-----------------------------------------------------------------------------
QGCCameraManager::CameraStruct::CameraStruct(QObject* parent)
: QObject(parent)
{
}
//-----------------------------------------------------------------------------
QGCCameraManager::QGCCameraManager(Vehicle *vehicle)
: _vehicle(vehicle)
......@@ -19,8 +25,11 @@ QGCCameraManager::QGCCameraManager(Vehicle *vehicle)
qCDebug(CameraManagerLog) << "QGCCameraManager Created";
connect(qgcApp()->toolbox()->multiVehicleManager(), &MultiVehicleManager::parameterReadyVehicleAvailableChanged, this, &QGCCameraManager::_vehicleReady);
connect(_vehicle, &Vehicle::mavlinkMessageReceived, this, &QGCCameraManager::_mavlinkMessageReceived);
connect(&_cameraTimer, &QTimer::timeout, this, &QGCCameraManager::_cameraTimeout);
_cameraTimer.setSingleShot(false);
_lastZoomChange.start();
_lastCameraChange.start();
_cameraTimer.start(500);
}
//-----------------------------------------------------------------------------
......@@ -35,6 +44,7 @@ QGCCameraManager::setCurrentCamera(int sel)
if(sel != _currentCamera && sel >= 0 && sel < _cameras.count()) {
_currentCamera = sel;
emit currentCameraChanged();
emit streamChanged();
}
}
......@@ -80,6 +90,12 @@ QGCCameraManager::_mavlinkMessageReceived(const mavlink_message_t& message)
case MAVLINK_MSG_ID_PARAM_EXT_VALUE:
_handleParamValue(message);
break;
case MAVLINK_MSG_ID_VIDEO_STREAM_INFORMATION:
_handleVideoStreamInfo(message);
break;
case MAVLINK_MSG_ID_VIDEO_STREAM_STATUS:
_handleVideoStreamStatus(message);
break;
}
}
}
......@@ -90,16 +106,63 @@ QGCCameraManager::_handleHeartbeat(const mavlink_message_t &message)
{
mavlink_heartbeat_t heartbeat;
mavlink_msg_heartbeat_decode(&message, &heartbeat);
//-- If this heartbeat is from a different node within the vehicle
//-- If this heartbeat is from a different component within the vehicle
if(_vehicleReadyState && _vehicle->id() == message.sysid && _vehicle->defaultComponentId() != message.compid) {
if(!_cameraInfoRequested.contains(message.compid)) {
_cameraInfoRequested[message.compid] = true;
//-- First time hearing from this one?
if(!_cameraInfoRequest.contains(message.compid)) {
CameraStruct* pInfo = new CameraStruct(this);
pInfo->lastHeartbeat.start();
_cameraInfoRequest[message.compid] = pInfo;
//-- Request camera info
_requestCameraInfo(message.compid);
} else {
//-- Check if we have indeed received the camera info
if(_cameraInfoRequest[message.compid]->infoReceived) {
//-- We have it. Just update the heartbeat timeout
_cameraInfoRequest[message.compid]->lastHeartbeat.start();
} else {
//-- Try again. Maybe.
if(_cameraInfoRequest[message.compid]->lastHeartbeat.elapsed() > 2000) {
if(_cameraInfoRequest[message.compid]->tryCount > 3) {
if(!_cameraInfoRequest[message.compid]->gaveUp) {
_cameraInfoRequest[message.compid]->gaveUp = true;
qWarning() << "Giving up requesting camera info from" << _vehicle->id() << message.compid;
}
} else {
_cameraInfoRequest[message.compid]->tryCount++;
//-- Request camera info. Again. It could be something other than a camera, in which
// case, we won't ever receive it.
_requestCameraInfo(message.compid);
}
}
}
}
}
}
//-----------------------------------------------------------------------------
QGCCameraControl*
QGCCameraManager::currentCameraInstance()
{
if(_currentCamera < _cameras.count() && _cameras.count()) {
QGCCameraControl* pCamera = qobject_cast<QGCCameraControl*>(_cameras[_currentCamera]);
return pCamera;
}
return nullptr;
}
//-----------------------------------------------------------------------------
QGCVideoStreamInfo*
QGCCameraManager::currentStreamInstance()
{
QGCCameraControl* pCamera = currentCameraInstance();
if(pCamera) {
QGCVideoStreamInfo* pInfo = pCamera->currentStreamInstance();
return pInfo;
}
return nullptr;
}
//-----------------------------------------------------------------------------
QGCCameraControl*
QGCCameraManager::_findCamera(int id)
......@@ -125,9 +188,9 @@ void
QGCCameraManager::_handleCameraInfo(const mavlink_message_t& message)
{
//-- Have we requested it?
if(_cameraInfoRequested.contains(message.compid) && _cameraInfoRequested[message.compid]) {
if(_cameraInfoRequest.contains(message.compid) && !_cameraInfoRequest[message.compid]->infoReceived) {
//-- Flag it as done
_cameraInfoRequested[message.compid] = false;
_cameraInfoRequest[message.compid]->infoReceived = true;
mavlink_camera_information_t info;
mavlink_msg_camera_information_decode(&message, &info);
qCDebug(CameraManagerLog) << "_handleCameraInfo:" << reinterpret_cast<const char*>(info.model_name) << reinterpret_cast<const char*>(info.vendor_name) << "Comp ID:" << message.compid;
......@@ -142,6 +205,51 @@ QGCCameraManager::_handleCameraInfo(const mavlink_message_t& message)
}
}
//-----------------------------------------------------------------------------
void
QGCCameraManager::_cameraTimeout()
{
//-- Iterate cameras
for(int i = 0; i < _cameraInfoRequest.count(); i++) {
if(_cameraInfoRequest[i]) {
//-- Have we received a camera info message?
if(_cameraInfoRequest[i]->infoReceived) {
//-- Has the camera stopped talking to us?
if(_cameraInfoRequest[i]->lastHeartbeat.elapsed() > 5000) {
//-- Camera is gone. Remove it.
QGCCameraControl* pCamera = _findCamera(i);
qWarning() << "Camera" << pCamera->modelName() << "stopped transmitting. Removing from list.";
int idx = _cameraLabels.indexOf(pCamera->modelName());
if(idx >= 0) {
_cameraLabels.removeAt(idx);
}
idx = _cameras.indexOf(pCamera);
if(idx >= 0) {
_cameras.removeAt(idx);
}
bool autoStream = pCamera->autoStream();
pCamera->deleteLater();
delete _cameraInfoRequest[i];
_cameraInfoRequest.remove(i);
emit cameraLabelsChanged();
//-- If we have another camera, switch current camera.
if(_cameras.count()) {
setCurrentCamera(0);
} else {
//-- We're out of cameras
emit camerasChanged();
if(autoStream) {
emit streamChanged();
}
}
//-- Exit loop.
return;
}
}
}
}
}
//-----------------------------------------------------------------------------
void
QGCCameraManager::_handleCaptureStatus(const mavlink_message_t &message)
......@@ -202,6 +310,30 @@ QGCCameraManager::_handleParamValue(const mavlink_message_t& message)
}
}
//-----------------------------------------------------------------------------
void
QGCCameraManager::_handleVideoStreamInfo(const mavlink_message_t& message)
{
QGCCameraControl* pCamera = _findCamera(message.compid);
if(pCamera) {
mavlink_video_stream_information_t streamInfo;
mavlink_msg_video_stream_information_decode(&message, &streamInfo);
pCamera->handleVideoInfo(&streamInfo);
}
}
//-----------------------------------------------------------------------------
void
QGCCameraManager::_handleVideoStreamStatus(const mavlink_message_t& message)
{
QGCCameraControl* pCamera = _findCamera(message.compid);
if(pCamera) {
mavlink_video_stream_status_t streamStatus;
mavlink_msg_video_stream_status_decode(&message, &streamStatus);
pCamera->handleVideoStatus(&streamStatus);
}
}
//-----------------------------------------------------------------------------
void
QGCCameraManager::_requestCameraInfo(int compID)
......@@ -224,11 +356,13 @@ QGCCameraManager::_activeJoystickChanged(Joystick* joystick)
if(_activeJoystick) {
disconnect(_activeJoystick, &Joystick::stepZoom, this, &QGCCameraManager::_stepZoom);
disconnect(_activeJoystick, &Joystick::stepCamera, this, &QGCCameraManager::_stepCamera);
disconnect(_activeJoystick, &Joystick::stepStream, this, &QGCCameraManager::_stepStream);
}
_activeJoystick = joystick;
if(_activeJoystick) {
connect(_activeJoystick, &Joystick::stepZoom, this, &QGCCameraManager::_stepZoom);
connect(_activeJoystick, &Joystick::stepCamera, this, &QGCCameraManager::_stepCamera);
connect(_activeJoystick, &Joystick::stepStream, this, &QGCCameraManager::_stepStream);
}
}
......@@ -239,11 +373,9 @@ QGCCameraManager::_stepZoom(int direction)
if(_lastZoomChange.elapsed() > 250) {
_lastZoomChange.start();
qCDebug(CameraManagerLog) << "Step Camera Zoom" << direction;
if(_cameras.count() && _cameras[_currentCamera]) {
QGCCameraControl* pCamera = qobject_cast<QGCCameraControl*>(_cameras[_currentCamera]);
if(pCamera) {
pCamera->stepZoom(direction);
}
QGCCameraControl* pCamera = currentCameraInstance();
if(pCamera) {
pCamera->stepZoom(direction);
}
}
}
......@@ -262,4 +394,21 @@ QGCCameraManager::_stepCamera(int direction)
}
}
//-----------------------------------------------------------------------------
void
QGCCameraManager::_stepStream(int direction)
{
if(_lastCameraChange.elapsed() > 1000) {
_lastCameraChange.start();
QGCCameraControl* pCamera = currentCameraInstance();
if(pCamera) {
qCDebug(CameraManagerLog) << "Step Camera Stream" << direction;
int c = pCamera->currentStream() + direction;
if(c < 0) c = pCamera->streams()->count() - 1;
if(c >= pCamera->streams()->count()) c = 0;
pCamera->setCurrentStream(c);
}
}
}
......@@ -27,9 +27,10 @@ public:
QGCCameraManager(Vehicle* vehicle);
virtual ~QGCCameraManager();
Q_PROPERTY(QmlObjectListModel* cameras READ cameras NOTIFY camerasChanged)
Q_PROPERTY(QStringList cameraLabels READ cameraLabels NOTIFY cameraLabelsChanged)
Q_PROPERTY(int currentCamera READ currentCamera WRITE setCurrentCamera NOTIFY currentCameraChanged)
Q_PROPERTY(QmlObjectListModel* cameras READ cameras NOTIFY camerasChanged)
Q_PROPERTY(QStringList cameraLabels READ cameraLabels NOTIFY cameraLabelsChanged)
Q_PROPERTY(QGCCameraControl* currentCameraInstance READ currentCameraInstance NOTIFY currentCameraChanged)
Q_PROPERTY(int currentCamera READ currentCamera WRITE setCurrentCamera NOTIFY currentCameraChanged)
//-- Return a list of cameras provided by this vehicle
virtual QmlObjectListModel* cameras () { return &_cameras; }
......@@ -37,13 +38,17 @@ public:
virtual QStringList cameraLabels () { return _cameraLabels; }
//-- Current selected camera
virtual int currentCamera () { return _currentCamera; }
virtual QGCCameraControl* currentCameraInstance();
//-- Set current camera
virtual void setCurrentCamera (int sel);
//-- Current stream
virtual QGCVideoStreamInfo* currentStreamInstance();
signals:
void camerasChanged ();
void cameraLabelsChanged ();
void currentCameraChanged ();
void streamChanged ();
protected slots:
virtual void _vehicleReady (bool ready);
......@@ -51,6 +56,8 @@ protected slots:
virtual void _activeJoystickChanged (Joystick* joystick);
virtual void _stepZoom (int direction);
virtual void _stepCamera (int direction);
virtual void _stepStream (int direction);
virtual void _cameraTimeout ();
protected:
virtual QGCCameraControl* _findCamera (int id);
......@@ -62,16 +69,29 @@ protected:
virtual void _handleParamAck (const mavlink_message_t& message);
virtual void _handleParamValue (const mavlink_message_t& message);
virtual void _handleCaptureStatus (const mavlink_message_t& message);
virtual void _handleVideoStreamInfo (const mavlink_message_t& message);
virtual void _handleVideoStreamStatus(const mavlink_message_t& message);
protected:
class CameraStruct : public QObject {
public:
CameraStruct(QObject* parent);
QTime lastHeartbeat;
bool infoReceived = false;
bool gaveUp = false;
int tryCount = 0;
};
Vehicle* _vehicle = nullptr;
Joystick* _activeJoystick = nullptr;
bool _vehicleReadyState = false;
int _currentTask = 0;
QmlObjectListModel _cameras;
QStringList _cameraLabels;
QMap<int, bool> _cameraInfoRequested;
int _currentCamera = 0;
QTime _lastZoomChange;
QTime _lastCameraChange;
QTimer _cameraTimer;
QMap<int, CameraStruct*> _cameraInfoRequest;
};
......@@ -31,9 +31,7 @@ Item {
property int _curCameraIndex: _dynamicCameras ? _dynamicCameras.currentCamera : 0
property bool _isCamera: _dynamicCameras ? _dynamicCameras.cameras.count > 0 : false
property var _camera: _isCamera ? _dynamicCameras.cameras.get(_curCameraIndex) : null
property bool _hasCameraZoom: _camera && _camera.hasZoom
property bool _hasVideoZoom: QGroundControl.videoManager.hasZoom
property bool _hasZoom: _hasCameraZoom || _hasVideoZoom
property bool _hasZoom: _camera && _camera.hasZoom
property int _fitMode: QGroundControl.settingsManager.videoSettings.videoFit.rawValue
Rectangle {
id: noVideo
......@@ -141,13 +139,7 @@ Item {
z = Math.round(pinch.scale)
}
if(pinchZoom.zoom != z) {
//-- Camera zoom takes predence
if(_hasCameraZoom) {
_camera.stepZoom(z)
} else if (_hasVideoZoom) {
//-- Video zoom is for dumb cameras that only stream (do not present a camera interface)
QGroundControl.videoManager.stepZoom(z)
}
_camera.stepZoom(z)
}
}
}
......
......@@ -28,7 +28,7 @@
#include "MultiVehicleManager.h"
#include "Settings/SettingsManager.h"
#include "Vehicle.h"
#include "JoystickManager.h"
#include "QGCCameraManager.h"
QGC_LOGGING_CATEGORY(VideoManagerLog, "VideoManagerLog")
......@@ -36,9 +36,6 @@ QGC_LOGGING_CATEGORY(VideoManagerLog, "VideoManagerLog")
VideoManager::VideoManager(QGCApplication* app, QGCToolbox* toolbox)
: QGCTool(app, toolbox)
{
_streamInfo = {};
_lastZoomChange.start();
_lastStreamChange.start();
}
//-----------------------------------------------------------------------------
......@@ -64,11 +61,9 @@ VideoManager::setToolbox(QGCToolbox *toolbox)
connect(_videoSettings->udpPort(), &Fact::rawValueChanged, this, &VideoManager::_udpPortChanged);
connect(_videoSettings->rtspUrl(), &Fact::rawValueChanged, this, &VideoManager::_rtspUrlChanged);
connect(_videoSettings->tcpUrl(), &Fact::rawValueChanged, this, &VideoManager::_tcpUrlChanged);
connect(_videoSettings->aspectRatio(), &Fact::rawValueChanged, this, &VideoManager::_streamInfoChanged);
connect(_videoSettings->aspectRatio(), &Fact::rawValueChanged, this, &VideoManager::_aspectRatioChanged);
MultiVehicleManager *pVehicleMgr = qgcApp()->toolbox()->multiVehicleManager();
connect(pVehicleMgr, &MultiVehicleManager::activeVehicleChanged, this, &VideoManager::_setActiveVehicle);
JoystickManager *pJoyMgr = qgcApp()->toolbox()->joystickManager();
connect(pJoyMgr, &JoystickManager::activeJoystickChanged, this, &VideoManager::_activeJoystickChanged);
#if defined(QGC_GST_STREAMING)
#ifndef QGC_DISABLE_UVC
......@@ -92,14 +87,26 @@ VideoManager::setToolbox(QGCToolbox *toolbox)
//-----------------------------------------------------------------------------
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);
if(_activeVehicle && _activeVehicle->dynamicCameras()) {
QGCVideoStreamInfo* pInfo = _activeVehicle->dynamicCameras()->currentStreamInstance();
if(pInfo) {
return pInfo->aspectRatio();
}
}
return _videoSettings->aspectRatio()->rawValue().toDouble();
}
//-----------------------------------------------------------------------------
bool
VideoManager::autoStreamConfigured()
{
if(_activeVehicle && _activeVehicle->dynamicCameras()) {
QGCVideoStreamInfo* pInfo = _activeVehicle->dynamicCameras()->currentStreamInstance();
if(pInfo) {
return !pInfo->uri().isEmpty();
}
return 1.0;
} else {
return _videoSettings->aspectRatio()->rawValue().toDouble();
}
return false;
}
//-----------------------------------------------------------------------------
......@@ -156,6 +163,9 @@ VideoManager::_tcpUrlChanged()
bool
VideoManager::hasVideo()
{
if(autoStreamConfigured()) {
return true;
}
QString videoSource = _videoSettings->videoSource()->rawValue().toString();
return !videoSource.isEmpty() && videoSource != VideoSettings::videoSourceNoVideo && videoSource != VideoSettings::videoDisabled;
}
......@@ -169,21 +179,9 @@ VideoManager::isGStreamer()
return
videoSource == VideoSettings::videoSourceUDP ||
videoSource == VideoSettings::videoSourceRTSP ||
videoSource == VideoSettings::videoSourceAuto ||
videoSource == VideoSettings::videoSourceTCP ||
videoSource == VideoSettings::videoSourceMPEGTS;
#else
return false;
#endif
}
//-----------------------------------------------------------------------------
bool
VideoManager::isAutoStream()
{
#if defined(QGC_GST_STREAMING)
QString videoSource = _videoSettings->videoSource()->rawValue().toString();
return videoSource == VideoSettings::videoSourceAuto;
videoSource == VideoSettings::videoSourceMPEGTS ||
autoStreamConfigured();
#else
return false;
#endif
......@@ -204,6 +202,28 @@ VideoManager::_updateSettings()
{
if(!_videoSettings || !_videoReceiver)
return;
//-- Auto discovery
if(_activeVehicle && _activeVehicle->dynamicCameras()) {
QGCVideoStreamInfo* pInfo = _activeVehicle->dynamicCameras()->currentStreamInstance();
if(pInfo) {
switch(pInfo->type()) {
case VIDEO_STREAM_TYPE_RTSP:
case VIDEO_STREAM_TYPE_TCP_MPEG:
_videoReceiver->setUri(pInfo->uri());
break;
case VIDEO_STREAM_TYPE_RTPUDP:
_videoReceiver->setUri(QStringLiteral("udp://0.0.0.0:%1").arg(pInfo->uri()));
break;
case VIDEO_STREAM_TYPE_MPEG_TS_H264:
_videoReceiver->setUri(QStringLiteral("mpegts://0.0.0.0:%1").arg(pInfo->uri()));
break;
default:
_videoReceiver->setUri(pInfo->uri());
break;
}
return;
}
}
QString source = _videoSettings->videoSource()->rawValue().toString();
if (source == VideoSettings::videoSourceUDP)
_videoReceiver->setUri(QStringLiteral("udp://0.0.0.0:%1").arg(_videoSettings->udpPort()->rawValue().toInt()));
......@@ -213,24 +233,6 @@ VideoManager::_updateSettings()
_videoReceiver->setUri(_videoSettings->rtspUrl()->rawValue().toString());
else if (source == VideoSettings::videoSourceTCP)
_videoReceiver->setUri(QStringLiteral("tcp://%1").arg(_videoSettings->tcpUrl()->rawValue().toString()));
//-- 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;
}
}
}
//-----------------------------------------------------------------------------
......@@ -252,116 +254,31 @@ void
VideoManager::_setActiveVehicle(Vehicle* vehicle)
{
if(_activeVehicle) {
disconnect(_activeVehicle, &Vehicle::mavlinkMessageReceived, this, &VideoManager::_vehicleMessageReceived);
if(_activeVehicle->dynamicCameras()) {
QGCCameraControl* pCamera = _activeVehicle->dynamicCameras()->currentCameraInstance();
if(pCamera) {
pCamera->stopStream();
}
disconnect(_activeVehicle->dynamicCameras(), &QGCCameraManager::streamChanged, this, &VideoManager::_restartVideo);
}
}
_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
1); // Request video stream information
}
}
//----------------------------------------------------------------------------------------
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) {
_videoStreamCompID = message.compid;
mavlink_msg_video_stream_information_decode(&message, &_streamInfo);
_hasAutoStream = true;
qCDebug(VideoManagerLog) << "Received video stream info:" << _streamInfo.uri;
_restartVideo();
emit streamInfoChanged();
}
}
//----------------------------------------------------------------------------------------
void
VideoManager::_activeJoystickChanged(Joystick* joystick)
{
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();
if(_activeVehicle->dynamicCameras()) {
connect(_activeVehicle->dynamicCameras(), &QGCCameraManager::streamChanged, this, &VideoManager::_restartVideo);
QGCCameraControl* pCamera = _activeVehicle->dynamicCameras()->currentCameraInstance();
if(pCamera) {
pCamera->resumeStream();
}
}
}
emit autoStreamConfiguredChanged();
_restartVideo();
}
//----------------------------------------------------------------------------------------
void
VideoManager::_streamInfoChanged()
VideoManager::_aspectRatioChanged()
{
emit streamInfoChanged();
emit aspectRatioChanged();
}
......@@ -35,18 +35,15 @@ public:
VideoManager (QGCApplication* app, QGCToolbox* toolbox);
~VideoManager ();
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 streamInfoChanged)
Q_PROPERTY(bool hasZoom READ hasZoom NOTIFY streamInfoChanged)
Q_PROPERTY(int streamCount READ streamCount NOTIFY streamCountChanged)
Q_PROPERTY(int currentStream READ currentStream WRITE setCurrentStream NOTIFY currentStreamChanged)
Q_PROPERTY(bool hasVideo READ hasVideo NOTIFY hasVideoChanged)
Q_PROPERTY(bool isGStreamer READ isGStreamer NOTIFY isGStreamerChanged)
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)
Q_PROPERTY(bool autoStreamConfigured READ autoStreamConfigured NOTIFY autoStreamConfiguredChanged)
bool hasVideo ();
bool isGStreamer ();
......@@ -54,11 +51,8 @@ public:
bool isTaisync () { return _isTaisync; }
bool fullScreen () { return _fullScreen; }
QString videoSourceID () { return _videoSourceID; }
QString autoURL () { return QString(_streamInfo.uri); }
double aspectRatio ();
bool hasZoom () { return _streamInfo.flags & VIDEO_STREAM_HAS_BASIC_ZOOM; }
int currentStream () { return _currentStream; }
int streamCount () { return _streamInfo.count; }
bool autoStreamConfigured();
VideoReceiver* videoReceiver () { return _videoReceiver; }
......@@ -70,15 +64,12 @@ public:
void setfullScreen (bool f) { _fullScreen = f; emit fullScreenChanged(); }
void setIsTaisync (bool t) { _isTaisync = t; emit isTaisyncChanged(); }
void setCurrentStream (int stream);
// Override from QGCTool
void setToolbox (QGCToolbox *toolbox);
Q_INVOKABLE void startVideo () { _videoReceiver->start(); }
Q_INVOKABLE void stopVideo () { _videoReceiver->stop(); }
Q_INVOKABLE void stepZoom (int direction);
Q_INVOKABLE void stepStream (int direction);
signals:
void hasVideoChanged ();
......@@ -86,10 +77,9 @@ signals:
void videoSourceIDChanged ();
void fullScreenChanged ();
void isAutoStreamChanged ();
void streamInfoChanged ();
void isTaisyncChanged ();
void currentStreamChanged ();
void streamCountChanged ();
void aspectRatioChanged ();
void autoStreamConfiguredChanged();
private slots:
void _videoSourceChanged ();
......@@ -97,14 +87,12 @@ private slots:
void _rtspUrlChanged ();
void _tcpUrlChanged ();
void _updateUVC ();
void _streamInfoChanged ();
void _setActiveVehicle (Vehicle* vehicle);
void _activeJoystickChanged (Joystick* joystick);
void _vehicleMessageReceived (const mavlink_message_t& message);
void _aspectRatioChanged ();
void _restartVideo ();
private:
void _updateSettings ();
void _restartVideo ();
private:
bool _isTaisync = false;
......@@ -113,13 +101,6 @@ private:
QString _videoSourceID;
bool _fullScreen = false;
Vehicle* _activeVehicle = nullptr;
Joystick* _activeJoystick = nullptr;
mavlink_video_stream_information_t _streamInfo;
bool _hasAutoStream = false;
uint8_t _videoStreamCompID = 0;
int _currentStream = 1;
QTime _lastZoomChange;
QTime _lastStreamChange;
};
#endif
......@@ -414,6 +414,7 @@ void QGCApplication::_initCommon(void)
qmlRegisterUncreatableType<ParameterManager> (kQGCVehicle, 1, 0, "ParameterManager", kRefOnly);
qmlRegisterUncreatableType<QGCCameraManager> (kQGCVehicle, 1, 0, "QGCCameraManager", kRefOnly);
qmlRegisterUncreatableType<QGCCameraControl> (kQGCVehicle, 1, 0, "QGCCameraControl", kRefOnly);
qmlRegisterUncreatableType<QGCVideoStreamInfo> (kQGCVehicle, 1, 0, "QGCVideoStreamInfo", kRefOnly);
qmlRegisterUncreatableType<LinkInterface> (kQGCVehicle, 1, 0, "LinkInterface", kRefOnly);
qmlRegisterUncreatableType<MissionController> (kQGCControllers, 1, 0, "MissionController", kRefOnly);
qmlRegisterUncreatableType<GeoFenceController> (kQGCControllers, 1, 0, "GeoFenceController", kRefOnly);
......
......@@ -21,7 +21,6 @@
const char* VideoSettings::videoSourceNoVideo = "No Video Available";
const char* VideoSettings::videoDisabled = "Video Stream Disabled";
const char* VideoSettings::videoSourceAuto = "Automatic Video Stream";
const char* VideoSettings::videoSourceRTSP = "RTSP Video Stream";
const char* VideoSettings::videoSourceUDP = "UDP Video Stream";
const char* VideoSettings::videoSourceTCP = "TCP-MPEG2 Video Stream";
......@@ -35,7 +34,6 @@ DECLARE_SETTINGGROUP(Video, "Video")
// Setup enum values for videoSource settings into meta data
QStringList videoSourceList;
#ifdef QGC_GST_STREAMING
videoSourceList.append(videoSourceAuto);
videoSourceList.append(videoSourceRTSP);
#ifndef NO_UDP_VIDEO
videoSourceList.append(videoSourceUDP);
......@@ -133,10 +131,16 @@ bool VideoSettings::streamConfigured(void)
#if !defined(QGC_GST_STREAMING)
return false;
#endif
//-- First, check if it's disabled
QString vSource = videoSource()->rawValue().toString();
if(vSource == videoSourceNoVideo || vSource == videoDisabled) {
return false;
}
//-- Check if it's autoconfigured
if(qgcApp()->toolbox()->videoManager()->autoStreamConfigured()) {
qCDebug(VideoManagerLog) << "Stream auto configured";
return true;
}
//-- If UDP, check if port is set
if(vSource == videoSourceUDP) {
qCDebug(VideoManagerLog) << "Testing configuration for UDP Stream:" << udpPort()->rawValue().toInt();
......@@ -157,11 +161,6 @@ bool VideoSettings::streamConfigured(void)
qCDebug(VideoManagerLog) << "Testing configuration for MPEG-TS Stream:" << udpPort()->rawValue().toInt();
return udpPort()->rawValue().toInt() != 0;
}
//-- 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;
}
......
......@@ -36,14 +36,12 @@ public:
DEFINE_SETTINGFACT(disableWhenDisarmed)
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)
Q_PROPERTY(QString mpegtsVideoSource READ mpegtsVideoSource CONSTANT)
bool streamConfigured ();
QString autoVideoSource () { return videoSourceAuto; }
QString rtspVideoSource () { return videoSourceRTSP; }
QString udpVideoSource () { return videoSourceUDP; }
QString tcpVideoSource () { return videoSourceTCP; }
......@@ -53,7 +51,6 @@ public:
static const char* videoDisabled;
static const char* videoSourceUDP;
static const char* videoSourceRTSP;
static const char* videoSourceAuto;
static const char* videoSourceTCP;
static const char* videoSourceMPEGTS;
......
......@@ -47,7 +47,6 @@ QGCView {
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
......@@ -691,7 +690,7 @@ QGCView {
QGCLabel {
id: videoSectionLabel
text: qsTr("Video")
visible: QGroundControl.settingsManager.videoSettings.visible
visible: QGroundControl.settingsManager.videoSettings.visible && !QGroundControl.videoManager.autoStreamConfigured
}
Rectangle {
Layout.preferredWidth: videoGrid.width + (_margins * 2)
......@@ -751,12 +750,12 @@ QGCView {
}
QGCLabel {
text: qsTr("Aspect Ratio")
visible: !_isAutoStream && _isGst && QGroundControl.settingsManager.videoSettings.aspectRatio.visible
visible: _isGst && QGroundControl.settingsManager.videoSettings.aspectRatio.visible
}
FactTextField {
Layout.preferredWidth: _comboFieldWidth
fact: QGroundControl.settingsManager.videoSettings.aspectRatio
visible: !_isAutoStream && _isGst && QGroundControl.settingsManager.videoSettings.aspectRatio.visible
visible: _isGst && QGroundControl.settingsManager.videoSettings.aspectRatio.visible
}
QGCLabel {
......@@ -776,10 +775,10 @@ QGCView {
QGCLabel {
id: videoRecSectionLabel
text: qsTr("Video Recording")
visible: QGroundControl.settingsManager.videoSettings.visible && _isGst
visible: (QGroundControl.settingsManager.videoSettings.visible && _isGst) || QGroundControl.videoManager.autoStreamConfigured
}
Rectangle {
Layout.preferredWidth: videoRecCol.width + (_margins * 2)
Layout.preferredWidth: videoRecCol.width + (_margins * 2)
Layout.preferredHeight: videoRecCol.height + (_margins * 2)
Layout.fillWidth: true
color: qgcPal.windowShade
......
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