Skip to content
Open
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
32 changes: 32 additions & 0 deletions custom/herelink/VideoStreamControl.cc
Original file line number Diff line number Diff line change
Expand Up @@ -26,9 +26,11 @@ VideoStreamControl::VideoStreamControl()
_resolutionSwitchPending = false;
_currentHdmiInput = 0; // Default to HDMI 1
_currentResolution = 1; // Default to 1080p
_currentActiveSource = _videoSettings->herelinkActiveSource()->rawValue().toUInt();

connect(_videoSettings->cameraId(), &Fact::rawValueChanged, this, &VideoStreamControl::_cameraIdChanged);
connect(_videoSettings->resolution(), &Fact::rawValueChanged, this, &VideoStreamControl::_resolutionChanged);
connect(_videoSettings->herelinkActiveSource(), &Fact::rawValueChanged, this, &VideoStreamControl::_activeSourceChanged);
//connect(&_infoRequestTimer, &QTimer::timeout, this, &VideoStreamControl::_requestVideoStreamInfo);
//_infoRequestTimer.setInterval(1000);
}
Expand Down Expand Up @@ -61,6 +63,36 @@ void VideoStreamControl::_cameraIdChanged()
_setCameraIdLockUi(true);
}

void VideoStreamControl::_activeSourceChanged()
{
uint32_t source = _videoSettings->herelinkActiveSource()->rawValue().toUInt();
qCDebug(VideoStreamControlLog) << "Active source changed to:" << source
<< "(0=HDMI1, 1=HDMI2, 2=RTSP1, 3=RTSP2)";

if (source == _currentActiveSource) {
return;
}
_currentActiveSource = source;
emit currentActiveSourceChanged();

if (source < 2) {
// HDMI 1 or HDMI 2 — drive the existing cameraId path
uint32_t newCameraId = source;
if (newCameraId != _videoSettings->cameraId()->rawValue().toUInt()) {
// Cascades to _cameraIdChanged → _setCameraIdLockUi which sends VIDEO_START_STREAMING
_videoSettings->cameraId()->setRawValue(newCameraId);
} else {
// Coming back from RTSP with the same HDMI as before — cameraId hasn't changed
// so _cameraIdChanged won't fire. Re-send VIDEO_START_STREAMING in case the
// air unit's stream stopped while we were on RTSP.
_startVideoStreaming();
}
} else {
// RTSP 1 or RTSP 2 — VideoManager handles the URI swap based on herelinkActiveSource.
qCDebug(VideoStreamControlLog) << "RTSP source selected, no MAVLink HDMI command sent";
}
}

