diff --git a/src/FlightDisplay/FlightDisplayViewVideo.qml b/src/FlightDisplay/FlightDisplayViewVideo.qml index 0ed7eed06c52d2d51be399a794aa5108e788aa5d..ed59ab671ae69e0ea8de4ba607a9d6a7ea7a6919 100644 --- a/src/FlightDisplay/FlightDisplayViewVideo.qml +++ b/src/FlightDisplay/FlightDisplayViewVideo.qml @@ -22,7 +22,7 @@ import QGroundControl.Controllers 1.0 Item { id: root - property double _ar: QGroundControl.settingsManager.videoSettings.aspectRatio.rawValue + property double _ar: QGroundControl.videoManager.aspectRatio property bool _showGrid: QGroundControl.settingsManager.videoSettings.gridLines.rawValue > 0 property var _videoReceiver: QGroundControl.videoManager.videoReceiver property var _activeVehicle: QGroundControl.multiVehicleManager.activeVehicle diff --git a/src/FlightDisplay/VideoManager.cc b/src/FlightDisplay/VideoManager.cc index f8fd614fb002022dba98379705aa6c446a0e3cdb..889d1dd77208db8161782344c2e2095e2002f214 100644 --- a/src/FlightDisplay/VideoManager.cc +++ b/src/FlightDisplay/VideoManager.cc @@ -25,7 +25,9 @@ #include "QGCToolbox.h" #include "QGCCorePlugin.h" #include "QGCOptions.h" +#include "MultiVehicleManager.h" #include "Settings/SettingsManager.h" +#include "Vehicle.h" QGC_LOGGING_CATEGORY(VideoManagerLog, "VideoManagerLog") @@ -35,6 +37,7 @@ VideoManager::VideoManager(QGCApplication* app, QGCToolbox* toolbox) , _videoReceiver(nullptr) , _videoSettings(nullptr) , _fullScreen(false) + , _activeVehicle(nullptr) { } @@ -61,6 +64,9 @@ VideoManager::setToolbox(QGCToolbox *toolbox) connect(_videoSettings->udpPort(), &Fact::rawValueChanged, this, &VideoManager::_udpPortChanged); connect(_videoSettings->rtspUrl(), &Fact::rawValueChanged, this, &VideoManager::_rtspUrlChanged); connect(_videoSettings->tcpUrl(), &Fact::rawValueChanged, this, &VideoManager::_tcpUrlChanged); + connect(_videoSettings->aspectRatio(), &Fact::rawValueChanged, this, &VideoManager::_aspectRatioChanged); + MultiVehicleManager *manager = qgcApp()->toolbox()->multiVehicleManager(); + connect(manager, &MultiVehicleManager::activeVehicleChanged, this, &VideoManager::_setActiveVehicle); #if defined(QGC_GST_STREAMING) #ifndef QGC_DISABLE_UVC @@ -81,6 +87,19 @@ VideoManager::setToolbox(QGCToolbox *toolbox) #endif } +//----------------------------------------------------------------------------- +double VideoManager::aspectRatio() +{ + if(isAutoStream()) { + if(_streamInfo.resolution_h && _streamInfo.resolution_v) { + return static_cast(_streamInfo.resolution_h) / static_cast(_streamInfo.resolution_v); + } + return 1.0; + } else { + return _videoSettings->aspectRatio()->rawValue().toDouble(); + } +} + //----------------------------------------------------------------------------- void VideoManager::_updateUVC() @@ -106,6 +125,7 @@ VideoManager::_videoSourceChanged() _updateUVC(); emit hasVideoChanged(); emit isGStreamerChanged(); + emit isAutoStreamChanged(); _restartVideo(); } @@ -144,7 +164,23 @@ VideoManager::isGStreamer() { #if defined(QGC_GST_STREAMING) QString videoSource = _videoSettings->videoSource()->rawValue().toString(); - return videoSource == VideoSettings::videoSourceUDP || videoSource == VideoSettings::videoSourceRTSP || videoSource == VideoSettings::videoSourceTCP; + return + videoSource == VideoSettings::videoSourceUDP || + videoSource == VideoSettings::videoSourceRTSP || + videoSource == VideoSettings::videoSourceAuto || + videoSource == VideoSettings::videoSourceTCP; +#else + return false; +#endif +} + +//----------------------------------------------------------------------------- +bool +VideoManager::isAutoStream() +{ +#if defined(QGC_GST_STREAMING) + QString videoSource = _videoSettings->videoSource()->rawValue().toString(); + return videoSource == VideoSettings::videoSourceAuto; #else return false; #endif @@ -171,6 +207,8 @@ VideoManager::_updateSettings() _videoReceiver->setUri(_videoSettings->rtspUrl()->rawValue().toString()); else if (_videoSettings->videoSource()->rawValue().toString() == VideoSettings::videoSourceTCP) _videoReceiver->setUri(QStringLiteral("tcp://%1").arg(_videoSettings->tcpUrl()->rawValue().toString())); + else if (isAutoStream()) + _videoReceiver->setUri(QString(_streamInfo.uri)); } //----------------------------------------------------------------------------- @@ -185,3 +223,45 @@ VideoManager::_restartVideo() _videoReceiver->start(); #endif } + +//---------------------------------------------------------------------------------------- +void +VideoManager::_setActiveVehicle(Vehicle* vehicle) +{ + if(_activeVehicle) { + disconnect(_activeVehicle, &Vehicle::mavlinkMessageReceived, this, &VideoManager::_vehicleMessageReceived); + } + _activeVehicle = vehicle; + if(_activeVehicle) { + if(isAutoStream()) { + _videoReceiver->stop(); + } + //-- Video Stream Discovery + connect(_activeVehicle, &Vehicle::mavlinkMessageReceived, this, &VideoManager::_vehicleMessageReceived); + _activeVehicle->sendMavCommand( + 0, // Target component + MAV_CMD_REQUEST_VIDEO_STREAM_INFORMATION, // Command id + false, // ShowError + 1, // First camera only + 0); // Reserved (Set to 0) + } +} + +//---------------------------------------------------------------------------------------- +void +VideoManager::_vehicleMessageReceived(const mavlink_message_t& message) +{ + //-- For now we only handle one stream. There is no UI to pick different streams. + if(message.msgid == MAVLINK_MSG_ID_VIDEO_STREAM_INFORMATION) { + mavlink_msg_video_stream_information_decode(&message, &_streamInfo); + _restartVideo(); + emit aspectRatioChanged(); + } +} + +//---------------------------------------------------------------------------------------- +void +VideoManager::_aspectRatioChanged() +{ + emit aspectRatioChanged(); +} diff --git a/src/FlightDisplay/VideoManager.h b/src/FlightDisplay/VideoManager.h index 1de729d6c8d2a08be054239e8d42a442d055bce2..648fbeb9d934cf4fba72bbb1b0dd17a646033be8 100644 --- a/src/FlightDisplay/VideoManager.h +++ b/src/FlightDisplay/VideoManager.h @@ -15,6 +15,7 @@ #include #include +#include "QGCMAVLink.h" #include "QGCLoggingCategory.h" #include "VideoReceiver.h" #include "QGCToolbox.h" @@ -22,6 +23,7 @@ Q_DECLARE_LOGGING_CATEGORY(VideoManagerLog) class VideoSettings; +class Vehicle; class VideoManager : public QGCTool { @@ -33,15 +35,20 @@ public: Q_PROPERTY(bool hasVideo READ hasVideo NOTIFY hasVideoChanged) Q_PROPERTY(bool isGStreamer READ isGStreamer NOTIFY isGStreamerChanged) + Q_PROPERTY(bool isAutoStream READ isAutoStream NOTIFY isAutoStreamChanged) Q_PROPERTY(QString videoSourceID READ videoSourceID NOTIFY videoSourceIDChanged) Q_PROPERTY(bool uvcEnabled READ uvcEnabled CONSTANT) Q_PROPERTY(bool fullScreen READ fullScreen WRITE setfullScreen NOTIFY fullScreenChanged) Q_PROPERTY(VideoReceiver* videoReceiver READ videoReceiver CONSTANT) + Q_PROPERTY(double aspectRatio READ aspectRatio NOTIFY aspectRatioChanged) bool hasVideo (); bool isGStreamer (); + bool isAutoStream (); bool fullScreen () { return _fullScreen; } QString videoSourceID () { return _videoSourceID; } + QString autoURL () { return QString(_streamInfo.uri); } + double aspectRatio (); VideoReceiver* videoReceiver () { return _videoReceiver; } @@ -64,6 +71,8 @@ signals: void isGStreamerChanged (); void videoSourceIDChanged (); void fullScreenChanged (); + void isAutoStreamChanged (); + void aspectRatioChanged (); private slots: void _videoSourceChanged (); @@ -71,6 +80,9 @@ private slots: void _rtspUrlChanged (); void _tcpUrlChanged (); void _updateUVC (); + void _aspectRatioChanged (); + void _setActiveVehicle (Vehicle* vehicle); + void _vehicleMessageReceived (const mavlink_message_t& message); private: void _updateSettings (); @@ -80,6 +92,8 @@ private: VideoSettings* _videoSettings; QString _videoSourceID; bool _fullScreen; + Vehicle* _activeVehicle; + mavlink_video_stream_information_t _streamInfo; }; #endif diff --git a/src/Settings/VideoSettings.cc b/src/Settings/VideoSettings.cc index 48430a6895412ebe488867b924e269350dfd4c10..29e9054f06eeb23c1ee8d62b1fb37b93e197e8b3 100644 --- a/src/Settings/VideoSettings.cc +++ b/src/Settings/VideoSettings.cc @@ -8,6 +8,8 @@ ****************************************************************************/ #include "VideoSettings.h" +#include "QGCApplication.h" +#include "VideoManager.h" #include #include @@ -17,14 +19,12 @@ #include #endif -const char* VideoSettings::videoSourceNoVideo = "No Video Available"; -const char* VideoSettings::videoDisabled = "Video Stream Disabled"; -const char* VideoSettings::videoSourceUDP = "UDP Video Stream"; -const char* VideoSettings::videoSourceRTSP = "RTSP Video Stream"; -const char* VideoSettings::videoSourceTCP = "TCP-MPEG2 Video Stream"; -#ifdef QGC_GST_TAISYNC_USB -const char* VideoSettings::videoSourceTaiSyncUSB = "Taisync USB"; -#endif +const char* VideoSettings::videoSourceNoVideo = "No Video Available"; +const char* VideoSettings::videoDisabled = "Video Stream Disabled"; +const char* VideoSettings::videoSourceAuto = "Automatic Video Stream"; +const char* VideoSettings::videoSourceRTSP = "RTSP Video Stream"; +const char* VideoSettings::videoSourceUDP = "UDP Video Stream"; +const char* VideoSettings::videoSourceTCP = "TCP-MPEG2 Video Stream"; DECLARE_SETTINGGROUP(Video, "Video") { @@ -34,14 +34,12 @@ DECLARE_SETTINGGROUP(Video, "Video") // Setup enum values for videoSource settings into meta data QStringList videoSourceList; #ifdef QGC_GST_STREAMING + videoSourceList.append(videoSourceAuto); + videoSourceList.append(videoSourceRTSP); #ifndef NO_UDP_VIDEO videoSourceList.append(videoSourceUDP); #endif - videoSourceList.append(videoSourceRTSP); videoSourceList.append(videoSourceTCP); -#ifdef QGC_GST_TAISYNC_USB - videoSourceList.append(videoSourceTaiSyncUSB); -#endif #endif #ifndef QGC_DISABLE_UVC QList cameras = QCameraInfo::availableCameras(); @@ -60,7 +58,6 @@ DECLARE_SETTINGGROUP(Video, "Video") videoSourceVarList.append(QVariant::fromValue(videoSource)); } _nameToMetaDataMap[videoSourceName]->setEnumInfo(videoSourceList, videoSourceVarList); - // Set default value for videoSource _setDefaults(); } @@ -138,11 +135,6 @@ bool VideoSettings::streamConfigured(void) if(vSource == videoSourceNoVideo || vSource == videoDisabled) { return false; } -#ifdef QGC_GST_TAISYNC_USB - if(vSource == videoSourceTaiSyncUSB) { - return true; - } -#endif //-- If UDP, check if port is set if(vSource == videoSourceUDP) { return udpPort()->rawValue().toInt() != 0; @@ -151,9 +143,13 @@ bool VideoSettings::streamConfigured(void) if(vSource == videoSourceRTSP) { return !rtspUrl()->rawValue().toString().isEmpty(); } - //-- If TCP, check for URL + //-- If Auto, check for URL + if(vSource == videoSourceAuto) { + return !rtspUrl()->rawValue().toString().isEmpty(); + } + //-- If Auto, check for received URL if(vSource == videoSourceTCP) { - return !tcpUrl()->rawValue().toString().isEmpty(); + return !qgcApp()->toolbox()->videoManager()->autoURL().isEmpty(); } return false; } diff --git a/src/Settings/VideoSettings.h b/src/Settings/VideoSettings.h index 1f5f3b21377f87ad9284765b080ce44f673363cc..d0002fd0c07e14a88f11e991ef542069b3280b19 100644 --- a/src/Settings/VideoSettings.h +++ b/src/Settings/VideoSettings.h @@ -35,18 +35,24 @@ public: DEFINE_SETTINGFACT(streamEnabled) DEFINE_SETTINGFACT(disableWhenDisarmed) - Q_PROPERTY(bool streamConfigured READ streamConfigured NOTIFY streamConfiguredChanged) + Q_PROPERTY(bool streamConfigured READ streamConfigured NOTIFY streamConfiguredChanged) + Q_PROPERTY(QString autoVideoSource READ autoVideoSource CONSTANT) + Q_PROPERTY(QString rtspVideoSource READ rtspVideoSource CONSTANT) + Q_PROPERTY(QString udpVideoSource READ udpVideoSource CONSTANT) + Q_PROPERTY(QString tcpVideoSource READ tcpVideoSource CONSTANT) - bool streamConfigured (); + bool streamConfigured (); + QString autoVideoSource () { return videoSourceAuto; } + QString rtspVideoSource () { return videoSourceRTSP; } + QString udpVideoSource () { return videoSourceUDP; } + QString tcpVideoSource () { return videoSourceTCP; } static const char* videoSourceNoVideo; static const char* videoDisabled; static const char* videoSourceUDP; static const char* videoSourceRTSP; + static const char* videoSourceAuto; static const char* videoSourceTCP; -#ifdef QGC_GST_TAISYNC_USB - static const char* videoSourceTaiSyncUSB; -#endif signals: void streamConfiguredChanged (); diff --git a/src/Vehicle/Vehicle.h b/src/Vehicle/Vehicle.h index fc81a396c359c1e36ee4532a589a0067aa3d6e1a..4afdb3b6cb3f8267a9cf97caafa13d4dd36cedf3 100644 --- a/src/Vehicle/Vehicle.h +++ b/src/Vehicle/Vehicle.h @@ -501,7 +501,7 @@ public: Vehicle(MAV_AUTOPILOT firmwareType, MAV_TYPE vehicleType, FirmwarePluginManager* firmwarePluginManager, - QObject* parent = NULL); + QObject* parent = nullptr); ~Vehicle(); @@ -892,9 +892,9 @@ public: QString formatedMessages (); QString formatedMessage () { return _formatedMessage; } QString latestError () { return _latestError; } - float latitude () { return _coordinate.latitude(); } - float longitude () { return _coordinate.longitude(); } - bool mavPresent () { return _mav != NULL; } + float latitude () { return static_cast(_coordinate.latitude()); } + float longitude () { return static_cast(_coordinate.longitude()); } + bool mavPresent () { return _mav != nullptr; } int rcRSSI () { return _rcRSSI; } bool px4Firmware () const { return _firmwareType == MAV_AUTOPILOT_PX4; } bool apmFirmware () const { return _firmwareType == MAV_AUTOPILOT_ARDUPILOTMEGA; } @@ -990,8 +990,19 @@ public: void sendMavCommandInt(int component, MAV_CMD command, MAV_FRAME frame, bool showError, float param1, float param2, float param3, float param4, double param5, double param6, float param7); /// Same as sendMavCommand but available from Qml. - Q_INVOKABLE void sendCommand(int component, int command, bool showError, double param1 = 0.0f, double param2 = 0.0f, double param3 = 0.0f, double param4 = 0.0f, double param5 = 0.0f, double param6 = 0.0f, double param7 = 0.0f) - { sendMavCommand(component, (MAV_CMD)command, showError, param1, param2, param3, param4, param5, param6, param7); } + Q_INVOKABLE void sendCommand(int component, int command, bool showError, double param1 = 0.0, double param2 = 0.0, double param3 = 0.0, double param4 = 0.0, double param5 = 0.0, double param6 = 0.0, double param7 = 0.0) + { + sendMavCommand( + component, static_cast(command), + showError, + static_cast(param1), + static_cast(param2), + static_cast(param3), + static_cast(param4), + static_cast(param5), + static_cast(param6), + static_cast(param7)); + } int firmwareMajorVersion(void) const { return _firmwareMajorVersion; } int firmwareMinorVersion(void) const { return _firmwareMinorVersion; } diff --git a/src/ui/preferences/GeneralSettings.qml b/src/ui/preferences/GeneralSettings.qml index 2853c969fb308c6d5850a832c8b9f8315ab5a610..fdb49133e4eca3d21567d10792f5011780fabc91 100644 --- a/src/ui/preferences/GeneralSettings.qml +++ b/src/ui/preferences/GeneralSettings.qml @@ -45,7 +45,14 @@ QGCView { property real _panelWidth: _qgcView.width * _internalWidthRatio property real _margins: ScreenTools.defaultFontPixelWidth - readonly property real _internalWidthRatio: 0.8 + property string _videoSource: QGroundControl.settingsManager.videoSettings.videoSource.value + property bool _isGst: QGroundControl.videoManager.isGStreamer + property bool _isAutoStream: QGroundControl.videoManager.isAutoStream + property bool _isUDP: _isGst && _videoSource === QGroundControl.settingsManager.videoSettings.udpVideoSource + property bool _isRTSP: _isGst && _videoSource === QGroundControl.settingsManager.videoSettings.rtspVideoSource + property bool _isTCP: _isGst && _videoSource === QGroundControl.settingsManager.videoSettings.tcpVideoSource + + readonly property real _internalWidthRatio: 0.8 QGCPalette { id: qgcPal } @@ -702,8 +709,8 @@ QGCView { columns: 2 QGCLabel { - text: qsTr("Video Source") - visible: QGroundControl.settingsManager.videoSettings.videoSource.visible + text: qsTr("Video Source") + visible: QGroundControl.settingsManager.videoSettings.videoSource.visible } FactComboBox { id: videoSource @@ -714,53 +721,52 @@ QGCView { } QGCLabel { - text: qsTr("UDP Port") - visible: QGroundControl.settingsManager.videoSettings.udpPort.visible && QGroundControl.videoManager.isGStreamer && videoSource.currentIndex === 1 + text: qsTr("UDP Port") + visible: _isUDP && QGroundControl.settingsManager.videoSettings.udpPort.visible } FactTextField { Layout.preferredWidth: _comboFieldWidth fact: QGroundControl.settingsManager.videoSettings.udpPort - visible: QGroundControl.settingsManager.videoSettings.udpPort.visible && QGroundControl.videoManager.isGStreamer && videoSource.currentIndex === 1 + visible: _isUDP && QGroundControl.settingsManager.videoSettings.udpPort.visible } QGCLabel { - text: qsTr("RTSP URL") - visible: QGroundControl.settingsManager.videoSettings.rtspUrl.visible && QGroundControl.videoManager.isGStreamer && videoSource.currentIndex === 2 + text: qsTr("RTSP URL") + visible: _isRTSP && QGroundControl.settingsManager.videoSettings.rtspUrl.visible } FactTextField { Layout.preferredWidth: _comboFieldWidth fact: QGroundControl.settingsManager.videoSettings.rtspUrl - visible: QGroundControl.settingsManager.videoSettings.rtspUrl.visible && QGroundControl.videoManager.isGStreamer && videoSource.currentIndex === 2 + visible: _isRTSP && QGroundControl.settingsManager.videoSettings.rtspUrl.visible } QGCLabel { - text: qsTr("TCP URL") - visible: QGroundControl.settingsManager.videoSettings.tcpUrl.visible && QGroundControl.videoManager.isGStreamer && videoSource.currentIndex === 3 + text: qsTr("TCP URL") + visible: _isTCP && QGroundControl.settingsManager.videoSettings.tcpUrl.visible } FactTextField { Layout.preferredWidth: _comboFieldWidth fact: QGroundControl.settingsManager.videoSettings.tcpUrl - visible: QGroundControl.settingsManager.videoSettings.tcpUrl.visible && QGroundControl.videoManager.isGStreamer && videoSource.currentIndex === 3 + visible: _isTCP && QGroundControl.settingsManager.videoSettings.tcpUrl.visible } - QGCLabel { - text: qsTr("Aspect Ratio") - visible: QGroundControl.videoManager.isGStreamer && videoSource.currentIndex && videoSource.currentIndex < 3 && QGroundControl.settingsManager.videoSettings.aspectRatio.visible + text: qsTr("Aspect Ratio") + visible: !_isAutoStream && _isGst && QGroundControl.settingsManager.videoSettings.aspectRatio.visible } FactTextField { Layout.preferredWidth: _comboFieldWidth fact: QGroundControl.settingsManager.videoSettings.aspectRatio - visible: QGroundControl.videoManager.isGStreamer && videoSource.currentIndex && videoSource.currentIndex < 3 && QGroundControl.settingsManager.videoSettings.aspectRatio.visible + visible: !_isAutoStream && _isGst && QGroundControl.settingsManager.videoSettings.aspectRatio.visible } QGCLabel { - text: qsTr("Disable When Disarmed") - visible: QGroundControl.videoManager.isGStreamer && videoSource.currentIndex && videoSource.currentIndex < 3 && QGroundControl.settingsManager.videoSettings.gridLines.visible + text: qsTr("Disable When Disarmed") + visible: _isGst && QGroundControl.settingsManager.videoSettings.disableWhenDisarmed.visible } FactCheckBox { - text: "" - fact: QGroundControl.settingsManager.videoSettings.disableWhenDisarmed - visible: QGroundControl.videoManager.isGStreamer && videoSource.currentIndex && videoSource.currentIndex < 3 && QGroundControl.settingsManager.videoSettings.gridLines.visible + text: "" + fact: QGroundControl.settingsManager.videoSettings.disableWhenDisarmed + visible: _isGst && QGroundControl.settingsManager.videoSettings.disableWhenDisarmed.visible } } } @@ -768,16 +774,16 @@ QGCView { Item { width: 1; height: _margins } QGCLabel { - id: videoRecSectionLabel - text: qsTr("Video Recording") - visible: QGroundControl.settingsManager.videoSettings.visible && QGroundControl.videoManager.isGStreamer && videoSource.currentIndex && videoSource.currentIndex < 4 + id: videoRecSectionLabel + text: qsTr("Video Recording") + visible: QGroundControl.settingsManager.videoSettings.visible && _isGst } Rectangle { - Layout.preferredWidth: videoRecCol.width + (_margins * 2) - Layout.preferredHeight: videoRecCol.height + (_margins * 2) - Layout.fillWidth: true - color: qgcPal.windowShade - visible: videoRecSectionLabel.visible + Layout.preferredWidth: videoRecCol.width + (_margins * 2) + Layout.preferredHeight: videoRecCol.height + (_margins * 2) + Layout.fillWidth: true + color: qgcPal.windowShade + visible: videoRecSectionLabel.visible GridLayout { id: videoRecCol @@ -788,18 +794,18 @@ QGCView { columns: 2 QGCLabel { - text: qsTr("Auto-Delete Files") - visible: QGroundControl.settingsManager.videoSettings.enableStorageLimit.visible + text: qsTr("Auto-Delete Files") + visible: QGroundControl.settingsManager.videoSettings.enableStorageLimit.visible } FactCheckBox { - text: "" - fact: QGroundControl.settingsManager.videoSettings.enableStorageLimit - visible: QGroundControl.settingsManager.videoSettings.enableStorageLimit.visible + text: "" + fact: QGroundControl.settingsManager.videoSettings.enableStorageLimit + visible: QGroundControl.settingsManager.videoSettings.enableStorageLimit.visible } QGCLabel { - text: qsTr("Max Storage Usage") - visible: QGroundControl.settingsManager.videoSettings.maxVideoSize.visible && QGroundControl.settingsManager.videoSettings.enableStorageLimit.value + text: qsTr("Max Storage Usage") + visible: QGroundControl.settingsManager.videoSettings.maxVideoSize.visible && QGroundControl.settingsManager.videoSettings.enableStorageLimit.value } FactTextField { Layout.preferredWidth: _comboFieldWidth @@ -808,8 +814,8 @@ QGCView { } QGCLabel { - text: qsTr("Video File Format") - visible: QGroundControl.settingsManager.videoSettings.recordingFormat.visible + text: qsTr("Video File Format") + visible: QGroundControl.settingsManager.videoSettings.recordingFormat.visible } FactComboBox { Layout.preferredWidth: _comboFieldWidth