Commit 7a05c933 authored by Gus Grubba's avatar Gus Grubba

CP - Video Stream Names

parent 0f73e53f
......@@ -1496,7 +1496,10 @@ QGCCameraControl::handleVideoInfo(const mavlink_video_stream_information_t* vi)
QGCVideoStreamInfo* pStream = new QGCVideoStreamInfo(this, vi);
QQmlEngine::setObjectOwnership(pStream, QQmlEngine::CppOwnership);
_streams.append(pStream);
_streamLabels.append(pStream->name());
emit streamsChanged();
emit streamLabelsChanged();
qDebug() << _streamLabels;
}
//-- Check for missing count
if(_streams.count() < _expectedCount) {
......@@ -1532,6 +1535,7 @@ QGCCameraControl::setCurrentStream(int stream)
if(_currentStream != stream) {
QGCVideoStreamInfo* pInfo = currentStreamInstance();
if(pInfo) {
qCDebug(CameraControlLog) << "Stopping stream:" << pInfo->uri();
//-- Stop current stream
_vehicle->sendMavCommand(
_compID, // Target component
......@@ -1543,6 +1547,7 @@ QGCCameraControl::setCurrentStream(int stream)
pInfo = currentStreamInstance();
if(pInfo) {
//-- Start new stream
qCDebug(CameraControlLog) << "Starting stream:" << pInfo->uri();
_vehicle->sendMavCommand(
_compID, // Target component
MAV_CMD_VIDEO_START_STREAMING, // Command id
......@@ -2034,10 +2039,11 @@ QGCVideoStreamInfo::QGCVideoStreamInfo(QObject* parent, const mavlink_video_stre
qreal
QGCVideoStreamInfo::aspectRatio()
{
qreal ar = 1.0;
if(_streamInfo.resolution_h && _streamInfo.resolution_v) {
return static_cast<double>(_streamInfo.resolution_h) / static_cast<double>(_streamInfo.resolution_v);
ar = static_cast<double>(_streamInfo.resolution_h) / static_cast<double>(_streamInfo.resolution_v);
}
return 1.0;
return ar;
}
//-----------------------------------------------------------------------------
......
......@@ -25,13 +25,15 @@ public:
QGCVideoStreamInfo(QObject* parent, const mavlink_video_stream_information_t* si);
Q_PROPERTY(QString uri READ uri NOTIFY infoChanged)
Q_PROPERTY(QString name READ name 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); }
QString uri () { return QString(_streamInfo.uri); }
QString name () { return QString(_streamInfo.name); }
qreal aspectRatio ();
qreal hfov () { return _streamInfo.hfov; }
int type () { return _streamInfo.type; }
......@@ -162,6 +164,7 @@ public:
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_PROPERTY(QStringList streamLabels READ streamLabels NOTIFY streamLabelsChanged)
Q_INVOKABLE virtual void setVideoMode ();
Q_INVOKABLE virtual void setPhotoMode ();
......@@ -227,6 +230,9 @@ public:
virtual Fact* wb ();
virtual Fact* mode ();
//-- Stream names to show the user (for selection)
virtual QStringList streamLabels () { return _streamLabels; }
virtual void setZoomLevel (qreal level);
virtual void setFocusLevel (qreal level);
virtual void setCameraMode (CameraMode mode);
......@@ -278,6 +284,7 @@ signals:
void currentStreamChanged ();
void autoStreamChanged ();
void recordTimeChanged ();
void streamLabelsChanged ();
protected:
virtual void _setVideoStatus (VideoStatus status);
......@@ -368,4 +375,5 @@ protected:
QTimer _streamInfoTimer;
QTimer _streamStatusTimer;
QmlObjectListModel _streams;
QStringList _streamLabels;
};
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