From 7a05c933819383da976488e7a409060d5ec25df9 Mon Sep 17 00:00:00 2001
From: Gus Grubba <gus@auterion.com>
Date: Wed, 27 Mar 2019 16:59:56 -0400
Subject: [PATCH 1/3] CP - Video Stream Names

---
 src/Camera/QGCCameraControl.cc | 10 ++++++++--
 src/Camera/QGCCameraControl.h  | 10 +++++++++-
 2 files changed, 17 insertions(+), 3 deletions(-)

diff --git a/src/Camera/QGCCameraControl.cc b/src/Camera/QGCCameraControl.cc
index 8ba5927..0cd9e6a 100644
--- a/src/Camera/QGCCameraControl.cc
+++ b/src/Camera/QGCCameraControl.cc
@@ -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;
 }
 
 //-----------------------------------------------------------------------------
diff --git a/src/Camera/QGCCameraControl.h b/src/Camera/QGCCameraControl.h
index 8e06b63..2ea4532 100644
--- a/src/Camera/QGCCameraControl.h
+++ b/src/Camera/QGCCameraControl.h
@@ -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;
 };

From 87f82d25ee7428e060dbdebb3a4ac6825ff51afc Mon Sep 17 00:00:00 2001
From: Gus Grubba <gus@auterion.com>
Date: Wed, 27 Mar 2019 17:00:24 -0400
Subject: [PATCH 2/3] CP - Update aspect ratio when changing video streams

---
 src/FlightDisplay/VideoManager.cc | 1 +
 1 file changed, 1 insertion(+)

diff --git a/src/FlightDisplay/VideoManager.cc b/src/FlightDisplay/VideoManager.cc
index 3f24911..bd2d7fa 100644
--- a/src/FlightDisplay/VideoManager.cc
+++ b/src/FlightDisplay/VideoManager.cc
@@ -246,6 +246,7 @@ VideoManager::_restartVideo()
     _videoReceiver->stop();
     _updateSettings();
     _videoReceiver->start();
+    emit aspectRatioChanged();
 #endif
 }
 

From 1d6b056033bc8b08405c5ac49010edfd13e9cb4c Mon Sep 17 00:00:00 2001
From: Gus Grubba <gus@auterion.com>
Date: Thu, 28 Mar 2019 12:05:53 -0400
Subject: [PATCH 3/3] Add stream selector

---
 src/FlightMap/Widgets/CameraPageWidget.qml | 20 ++++++++++++++++++++
 1 file changed, 20 insertions(+)

diff --git a/src/FlightMap/Widgets/CameraPageWidget.qml b/src/FlightMap/Widgets/CameraPageWidget.qml
index 50a564f..dc65ed3 100644
--- a/src/FlightMap/Widgets/CameraPageWidget.qml
+++ b/src/FlightMap/Widgets/CameraPageWidget.qml
@@ -203,6 +203,8 @@ Column {
                     anchors.left:   parent.left
                     anchors.right:  parent.right
                     spacing:        _margins
+                    //-------------------------------------------
+                    //-- Camera Selector
                     Row {
                         visible:    _isCamera
                         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
                     Repeater {
                         model:      _camera ? _camera.activeSettings : []