void VideoStreamControl::_requestVideoStreamInfo()
{
if (_linkInterface == NULL) {
Expand Down
6 changes: 6 additions & 0 deletions custom/herelink/VideoStreamControl.h
Original file line number Diff line number Diff line change
Expand Up @@ -28,17 +28,22 @@ class VideoStreamControl : public QObject
Q_PROPERTY(uint8_t currentResolution READ currentResolution NOTIFY currentResolutionChanged)
uint8_t currentResolution() { return _currentResolution; }

Q_PROPERTY(uint8_t currentActiveSource READ currentActiveSource NOTIFY currentActiveSourceChanged)
uint8_t currentActiveSource() { return _currentActiveSource; }

signals:
void settingInProgressChanged();
void videoNeedsReset();
void decodingNeedsRestart(); // Lighter-weight reset: just restart decoder/sink, keep RTSP alive
void currentHdmiInputChanged();
void cameraInfoReceivedChanged();
void currentResolutionChanged();
void currentActiveSourceChanged();

private slots:
void _mavlinkMessageReceived(LinkInterface *link, mavlink_message_t message);
void _cameraIdChanged();
void _activeSourceChanged();
void _resolutionChanged();
void _requestVideoStreamInfo();

Expand All @@ -56,6 +61,7 @@ private slots:
bool _resolutionSwitchPending; // Suppress encoder resets during resolution change
uint8_t _currentHdmiInput;
uint8_t _currentResolution;
uint8_t _currentActiveSource; // 0=HDMI1, 1=HDMI2, 2=RTSP1, 3=RTSP2

void _handleHeartbeatInfo(LinkInterface* link, mavlink_message_t& message);
void _handleVideoStreamInformation(mavlink_message_t& message);
Expand Down
37 changes: 29 additions & 8 deletions src/FlightMap/Widgets/PhotoVideoControl.qml
Original file line number Diff line number Diff line change
Expand Up @@ -375,14 +375,14 @@ Rectangle {
}

QGCLabel {
text: qsTr("HDMI Input")
text: qsTr("Video Source")
visible: QGroundControl.corePlugin.isHerelink
onVisibleChanged: gridLayout.dynamicRows += visible ? 1 : -1
}

QGCLabel {
text: qsTr("Resolution")
visible: QGroundControl.corePlugin.isHerelink
visible: QGroundControl.corePlugin.isHerelink && _videoStreamSettings.herelinkActiveSource.rawValue < 2
onVisibleChanged: gridLayout.dynamicRows += visible ? 1 : -1
}

Expand Down Expand Up @@ -472,27 +472,48 @@ Rectangle {
spacing: ScreenTools.defaultFontPixelWidth / 2
visible: QGroundControl.corePlugin.isHerelink

property var _streamControl: QGroundControl.videoManager.videoStreamControl

QGCButton {
text: qsTr("HDMI 1")
enabled: QGroundControl.videoManager.videoStreamControl.cameraInfoReceived && !QGroundControl.videoManager.videoStreamControl.settingInProgress && QGroundControl.videoManager.videoStreamControl.currentHdmiInput !== 0
visible: _videoStreamSettings.herelinkHdmi1Enabled.rawValue
enabled: parent._streamControl.cameraInfoReceived && !parent._streamControl.settingInProgress && parent._streamControl.currentActiveSource !== 0
onClicked: {
console.log("HDMI 1 button clicked")
_videoStreamSettings.cameraId.rawValue = 0
_videoStreamSettings.herelinkActiveSource.rawValue = 0
}
}

QGCButton {
text: qsTr("HDMI 2")
enabled: QGroundControl.videoManager.videoStreamControl.cameraInfoReceived && !QGroundControl.videoManager.videoStreamControl.settingInProgress && QGroundControl.videoManager.videoStreamControl.currentHdmiInput !== 1
visible: _videoStreamSettings.herelinkHdmi2Enabled.rawValue
enabled: parent._streamControl.cameraInfoReceived && !parent._streamControl.settingInProgress && parent._streamControl.currentActiveSource !== 1
onClicked: {
_videoStreamSettings.herelinkActiveSource.rawValue = 1
}
}

QGCButton {
text: qsTr("RTSP 1")
visible: _videoStreamSettings.herelinkRtsp1Url.rawValue.length > 0
enabled: parent._streamControl.currentActiveSource !== 2
onClicked: {
_videoStreamSettings.cameraId.rawValue = 1
_videoStreamSettings.herelinkActiveSource.rawValue = 2
}
}

QGCButton {
text: qsTr("RTSP 2")
visible: _videoStreamSettings.herelinkRtsp2Url.rawValue.length > 0
enabled: parent._streamControl.currentActiveSource !== 3
onClicked: {
_videoStreamSettings.herelinkActiveSource.rawValue = 3
}
}
}

Row {
spacing: ScreenTools.defaultFontPixelWidth / 2
visible: QGroundControl.corePlugin.isHerelink
visible: QGroundControl.corePlugin.isHerelink && _videoStreamSettings.herelinkActiveSource.rawValue < 2

QGCComboBox {
model: [ qsTr("720p"), qsTr("1080p") ]
Expand Down
37 changes: 37 additions & 0 deletions src/Settings/Video.SettingsGroup.json
Original file line number Diff line number Diff line change
Expand Up @@ -151,6 +151,43 @@
"enumStrings": "720p,1080p",
"enumValues": "0,1",
"default": 1
},
{
"name": "herelinkHdmi1Enabled",
"shortDesc": "Enable HDMI 1 source",
"longDesc": "When enabled, the HDMI 1 button is available in the camera config dialog.",
"type": "bool",
"default": true
},
{
"name": "herelinkHdmi2Enabled",
"shortDesc": "Enable HDMI 2 source",
"longDesc": "When enabled, the HDMI 2 button is available in the camera config dialog.",
"type": "bool",
"default": true
},
{
"name": "herelinkRtsp1Url",
"shortDesc": "RTSP 1 URL",
"longDesc": "RTSP URL for the RTSP 1 source. Leave empty to hide the RTSP 1 button. Example: rtsp://10.0.0.5:554/stream",
"type": "string",
"default": ""
},
{
"name": "herelinkRtsp2Url",
"shortDesc": "RTSP 2 URL",
"longDesc": "RTSP URL for the RTSP 2 source. Leave empty to hide the RTSP 2 button. Example: rtsp://10.0.0.6:554/stream",
"type": "string",
"default": ""
},
{
"name": "herelinkActiveSource",
"shortDesc": "Active video source",
"longDesc": "Currently selected video source: 0=HDMI 1, 1=HDMI 2, 2=RTSP 1, 3=RTSP 2.",
"type": "uint32",
"enumStrings": "HDMI 1,HDMI 2,RTSP 1,RTSP 2",
"enumValues": "0,1,2,3",
"default": 0
}
]
}
6 changes: 6 additions & 0 deletions src/Settings/VideoSettings.cc
Original file line number Diff line number Diff line change
Expand Up @@ -96,6 +96,12 @@ DECLARE_SETTINGSFACT(VideoSettings, disableWhenDisarmed)
DECLARE_SETTINGSFACT(VideoSettings, cameraId)
// Herelink resolution switching
DECLARE_SETTINGSFACT(VideoSettings, resolution)
// Herelink multi-source (HDMI 1/2 + RTSP 1/2) switching
DECLARE_SETTINGSFACT(VideoSettings, herelinkHdmi1Enabled)
DECLARE_SETTINGSFACT(VideoSettings, herelinkHdmi2Enabled)
DECLARE_SETTINGSFACT(VideoSettings, herelinkRtsp1Url)
DECLARE_SETTINGSFACT(VideoSettings, herelinkRtsp2Url)
DECLARE_SETTINGSFACT(VideoSettings, herelinkActiveSource)

DECLARE_SETTINGSFACT_NO_FUNC(VideoSettings, videoSource)
{
Expand Down
6 changes: 6 additions & 0 deletions src/Settings/VideoSettings.h
Original file line number Diff line number Diff line change
Expand Up @@ -39,6 +39,12 @@ class VideoSettings : public SettingsGroup
DEFINE_SETTINGFACT(cameraId)
// Herelink resolution switching
DEFINE_SETTINGFACT(resolution)
// Herelink multi-source (HDMI 1/2 + RTSP 1/2) switching
DEFINE_SETTINGFACT(herelinkHdmi1Enabled)
DEFINE_SETTINGFACT(herelinkHdmi2Enabled)
DEFINE_SETTINGFACT(herelinkRtsp1Url)
DEFINE_SETTINGFACT(herelinkRtsp2Url)
DEFINE_SETTINGFACT(herelinkActiveSource)

Q_PROPERTY(bool streamConfigured READ streamConfigured NOTIFY streamConfiguredChanged)
Q_PROPERTY(QString rtspVideoSource READ rtspVideoSource CONSTANT)
Expand Down
32 changes: 32 additions & 0 deletions src/UI/AppSettings/VideoSettings.qml
Original file line number Diff line number Diff line change
Expand Up @@ -80,6 +80,38 @@ SettingsPage {
}
}

SettingsGroupLayout {
Layout.fillWidth: true
heading: qsTr("Herelink Sources")
visible: QGroundControl.corePlugin.isHerelink

FactCheckBoxSlider {
Layout.fillWidth: true
text: qsTr("HDMI 1")
fact: _videoSettings.herelinkHdmi1Enabled
}

FactCheckBoxSlider {
Layout.fillWidth: true
text: qsTr("HDMI 2")
fact: _videoSettings.herelinkHdmi2Enabled
}

LabelledFactTextField {
Layout.fillWidth: true
textFieldPreferredWidth: _urlFieldWidth
label: qsTr("RTSP 1 URL")
fact: _videoSettings.herelinkRtsp1Url
}

LabelledFactTextField {
Layout.fillWidth: true
textFieldPreferredWidth: _urlFieldWidth
label: qsTr("RTSP 2 URL")
fact: _videoSettings.herelinkRtsp2Url
}
}

SettingsGroupLayout {
Layout.fillWidth: true
heading: qsTr("Settings")
Expand Down
23 changes: 22 additions & 1 deletion src/VideoManager/VideoManager.cc
Original file line number Diff line number Diff line change
Expand Up @@ -108,6 +108,9 @@ void VideoManager::init(QQuickWindow *window)
(void) connect(_videoSettings->udpUrl(), &Fact::rawValueChanged, this, &VideoManager::_videoSourceChanged);
(void) connect(_videoSettings->rtspUrl(), &Fact::rawValueChanged, this, &VideoManager::_videoSourceChanged);
(void) connect(_videoSettings->tcpUrl(), &Fact::rawValueChanged, this, &VideoManager::_videoSourceChanged);
(void) connect(_videoSettings->herelinkActiveSource(), &Fact::rawValueChanged, this, &VideoManager::_videoSourceChanged);
(void) connect(_videoSettings->herelinkRtsp1Url(), &Fact::rawValueChanged, this, &VideoManager::_videoSourceChanged);
(void) connect(_videoSettings->herelinkRtsp2Url(), &Fact::rawValueChanged, this, &VideoManager::_videoSourceChanged);
(void) connect(_videoSettings->aspectRatio(), &Fact::rawValueChanged, this, &VideoManager::aspectRatioChanged);
(void) connect(_videoSettings->lowLatencyMode(), &Fact::rawValueChanged, this, [this](const QVariant &value) { Q_UNUSED(value); _restartAllVideos(); });
(void) connect(MultiVehicleManager::instance(), &MultiVehicleManager::activeVehicleChanged, this, &VideoManager::_setActiveVehicle);
Expand Down Expand Up @@ -552,7 +555,25 @@ bool VideoManager::_updateSettings(VideoReceiver *receiver)
} else if (source == VideoSettings::videoSourceYuneecMantisG) {
settingsChanged |= _updateVideoUri(receiver, QStringLiteral("rtsp://192.168.42.1:554/live"));
} else if (source == VideoSettings::videoSourceHerelinkAirUnit) {
settingsChanged |= _updateVideoUri(receiver, QStringLiteral("rtsp://192.168.0.10:8554/H264Video"));
QString uri;
const uint32_t activeSource = _videoSettings->herelinkActiveSource()->rawValue().toUInt();
switch (activeSource) {
case 0:
case 1:
// HDMI 1 / HDMI 2 — Air Unit multiplexes the chosen HDMI into this fixed RTSP URL
uri = QStringLiteral("rtsp://192.168.0.10:8554/H264Video");
break;
case 2:
uri = _videoSettings->herelinkRtsp1Url()->rawValue().toString();
break;
case 3:
uri = _videoSettings->herelinkRtsp2Url()->rawValue().toString();
break;
default:
uri = QStringLiteral("rtsp://192.168.0.10:8554/H264Video");
break;
}
settingsChanged |= _updateVideoUri(receiver, uri);
} else if (source == VideoSettings::videoSourceHerelinkHotspot) {
settingsChanged |= _updateVideoUri(receiver, QStringLiteral("rtsp://192.168.43.1:8554/fpv_stream"));
} else if ((source == VideoSettings::videoDisabled) || (source == VideoSettings::videoSourceNoVideo)) {
Expand Down
Loading