diff --git a/src/Settings/VideoSettings.cc b/src/Settings/VideoSettings.cc index 453f37f..8ade41d 100644 --- a/src/Settings/VideoSettings.cc +++ b/src/Settings/VideoSettings.cc @@ -29,6 +29,8 @@ const char* VideoSettings::videoSourceMPEGTS = QT_TRANSLATE_NOOP("Vid const char* VideoSettings::videoSource3DRSolo = QT_TRANSLATE_NOOP("VideoSettings", "3DR Solo (requires restart)"); const char* VideoSettings::videoSourceParrotDiscovery = QT_TRANSLATE_NOOP("VideoSettings", "Parrot Discovery"); const char* VideoSettings::videoSourceYuneecMantisG = QT_TRANSLATE_NOOP("VideoSettings", "Yuneec Mantis G"); +const char* VideoSettings::videoSourceHerelinkAirUnit = QT_TRANSLATE_NOOP("VideoSettings", "Herelink AirUnit"); +const char* VideoSettings::videoSourceHerelinkHotspot = QT_TRANSLATE_NOOP("VideoSettings", "Herelink Hotspot"); DECLARE_SETTINGGROUP(Video, "Video") { @@ -48,6 +50,13 @@ DECLARE_SETTINGGROUP(Video, "Video") videoSourceList.append(videoSourceParrotDiscovery); videoSourceList.append(videoSourceYuneecMantisG); #endif + +#ifdef QGC_HERELINK_AIRUNIT_VIDEO + videoSourceList.append(videoSourceHerelinkAirUnit); +#else + videoSourceList.append(videoSourceHerelinkHotspot); +#endif + #ifndef QGC_DISABLE_UVC QList cameras = QCameraInfo::availableCameras(); for (const QCameraInfo &cameraInfo: cameras) { diff --git a/src/Settings/VideoSettings.h b/src/Settings/VideoSettings.h index 3a2bd5e..f947577 100644 --- a/src/Settings/VideoSettings.h +++ b/src/Settings/VideoSettings.h @@ -73,6 +73,8 @@ public: static const char* videoSource3DRSolo; static const char* videoSourceParrotDiscovery; static const char* videoSourceYuneecMantisG; + static const char* videoSourceHerelinkAirUnit; + static const char* videoSourceHerelinkHotspot; signals: void streamConfiguredChanged (bool configured); diff --git a/src/VideoManager/VideoManager.cc b/src/VideoManager/VideoManager.cc index cca88f1..fd6d90a 100644 --- a/src/VideoManager/VideoManager.cc +++ b/src/VideoManager/VideoManager.cc @@ -565,6 +565,8 @@ VideoManager::isGStreamer() videoSource == VideoSettings::videoSource3DRSolo || videoSource == VideoSettings::videoSourceParrotDiscovery || videoSource == VideoSettings::videoSourceYuneecMantisG || + videoSource == VideoSettings::videoSourceHerelinkAirUnit || + videoSource == VideoSettings::videoSourceHerelinkHotspot || autoStreamConfigured(); #else return false; @@ -741,6 +743,10 @@ VideoManager::_updateSettings(unsigned id) settingsChanged |= _updateVideoUri(0, QStringLiteral("udp://0.0.0.0:8888")); else if (source == VideoSettings::videoSourceYuneecMantisG) settingsChanged |= _updateVideoUri(0, QStringLiteral("rtsp://192.168.42.1:554/live")); + else if (source == VideoSettings::videoSourceHerelinkAirUnit) + settingsChanged |= _updateVideoUri(0, QStringLiteral("rtsp://192.168.0.10:8554/H264Video")); + else if (source == VideoSettings::videoSourceHerelinkHotspot) + settingsChanged |= _updateVideoUri(0, QStringLiteral("rtsp://192.168.43.1:8554/fpv_stream")); else if (source == VideoSettings::videoDisabled || source == VideoSettings::videoSourceNoVideo) settingsChanged |= _updateVideoUri(0, ""); else {