diff --git a/ground/openpilotgcs/src/plugins/config/configrevohwwidget.cpp b/ground/openpilotgcs/src/plugins/config/configrevohwwidget.cpp index 5a0258da8..1f3d0e2e3 100644 --- a/ground/openpilotgcs/src/plugins/config/configrevohwwidget.cpp +++ b/ground/openpilotgcs/src/plugins/config/configrevohwwidget.cpp @@ -66,6 +66,7 @@ ConfigRevoHWWidget::ConfigRevoHWWidget(QWidget *parent) : ConfigTaskWidget(paren addWidgetBinding("HwSettings", "ComUsbBridgeSpeed", m_ui->cbMainComSpeed); addWidgetBinding("HwSettings", "TelemetrySpeed", m_ui->cbRcvrTelemSpeed); + addWidgetBinding("HwSettings", "ComUsbBridgeSpeed", m_ui->cbRcvrComSpeed); // Add Gps protocol configuration addWidgetBinding("GPSSettings", "DataProtocol", m_ui->cbMainGPSProtocol); @@ -121,7 +122,8 @@ void ConfigRevoHWWidget::updateObjectsFromWidgets() // If any port is configured to be GPS port, enable GPS module if it is not enabled. // Otherwise disable GPS module. - if (m_ui->cbFlexi->currentIndex() == HwSettings::RM_FLEXIPORT_GPS || m_ui->cbMain->currentIndex() == HwSettings::RM_MAINPORT_GPS) { + if (isComboboxOptionSelected(m_ui->cbFlexi, HwSettings::RM_FLEXIPORT_GPS) + || isComboboxOptionSelected(m_ui->cbMain, HwSettings::RM_MAINPORT_GPS)) { data.OptionalModules[HwSettings::OPTIONALMODULES_GPS] = HwSettings::OPTIONALMODULES_ENABLED; } else { data.OptionalModules[HwSettings::OPTIONALMODULES_GPS] = HwSettings::OPTIONALMODULES_DISABLED; @@ -134,44 +136,40 @@ void ConfigRevoHWWidget::usbVCPPortChanged(int index) { Q_UNUSED(index); - bool vcpComBridgeEnabled = m_ui->cbUSBVCPFunction->currentIndex() == HwSettings::USB_VCPPORT_COMBRIDGE; + bool vcpComBridgeEnabled = isComboboxOptionSelected(m_ui->cbUSBVCPFunction, HwSettings::USB_VCPPORT_COMBRIDGE); m_ui->lblUSBVCPSpeed->setVisible(vcpComBridgeEnabled); m_ui->cbUSBVCPSpeed->setVisible(vcpComBridgeEnabled); - if (!vcpComBridgeEnabled && m_ui->cbFlexi->currentIndex() == HwSettings::RM_FLEXIPORT_COMBRIDGE) { - m_ui->cbFlexi->setCurrentIndex(HwSettings::RM_FLEXIPORT_DISABLED); + if (!vcpComBridgeEnabled && isComboboxOptionSelected(m_ui->cbFlexi, HwSettings::RM_FLEXIPORT_COMBRIDGE)) { + setComboboxSelectedOption(m_ui->cbFlexi, HwSettings::RM_FLEXIPORT_DISABLED); } - m_ui->cbFlexi->model()->setData(m_ui->cbFlexi->model()->index(HwSettings::RM_FLEXIPORT_COMBRIDGE, 0), - !vcpComBridgeEnabled ? QVariant(0) : QVariant(1 | 32), Qt::UserRole - 1); + enableComboBoxOptionItem(m_ui->cbFlexi, HwSettings::RM_FLEXIPORT_COMBRIDGE, vcpComBridgeEnabled); - if (!vcpComBridgeEnabled && m_ui->cbMain->currentIndex() == HwSettings::RM_MAINPORT_COMBRIDGE) { - m_ui->cbMain->setCurrentIndex(HwSettings::RM_MAINPORT_DISABLED); + if (!vcpComBridgeEnabled && isComboboxOptionSelected(m_ui->cbMain, HwSettings::RM_MAINPORT_COMBRIDGE)) { + setComboboxSelectedOption(m_ui->cbMain, HwSettings::RM_MAINPORT_DISABLED); } - m_ui->cbMain->model()->setData(m_ui->cbMain->model()->index(HwSettings::RM_MAINPORT_COMBRIDGE, 0), - !vcpComBridgeEnabled ? QVariant(0) : QVariant(1 | 32), Qt::UserRole - 1); + enableComboBoxOptionItem(m_ui->cbMain, HwSettings::RM_MAINPORT_COMBRIDGE, vcpComBridgeEnabled); - if (!vcpComBridgeEnabled && m_ui->cbRcvr->currentIndex() == HwSettings::RM_RCVRPORT_COMBRIDGE) { - m_ui->cbRcvr->setCurrentIndex(HwSettings::RM_RCVRPORT_DISABLED); + if (!vcpComBridgeEnabled && isComboboxOptionSelected(m_ui->cbRcvr, HwSettings::RM_RCVRPORT_COMBRIDGE)) { + setComboboxSelectedOption(m_ui->cbRcvr, HwSettings::RM_RCVRPORT_DISABLED); } - m_ui->cbRcvr->model()->setData(m_ui->cbRcvr->model()->index(HwSettings::RM_RCVRPORT_COMBRIDGE, 0), - !vcpComBridgeEnabled ? QVariant(0) : QVariant(1 | 32), Qt::UserRole - 1); + enableComboBoxOptionItem(m_ui->cbRcvr, HwSettings::RM_RCVRPORT_COMBRIDGE, vcpComBridgeEnabled); // _DEBUGCONSOLE modes are mutual exclusive - if (m_ui->cbUSBVCPFunction->currentIndex() == HwSettings::USB_VCPPORT_DEBUGCONSOLE) { - if (m_ui->cbMain->currentIndex() == HwSettings::RM_MAINPORT_DEBUGCONSOLE) { - m_ui->cbMain->setCurrentIndex(HwSettings::RM_MAINPORT_DISABLED); + if (isComboboxOptionSelected(m_ui->cbUSBVCPFunction, HwSettings::USB_VCPPORT_DEBUGCONSOLE)) { + if (isComboboxOptionSelected(m_ui->cbMain, HwSettings::RM_MAINPORT_DEBUGCONSOLE)) { + setComboboxSelectedOption(m_ui->cbMain, HwSettings::RM_MAINPORT_DISABLED); } - if (m_ui->cbFlexi->currentIndex() == HwSettings::RM_FLEXIPORT_DEBUGCONSOLE) { - m_ui->cbFlexi->setCurrentIndex(HwSettings::RM_FLEXIPORT_DISABLED); + if (isComboboxOptionSelected(m_ui->cbFlexi, HwSettings::RM_FLEXIPORT_DEBUGCONSOLE)) { + setComboboxSelectedOption(m_ui->cbFlexi, HwSettings::RM_FLEXIPORT_DISABLED); } } // _USBTELEMETRY modes are mutual exclusive - if (m_ui->cbUSBVCPFunction->currentIndex() == HwSettings::USB_VCPPORT_USBTELEMETRY) { - if (m_ui->cbUSBHIDFunction->currentIndex() == HwSettings::USB_HIDPORT_USBTELEMETRY) { - m_ui->cbUSBHIDFunction->setCurrentIndex(HwSettings::USB_HIDPORT_DISABLED); - } + if (isComboboxOptionSelected(m_ui->cbUSBVCPFunction, HwSettings::USB_VCPPORT_USBTELEMETRY) + && isComboboxOptionSelected(m_ui->cbUSBHIDFunction, HwSettings::USB_HIDPORT_USBTELEMETRY)) { + setComboboxSelectedOption(m_ui->cbUSBHIDFunction, HwSettings::USB_HIDPORT_DISABLED); } } @@ -180,10 +178,9 @@ void ConfigRevoHWWidget::usbHIDPortChanged(int index) Q_UNUSED(index); // _USBTELEMETRY modes are mutual exclusive - if (m_ui->cbUSBHIDFunction->currentIndex() == HwSettings::USB_HIDPORT_USBTELEMETRY) { - if (m_ui->cbUSBVCPFunction->currentIndex() == HwSettings::USB_VCPPORT_USBTELEMETRY) { - m_ui->cbUSBVCPFunction->setCurrentIndex(HwSettings::USB_VCPPORT_DISABLED); - } + if (isComboboxOptionSelected(m_ui->cbUSBHIDFunction, HwSettings::USB_HIDPORT_USBTELEMETRY) + && isComboboxOptionSelected(m_ui->cbUSBVCPFunction, HwSettings::USB_VCPPORT_USBTELEMETRY)) { + setComboboxSelectedOption(m_ui->cbUSBVCPFunction, HwSettings::USB_VCPPORT_DISABLED); } } @@ -200,15 +197,15 @@ void ConfigRevoHWWidget::flexiPortChanged(int index) m_ui->cbFlexiGPSProtocol->setVisible(false); m_ui->lbFlexiGPSProtocol->setVisible(false); - switch (m_ui->cbFlexi->currentIndex()) { + switch (getComboboxSelectedOption(m_ui->cbFlexi)) { case HwSettings::RM_FLEXIPORT_TELEMETRY: m_ui->cbFlexiTelemSpeed->setVisible(true); - if (m_ui->cbMain->currentIndex() == HwSettings::RM_MAINPORT_TELEMETRY) { - m_ui->cbMain->setCurrentIndex(HwSettings::RM_MAINPORT_DISABLED); + if (isComboboxOptionSelected(m_ui->cbMain, HwSettings::RM_MAINPORT_TELEMETRY)) { + setComboboxSelectedOption(m_ui->cbMain, HwSettings::RM_MAINPORT_DISABLED); } - if (m_ui->cbRcvr->currentIndex() == HwSettings::RM_RCVRPORT_PPMTELEMETRY - || m_ui->cbRcvr->currentIndex() == HwSettings::RM_RCVRPORT_TELEMETRY) { - m_ui->cbRcvr->setCurrentIndex(HwSettings::RM_RCVRPORT_DISABLED); + if (isComboboxOptionSelected(m_ui->cbRcvr, HwSettings::RM_RCVRPORT_PPMTELEMETRY) + || isComboboxOptionSelected(m_ui->cbRcvr, HwSettings::RM_RCVRPORT_TELEMETRY)) { + setComboboxSelectedOption(m_ui->cbRcvr, HwSettings::RM_RCVRPORT_DISABLED); } break; case HwSettings::RM_FLEXIPORT_GPS: @@ -217,23 +214,26 @@ void ConfigRevoHWWidget::flexiPortChanged(int index) m_ui->lbFlexiGPSProtocol->setVisible(true); m_ui->cbFlexiGPSSpeed->setVisible(true); - if (m_ui->cbMain->currentIndex() == HwSettings::RM_MAINPORT_GPS) { - m_ui->cbMain->setCurrentIndex(HwSettings::RM_MAINPORT_DISABLED); + if (isComboboxOptionSelected(m_ui->cbMain, HwSettings::RM_MAINPORT_GPS)) { + setComboboxSelectedOption(m_ui->cbMain, HwSettings::RM_MAINPORT_DISABLED); } break; case HwSettings::RM_FLEXIPORT_COMBRIDGE: m_ui->cbFlexiComSpeed->setVisible(true); - if (m_ui->cbMain->currentIndex() == HwSettings::RM_MAINPORT_COMBRIDGE) { - m_ui->cbMain->setCurrentIndex(HwSettings::RM_MAINPORT_DISABLED); + if (isComboboxOptionSelected(m_ui->cbMain, HwSettings::RM_MAINPORT_COMBRIDGE)) { + setComboboxSelectedOption(m_ui->cbMain, HwSettings::RM_MAINPORT_DISABLED); + } + if (isComboboxOptionSelected(m_ui->cbRcvr, HwSettings::RM_RCVRPORT_COMBRIDGE)) { + setComboboxSelectedOption(m_ui->cbRcvr, HwSettings::RM_RCVRPORT_DISABLED); } break; case HwSettings::RM_FLEXIPORT_DEBUGCONSOLE: m_ui->cbFlexiComSpeed->setVisible(true); - if (m_ui->cbMain->currentIndex() == HwSettings::RM_MAINPORT_DEBUGCONSOLE) { - m_ui->cbMain->setCurrentIndex(HwSettings::RM_MAINPORT_DISABLED); + if (isComboboxOptionSelected(m_ui->cbMain, HwSettings::RM_MAINPORT_DEBUGCONSOLE)) { + setComboboxSelectedOption(m_ui->cbMain, HwSettings::RM_MAINPORT_DISABLED); } - if (m_ui->cbUSBVCPFunction->currentIndex() == HwSettings::USB_VCPPORT_DEBUGCONSOLE) { - m_ui->cbUSBVCPFunction->setCurrentIndex(HwSettings::USB_VCPPORT_DISABLED); + if (isComboboxOptionSelected(m_ui->cbUSBVCPFunction, HwSettings::USB_VCPPORT_DEBUGCONSOLE)) { + setComboboxSelectedOption(m_ui->cbUSBVCPFunction, HwSettings::USB_VCPPORT_DISABLED); } break; default: @@ -255,15 +255,15 @@ void ConfigRevoHWWidget::mainPortChanged(int index) m_ui->cbMainGPSProtocol->setVisible(false); m_ui->lbMainGPSProtocol->setVisible(false); - switch (m_ui->cbMain->currentIndex()) { + switch (getComboboxSelectedOption(m_ui->cbMain)) { case HwSettings::RM_MAINPORT_TELEMETRY: m_ui->cbMainTelemSpeed->setVisible(true); - if (m_ui->cbFlexi->currentIndex() == HwSettings::RM_FLEXIPORT_TELEMETRY) { - m_ui->cbFlexi->setCurrentIndex(HwSettings::RM_FLEXIPORT_DISABLED); + if (isComboboxOptionSelected(m_ui->cbFlexi, HwSettings::RM_FLEXIPORT_TELEMETRY)) { + setComboboxSelectedOption(m_ui->cbFlexi, HwSettings::RM_FLEXIPORT_DISABLED); } - if (m_ui->cbRcvr->currentIndex() == HwSettings::RM_RCVRPORT_PPMTELEMETRY - || m_ui->cbRcvr->currentIndex() == HwSettings::RM_RCVRPORT_TELEMETRY) { - m_ui->cbRcvr->setCurrentIndex(HwSettings::RM_RCVRPORT_DISABLED); + if (isComboboxOptionSelected(m_ui->cbRcvr, HwSettings::RM_RCVRPORT_PPMTELEMETRY) + || isComboboxOptionSelected(m_ui->cbRcvr, HwSettings::RM_RCVRPORT_TELEMETRY)) { + setComboboxSelectedOption(m_ui->cbRcvr, HwSettings::RM_RCVRPORT_DISABLED); } break; case HwSettings::RM_MAINPORT_GPS: @@ -272,23 +272,26 @@ void ConfigRevoHWWidget::mainPortChanged(int index) m_ui->lbMainGPSProtocol->setVisible(true); m_ui->cbMainGPSSpeed->setVisible(true); - if (m_ui->cbFlexi->currentIndex() == HwSettings::RM_FLEXIPORT_GPS) { - m_ui->cbFlexi->setCurrentIndex(HwSettings::RM_FLEXIPORT_DISABLED); + if (isComboboxOptionSelected(m_ui->cbFlexi, HwSettings::RM_FLEXIPORT_GPS)) { + setComboboxSelectedOption(m_ui->cbFlexi, HwSettings::RM_FLEXIPORT_DISABLED); } break; case HwSettings::RM_MAINPORT_COMBRIDGE: m_ui->cbMainComSpeed->setVisible(true); - if (m_ui->cbFlexi->currentIndex() == HwSettings::RM_FLEXIPORT_COMBRIDGE) { - m_ui->cbFlexi->setCurrentIndex(HwSettings::RM_FLEXIPORT_DISABLED); + if (isComboboxOptionSelected(m_ui->cbFlexi, HwSettings::RM_FLEXIPORT_COMBRIDGE)) { + setComboboxSelectedOption(m_ui->cbFlexi, HwSettings::RM_FLEXIPORT_DISABLED); + } + if (isComboboxOptionSelected(m_ui->cbRcvr, HwSettings::RM_RCVRPORT_COMBRIDGE)) { + setComboboxSelectedOption(m_ui->cbRcvr, HwSettings::RM_RCVRPORT_DISABLED); } break; case HwSettings::RM_MAINPORT_DEBUGCONSOLE: m_ui->cbMainComSpeed->setVisible(true); - if (m_ui->cbFlexi->currentIndex() == HwSettings::RM_FLEXIPORT_DEBUGCONSOLE) { - m_ui->cbFlexi->setCurrentIndex(HwSettings::RM_FLEXIPORT_DISABLED); + if (isComboboxOptionSelected(m_ui->cbFlexi, HwSettings::RM_FLEXIPORT_DEBUGCONSOLE)) { + setComboboxSelectedOption(m_ui->cbFlexi, HwSettings::RM_FLEXIPORT_DISABLED); } - if (m_ui->cbUSBVCPFunction->currentIndex() == HwSettings::USB_VCPPORT_DEBUGCONSOLE) { - m_ui->cbUSBVCPFunction->setCurrentIndex(HwSettings::USB_VCPPORT_DISABLED); + if (isComboboxOptionSelected(m_ui->cbUSBVCPFunction, HwSettings::USB_VCPPORT_DEBUGCONSOLE)) { + setComboboxSelectedOption(m_ui->cbUSBVCPFunction, HwSettings::USB_VCPPORT_DISABLED); } break; default: @@ -300,23 +303,33 @@ void ConfigRevoHWWidget::mainPortChanged(int index) void ConfigRevoHWWidget::rcvrPortChanged(int index) { Q_UNUSED(index); + m_ui->lblRcvrSpeed->setVisible(true); + m_ui->cbRcvrTelemSpeed->setVisible(false); + m_ui->cbRcvrComSpeed->setVisible(false); - switch (m_ui->cbRcvr->currentIndex()) { + switch (getComboboxSelectedOption(m_ui->cbRcvr)) { case HwSettings::RM_RCVRPORT_TELEMETRY: case HwSettings::RM_RCVRPORT_PPMTELEMETRY: - m_ui->lblRcvrSpeed->setVisible(true); m_ui->cbRcvrTelemSpeed->setVisible(true); - if (m_ui->cbFlexi->currentIndex() == HwSettings::RM_FLEXIPORT_TELEMETRY) { - m_ui->cbFlexi->setCurrentIndex(HwSettings::RM_FLEXIPORT_DISABLED); + if (isComboboxOptionSelected(m_ui->cbFlexi, HwSettings::RM_FLEXIPORT_TELEMETRY)) { + setComboboxSelectedOption(m_ui->cbFlexi, HwSettings::RM_FLEXIPORT_DISABLED); } - if (m_ui->cbMain->currentIndex() == HwSettings::RM_FLEXIPORT_TELEMETRY) { - m_ui->cbMain->setCurrentIndex(HwSettings::RM_FLEXIPORT_DISABLED); + if (isComboboxOptionSelected(m_ui->cbMain, HwSettings::RM_FLEXIPORT_TELEMETRY)) { + setComboboxSelectedOption(m_ui->cbMain, HwSettings::RM_FLEXIPORT_DISABLED); + } + break; + case HwSettings::RM_RCVRPORT_COMBRIDGE: + m_ui->cbRcvrComSpeed->setVisible(true); + if (isComboboxOptionSelected(m_ui->cbFlexi, HwSettings::RM_FLEXIPORT_COMBRIDGE)) { + setComboboxSelectedOption(m_ui->cbFlexi, HwSettings::RM_FLEXIPORT_DISABLED); + } + if (isComboboxOptionSelected(m_ui->cbMain, HwSettings::RM_MAINPORT_COMBRIDGE)) { + setComboboxSelectedOption(m_ui->cbMain, HwSettings::RM_MAINPORT_DISABLED); } break; default: m_ui->lblRcvrSpeed->setVisible(false); - m_ui->cbRcvrTelemSpeed->setVisible(false); break; } } diff --git a/ground/openpilotgcs/src/plugins/config/configrevohwwidget.ui b/ground/openpilotgcs/src/plugins/config/configrevohwwidget.ui index f199499cb..6534e3cbb 100644 --- a/ground/openpilotgcs/src/plugins/config/configrevohwwidget.ui +++ b/ground/openpilotgcs/src/plugins/config/configrevohwwidget.ui @@ -121,9 +121,9 @@ 0 - -87 - 789 - 847 + -148 + 796 + 804 @@ -232,130 +232,8 @@ - - - - - Protocol - - - Qt::PlainText - - - Qt::AlignCenter - - - - - - - - - - - - - Qt::Horizontal - - - - 80 - 10 - - - - - - - - Speed - - - Qt::AlignBottom|Qt::AlignHCenter - - - - - - - Qt::Vertical - - - QSizePolicy::Fixed - - - - 20 - 20 - - - - - - - - Qt::Vertical - - - QSizePolicy::Fixed - - - - 20 - 13 - - - - - - - - Qt::Vertical - - - QSizePolicy::Fixed - - - - 20 - 13 - - - - - - - - Qt::Horizontal - - - QSizePolicy::Minimum - - - - 120 - 10 - - - - - - - - Qt::Vertical - - - QSizePolicy::Fixed - - - - 20 - 13 - - - - - + + 0 @@ -375,10 +253,10 @@ - + - + Qt::Vertical @@ -394,7 +272,65 @@ - + + + + Speed + + + Qt::AlignBottom|Qt::AlignHCenter + + + + + + + Qt::Vertical + + + QSizePolicy::Fixed + + + + 20 + 20 + + + + + + + + Qt::Vertical + + + QSizePolicy::Fixed + + + + 20 + 13 + + + + + + + + + + + Qt::Horizontal + + + + 80 + 10 + + + + + Qt::Horizontal @@ -410,7 +346,7 @@ - + @@ -426,7 +362,10 @@ - + + + + @@ -442,7 +381,7 @@ - + Speed @@ -452,7 +391,7 @@ - + Qt::Horizontal @@ -468,17 +407,81 @@ - - + + - + false - + + + + Protocol + + + Qt::PlainText + + + Qt::AlignCenter + + + + + + + + + + Qt::Vertical + + + QSizePolicy::Fixed + + + + 20 + 13 + + + + + + + + Qt::Horizontal + + + QSizePolicy::Minimum + + + + 120 + 10 + + + + + + + + Qt::Vertical + + + QSizePolicy::Fixed + + + + 20 + 13 + + + + + Qt::Horizontal @@ -494,7 +497,7 @@ - + Qt::Vertical @@ -510,7 +513,7 @@ - + Main Port @@ -520,10 +523,7 @@ - - - - + Flexi Port @@ -533,7 +533,7 @@ - + @@ -564,7 +564,7 @@ - + 0 @@ -584,7 +584,7 @@ - + Qt::Horizontal @@ -600,7 +600,7 @@ - + Protocol @@ -610,7 +610,7 @@ - + Qt::Horizontal @@ -626,11 +626,14 @@ - + - + + 0 + + @@ -649,31 +652,24 @@ + + + - - - - Qt::Vertical - - - - 0 - 50 - - - - - + true - + + + + @@ -689,10 +685,10 @@ - - + + - + @@ -708,10 +704,7 @@ - - - - + diff --git a/shared/uavobjectdefinition/hwsettings.xml b/shared/uavobjectdefinition/hwsettings.xml index d5d991141..83585105a 100644 --- a/shared/uavobjectdefinition/hwsettings.xml +++ b/shared/uavobjectdefinition/hwsettings.xml @@ -10,7 +10,7 @@ + limits="%0905NE:PPM+PWM:PPM+Telemetry:Telemetry:ComBridge;"/>