Browse Source

Merge pull request #7329 from mavlink/multipleStreams

Multiple Video Streams
QGC4.4
Gus Grubba 6 years ago committed by GitHub
parent
commit
d93be01ada
No known key found for this signature in database
GPG Key ID: 4AEE18F83AFDEB23
  1. 10
      src/Camera/QGCCameraControl.cc
  2. 10
      src/Camera/QGCCameraControl.h
  3. 1
      src/FlightDisplay/VideoManager.cc
  4. 20
      src/FlightMap/Widgets/CameraPageWidget.qml

10
src/Camera/QGCCameraControl.cc

@ -1496,7 +1496,10 @@ QGCCameraControl::handleVideoInfo(const mavlink_video_stream_information_t* vi)
QGCVideoStreamInfo* pStream = new QGCVideoStreamInfo(this, vi); QGCVideoStreamInfo* pStream = new QGCVideoStreamInfo(this, vi);
QQmlEngine::setObjectOwnership(pStream, QQmlEngine::CppOwnership); QQmlEngine::setObjectOwnership(pStream, QQmlEngine::CppOwnership);
_streams.append(pStream); _streams.append(pStream);
_streamLabels.append(pStream->name());
emit streamsChanged(); emit streamsChanged();
emit streamLabelsChanged();
qDebug() << _streamLabels;
} }
//-- Check for missing count //-- Check for missing count
if(_streams.count() < _expectedCount) { if(_streams.count() < _expectedCount) {
@ -1532,6 +1535,7 @@ QGCCameraControl::setCurrentStream(int stream)
if(_currentStream != stream) { if(_currentStream != stream) {
QGCVideoStreamInfo* pInfo = currentStreamInstance(); QGCVideoStreamInfo* pInfo = currentStreamInstance();
if(pInfo) { if(pInfo) {
qCDebug(CameraControlLog) << "Stopping stream:" << pInfo->uri();
//-- Stop current stream //-- Stop current stream
_vehicle->sendMavCommand( _vehicle->sendMavCommand(
_compID, // Target component _compID, // Target component
@ -1543,6 +1547,7 @@ QGCCameraControl::setCurrentStream(int stream)
pInfo = currentStreamInstance(); pInfo = currentStreamInstance();
if(pInfo) { if(pInfo) {
//-- Start new stream //-- Start new stream
qCDebug(CameraControlLog) << "Starting stream:" << pInfo->uri();
_vehicle->sendMavCommand( _vehicle->sendMavCommand(
_compID, // Target component _compID, // Target component
MAV_CMD_VIDEO_START_STREAMING, // Command id MAV_CMD_VIDEO_START_STREAMING, // Command id
@ -2034,10 +2039,11 @@ QGCVideoStreamInfo::QGCVideoStreamInfo(QObject* parent, const mavlink_video_stre
qreal qreal
QGCVideoStreamInfo::aspectRatio() QGCVideoStreamInfo::aspectRatio()
{ {
qreal ar = 1.0;
if(_streamInfo.resolution_h && _streamInfo.resolution_v) { 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;
} }
//----------------------------------------------------------------------------- //-----------------------------------------------------------------------------

10
src/Camera/QGCCameraControl.h

@ -25,13 +25,15 @@ public:
QGCVideoStreamInfo(QObject* parent, const mavlink_video_stream_information_t* si); QGCVideoStreamInfo(QObject* parent, const mavlink_video_stream_information_t* si);
Q_PROPERTY(QString uri READ uri NOTIFY infoChanged) 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 streamID READ streamID NOTIFY infoChanged)
Q_PROPERTY(int type READ type NOTIFY infoChanged) Q_PROPERTY(int type READ type NOTIFY infoChanged)
Q_PROPERTY(qreal aspectRatio READ aspectRatio NOTIFY infoChanged) Q_PROPERTY(qreal aspectRatio READ aspectRatio NOTIFY infoChanged)
Q_PROPERTY(qreal hfov READ hfov NOTIFY infoChanged) Q_PROPERTY(qreal hfov READ hfov NOTIFY infoChanged)
Q_PROPERTY(bool isThermal READ isThermal 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 aspectRatio ();
qreal hfov () { return _streamInfo.hfov; } qreal hfov () { return _streamInfo.hfov; }
int type () { return _streamInfo.type; } int type () { return _streamInfo.type; }
@ -162,6 +164,7 @@ public:
Q_PROPERTY(QGCVideoStreamInfo* currentStreamInstance READ currentStreamInstance NOTIFY currentStreamChanged) Q_PROPERTY(QGCVideoStreamInfo* currentStreamInstance READ currentStreamInstance NOTIFY currentStreamChanged)
Q_PROPERTY(quint32 recordTime READ recordTime NOTIFY recordTimeChanged) Q_PROPERTY(quint32 recordTime READ recordTime NOTIFY recordTimeChanged)
Q_PROPERTY(QString recordTimeStr READ recordTimeStr 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 setVideoMode ();
Q_INVOKABLE virtual void setPhotoMode (); Q_INVOKABLE virtual void setPhotoMode ();
@ -227,6 +230,9 @@ public:
virtual Fact* wb (); virtual Fact* wb ();
virtual Fact* mode (); virtual Fact* mode ();
//-- Stream names to show the user (for selection)
virtual QStringList streamLabels () { return _streamLabels; }
virtual void setZoomLevel (qreal level); virtual void setZoomLevel (qreal level);
virtual void setFocusLevel (qreal level); virtual void setFocusLevel (qreal level);
virtual void setCameraMode (CameraMode mode); virtual void setCameraMode (CameraMode mode);
@ -278,6 +284,7 @@ signals:
void currentStreamChanged (); void currentStreamChanged ();
void autoStreamChanged (); void autoStreamChanged ();
void recordTimeChanged (); void recordTimeChanged ();
void streamLabelsChanged ();
protected: protected:
virtual void _setVideoStatus (VideoStatus status); virtual void _setVideoStatus (VideoStatus status);
@ -368,4 +375,5 @@ protected:
QTimer _streamInfoTimer; QTimer _streamInfoTimer;
QTimer _streamStatusTimer; QTimer _streamStatusTimer;
QmlObjectListModel _streams; QmlObjectListModel _streams;
QStringList _streamLabels;
}; };

1
src/FlightDisplay/VideoManager.cc

@ -246,6 +246,7 @@ VideoManager::_restartVideo()
_videoReceiver->stop(); _videoReceiver->stop();
_updateSettings(); _updateSettings();
_videoReceiver->start(); _videoReceiver->start();
emit aspectRatioChanged();
#endif #endif
} }

20
src/FlightMap/Widgets/CameraPageWidget.qml

@ -203,6 +203,8 @@ Column {
anchors.left: parent.left anchors.left: parent.left
anchors.right: parent.right anchors.right: parent.right
spacing: _margins spacing: _margins
//-------------------------------------------
//-- Camera Selector
Row { Row {
visible: _isCamera visible: _isCamera
spacing: ScreenTools.defaultFontPixelWidth spacing: ScreenTools.defaultFontPixelWidth
@ -221,6 +223,24 @@ Column {
} }
} }
//------------------------------------------- //-------------------------------------------
//-- Stream Selector
Row {
spacing: ScreenTools.defaultFontPixelWidth
anchors.horizontalCenter: parent.horizontalCenter
QGCLabel {
text: qsTr("Stream Selector:")
width: _labelFieldWidth
anchors.verticalCenter: parent.verticalCenter
}
QGCComboBox {
model: _camera ? _camera.streamLabels : []
width: _editFieldWidth
onActivated: _camera.currentStream = index
currentIndex: _camera ? _camera.currentStream : 0
}
}
//-------------------------------------------
//-- Camera Settings //-- Camera Settings
Repeater { Repeater {
model: _camera ? _camera.activeSettings : [] model: _camera ? _camera.activeSettings : []

Loading…
Cancel
Save