mirror of
https://bitbucket.org/librepilot/librepilot.git
synced 2025-03-16 08:29:15 +01:00
REVONANO: Update Nano Hw page to use 'limits safe' combobox code.
This commit is contained in:
parent
c4105240c2
commit
a871a6f455
@ -68,6 +68,7 @@ ConfigRevoNanoHWWidget::ConfigRevoNanoHWWidget(QWidget *parent) : ConfigTaskWidg
|
|||||||
addWidgetBinding("HwSettings", "ComUsbBridgeSpeed", m_ui->cbMainComSpeed);
|
addWidgetBinding("HwSettings", "ComUsbBridgeSpeed", m_ui->cbMainComSpeed);
|
||||||
|
|
||||||
addWidgetBinding("HwSettings", "TelemetrySpeed", m_ui->cbRcvrTelemSpeed);
|
addWidgetBinding("HwSettings", "TelemetrySpeed", m_ui->cbRcvrTelemSpeed);
|
||||||
|
addWidgetBinding("HwSettings", "ComUsbBridgeSpeed", m_ui->cbRcvrComSpeed);
|
||||||
|
|
||||||
// Add Gps protocol configuration
|
// Add Gps protocol configuration
|
||||||
addWidgetBinding("GPSSettings", "DataProtocol", m_ui->cbMainGPSProtocol);
|
addWidgetBinding("GPSSettings", "DataProtocol", m_ui->cbMainGPSProtocol);
|
||||||
@ -118,7 +119,8 @@ void ConfigRevoNanoHWWidget::updateObjectsFromWidgets()
|
|||||||
|
|
||||||
// If any port is configured to be GPS port, enable GPS module if it is not enabled.
|
// If any port is configured to be GPS port, enable GPS module if it is not enabled.
|
||||||
// Otherwise disable GPS module.
|
// 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;
|
data.OptionalModules[HwSettings::OPTIONALMODULES_GPS] = HwSettings::OPTIONALMODULES_ENABLED;
|
||||||
} else {
|
} else {
|
||||||
data.OptionalModules[HwSettings::OPTIONALMODULES_GPS] = HwSettings::OPTIONALMODULES_DISABLED;
|
data.OptionalModules[HwSettings::OPTIONALMODULES_GPS] = HwSettings::OPTIONALMODULES_DISABLED;
|
||||||
@ -131,38 +133,40 @@ void ConfigRevoNanoHWWidget::usbVCPPortChanged(int index)
|
|||||||
{
|
{
|
||||||
Q_UNUSED(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->lblUSBVCPSpeed->setVisible(vcpComBridgeEnabled);
|
||||||
m_ui->cbUSBVCPSpeed->setVisible(vcpComBridgeEnabled);
|
m_ui->cbUSBVCPSpeed->setVisible(vcpComBridgeEnabled);
|
||||||
|
|
||||||
if (!vcpComBridgeEnabled && m_ui->cbFlexi->currentIndex() == HwSettings::RM_FLEXIPORT_COMBRIDGE) {
|
if (!vcpComBridgeEnabled && isComboboxOptionSelected(m_ui->cbFlexi, HwSettings::RM_FLEXIPORT_COMBRIDGE)) {
|
||||||
m_ui->cbFlexi->setCurrentIndex(HwSettings::RM_FLEXIPORT_DISABLED);
|
setComboboxSelectedOption(m_ui->cbFlexi, HwSettings::RM_FLEXIPORT_DISABLED);
|
||||||
}
|
}
|
||||||
m_ui->cbFlexi->model()->setData(m_ui->cbFlexi->model()->index(HwSettings::RM_FLEXIPORT_COMBRIDGE, 0),
|
enableComboBoxOptionItem(m_ui->cbFlexi, HwSettings::RM_FLEXIPORT_COMBRIDGE, vcpComBridgeEnabled);
|
||||||
!vcpComBridgeEnabled ? QVariant(0) : QVariant(1 | 32), Qt::UserRole - 1);
|
|
||||||
|
|
||||||
if (!vcpComBridgeEnabled && m_ui->cbMain->currentIndex() == HwSettings::RM_MAINPORT_COMBRIDGE) {
|
if (!vcpComBridgeEnabled && isComboboxOptionSelected(m_ui->cbMain, HwSettings::RM_MAINPORT_COMBRIDGE)) {
|
||||||
m_ui->cbMain->setCurrentIndex(HwSettings::RM_MAINPORT_DISABLED);
|
setComboboxSelectedOption(m_ui->cbMain, HwSettings::RM_MAINPORT_DISABLED);
|
||||||
}
|
}
|
||||||
m_ui->cbMain->model()->setData(m_ui->cbMain->model()->index(HwSettings::RM_MAINPORT_COMBRIDGE, 0),
|
enableComboBoxOptionItem(m_ui->cbMain, HwSettings::RM_MAINPORT_COMBRIDGE, vcpComBridgeEnabled);
|
||||||
!vcpComBridgeEnabled ? QVariant(0) : QVariant(1 | 32), Qt::UserRole - 1);
|
|
||||||
|
if (!vcpComBridgeEnabled && isComboboxOptionSelected(m_ui->cbRcvr, HwSettings::RM_RCVRPORT_COMBRIDGE)) {
|
||||||
|
setComboboxSelectedOption(m_ui->cbRcvr, HwSettings::RM_RCVRPORT_DISABLED);
|
||||||
|
}
|
||||||
|
enableComboBoxOptionItem(m_ui->cbRcvr, HwSettings::RM_RCVRPORT_COMBRIDGE, vcpComBridgeEnabled);
|
||||||
|
|
||||||
// _DEBUGCONSOLE modes are mutual exclusive
|
// _DEBUGCONSOLE modes are mutual exclusive
|
||||||
if (m_ui->cbUSBVCPFunction->currentIndex() == HwSettings::USB_VCPPORT_DEBUGCONSOLE) {
|
if (isComboboxOptionSelected(m_ui->cbUSBVCPFunction, HwSettings::USB_VCPPORT_DEBUGCONSOLE)) {
|
||||||
if (m_ui->cbMain->currentIndex() == HwSettings::RM_MAINPORT_DEBUGCONSOLE) {
|
if (isComboboxOptionSelected(m_ui->cbMain, HwSettings::RM_MAINPORT_DEBUGCONSOLE)) {
|
||||||
m_ui->cbMain->setCurrentIndex(HwSettings::RM_MAINPORT_DISABLED);
|
setComboboxSelectedOption(m_ui->cbMain, HwSettings::RM_MAINPORT_DISABLED);
|
||||||
}
|
}
|
||||||
if (m_ui->cbFlexi->currentIndex() == HwSettings::RM_FLEXIPORT_DEBUGCONSOLE) {
|
if (isComboboxOptionSelected(m_ui->cbFlexi, HwSettings::RM_FLEXIPORT_DEBUGCONSOLE)) {
|
||||||
m_ui->cbFlexi->setCurrentIndex(HwSettings::RM_FLEXIPORT_DISABLED);
|
setComboboxSelectedOption(m_ui->cbFlexi, HwSettings::RM_FLEXIPORT_DISABLED);
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
// _USBTELEMETRY modes are mutual exclusive
|
// _USBTELEMETRY modes are mutual exclusive
|
||||||
if (m_ui->cbUSBVCPFunction->currentIndex() == HwSettings::USB_VCPPORT_USBTELEMETRY) {
|
if (isComboboxOptionSelected(m_ui->cbUSBVCPFunction, HwSettings::USB_VCPPORT_USBTELEMETRY)
|
||||||
if (m_ui->cbUSBHIDFunction->currentIndex() == HwSettings::USB_HIDPORT_USBTELEMETRY) {
|
&& isComboboxOptionSelected(m_ui->cbUSBHIDFunction, HwSettings::USB_HIDPORT_USBTELEMETRY)) {
|
||||||
m_ui->cbUSBHIDFunction->setCurrentIndex(HwSettings::USB_HIDPORT_DISABLED);
|
setComboboxSelectedOption(m_ui->cbUSBHIDFunction, HwSettings::USB_HIDPORT_DISABLED);
|
||||||
}
|
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
@ -171,10 +175,9 @@ void ConfigRevoNanoHWWidget::usbHIDPortChanged(int index)
|
|||||||
Q_UNUSED(index);
|
Q_UNUSED(index);
|
||||||
|
|
||||||
// _USBTELEMETRY modes are mutual exclusive
|
// _USBTELEMETRY modes are mutual exclusive
|
||||||
if (m_ui->cbUSBHIDFunction->currentIndex() == HwSettings::USB_HIDPORT_USBTELEMETRY) {
|
if (isComboboxOptionSelected(m_ui->cbUSBHIDFunction, HwSettings::USB_HIDPORT_USBTELEMETRY)
|
||||||
if (m_ui->cbUSBVCPFunction->currentIndex() == HwSettings::USB_VCPPORT_USBTELEMETRY) {
|
&& isComboboxOptionSelected(m_ui->cbUSBVCPFunction, HwSettings::USB_VCPPORT_USBTELEMETRY)) {
|
||||||
m_ui->cbUSBVCPFunction->setCurrentIndex(HwSettings::USB_VCPPORT_DISABLED);
|
setComboboxSelectedOption(m_ui->cbUSBVCPFunction, HwSettings::USB_VCPPORT_DISABLED);
|
||||||
}
|
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
@ -191,15 +194,15 @@ void ConfigRevoNanoHWWidget::flexiPortChanged(int index)
|
|||||||
m_ui->cbFlexiGPSProtocol->setVisible(false);
|
m_ui->cbFlexiGPSProtocol->setVisible(false);
|
||||||
m_ui->lbFlexiGPSProtocol->setVisible(false);
|
m_ui->lbFlexiGPSProtocol->setVisible(false);
|
||||||
|
|
||||||
switch (m_ui->cbFlexi->currentIndex()) {
|
switch (getComboboxSelectedOption(m_ui->cbFlexi)) {
|
||||||
case HwSettings::RM_FLEXIPORT_TELEMETRY:
|
case HwSettings::RM_FLEXIPORT_TELEMETRY:
|
||||||
m_ui->cbFlexiTelemSpeed->setVisible(true);
|
m_ui->cbFlexiTelemSpeed->setVisible(true);
|
||||||
if (m_ui->cbMain->currentIndex() == HwSettings::RM_MAINPORT_TELEMETRY) {
|
if (isComboboxOptionSelected(m_ui->cbMain, HwSettings::RM_MAINPORT_TELEMETRY)) {
|
||||||
m_ui->cbMain->setCurrentIndex(HwSettings::RM_MAINPORT_DISABLED);
|
setComboboxSelectedOption(m_ui->cbMain, HwSettings::RM_MAINPORT_DISABLED);
|
||||||
}
|
}
|
||||||
if (m_ui->cbRcvr->currentIndex() == HwSettings::RM_RCVRPORT_PPMTELEMETRY
|
if (isComboboxOptionSelected(m_ui->cbRcvr, HwSettings::RM_RCVRPORT_PPMTELEMETRY)
|
||||||
|| m_ui->cbRcvr->currentIndex() == HwSettings::RM_RCVRPORT_TELEMETRY) {
|
|| isComboboxOptionSelected(m_ui->cbRcvr, HwSettings::RM_RCVRPORT_TELEMETRY)) {
|
||||||
m_ui->cbRcvr->setCurrentIndex(HwSettings::RM_RCVRPORT_DISABLED);
|
setComboboxSelectedOption(m_ui->cbRcvr, HwSettings::RM_RCVRPORT_DISABLED);
|
||||||
}
|
}
|
||||||
break;
|
break;
|
||||||
case HwSettings::RM_FLEXIPORT_GPS:
|
case HwSettings::RM_FLEXIPORT_GPS:
|
||||||
@ -208,23 +211,26 @@ void ConfigRevoNanoHWWidget::flexiPortChanged(int index)
|
|||||||
m_ui->lbFlexiGPSProtocol->setVisible(true);
|
m_ui->lbFlexiGPSProtocol->setVisible(true);
|
||||||
|
|
||||||
m_ui->cbFlexiGPSSpeed->setVisible(true);
|
m_ui->cbFlexiGPSSpeed->setVisible(true);
|
||||||
if (m_ui->cbMain->currentIndex() == HwSettings::RM_MAINPORT_GPS) {
|
if (isComboboxOptionSelected(m_ui->cbMain, HwSettings::RM_MAINPORT_GPS)) {
|
||||||
m_ui->cbMain->setCurrentIndex(HwSettings::RM_MAINPORT_DISABLED);
|
setComboboxSelectedOption(m_ui->cbMain, HwSettings::RM_MAINPORT_DISABLED);
|
||||||
}
|
}
|
||||||
break;
|
break;
|
||||||
case HwSettings::RM_FLEXIPORT_COMBRIDGE:
|
case HwSettings::RM_FLEXIPORT_COMBRIDGE:
|
||||||
m_ui->cbFlexiComSpeed->setVisible(true);
|
m_ui->cbFlexiComSpeed->setVisible(true);
|
||||||
if (m_ui->cbMain->currentIndex() == HwSettings::RM_MAINPORT_COMBRIDGE) {
|
if (isComboboxOptionSelected(m_ui->cbMain, HwSettings::RM_MAINPORT_COMBRIDGE)) {
|
||||||
m_ui->cbMain->setCurrentIndex(HwSettings::RM_MAINPORT_DISABLED);
|
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;
|
break;
|
||||||
case HwSettings::RM_FLEXIPORT_DEBUGCONSOLE:
|
case HwSettings::RM_FLEXIPORT_DEBUGCONSOLE:
|
||||||
m_ui->cbFlexiComSpeed->setVisible(true);
|
m_ui->cbFlexiComSpeed->setVisible(true);
|
||||||
if (m_ui->cbMain->currentIndex() == HwSettings::RM_MAINPORT_DEBUGCONSOLE) {
|
if (isComboboxOptionSelected(m_ui->cbMain, HwSettings::RM_MAINPORT_DEBUGCONSOLE)) {
|
||||||
m_ui->cbMain->setCurrentIndex(HwSettings::RM_MAINPORT_DISABLED);
|
setComboboxSelectedOption(m_ui->cbMain, HwSettings::RM_MAINPORT_DISABLED);
|
||||||
}
|
}
|
||||||
if (m_ui->cbUSBVCPFunction->currentIndex() == HwSettings::USB_VCPPORT_DEBUGCONSOLE) {
|
if (isComboboxOptionSelected(m_ui->cbUSBVCPFunction, HwSettings::USB_VCPPORT_DEBUGCONSOLE)) {
|
||||||
m_ui->cbUSBVCPFunction->setCurrentIndex(HwSettings::USB_VCPPORT_DISABLED);
|
setComboboxSelectedOption(m_ui->cbUSBVCPFunction, HwSettings::USB_VCPPORT_DISABLED);
|
||||||
}
|
}
|
||||||
break;
|
break;
|
||||||
default:
|
default:
|
||||||
@ -246,15 +252,15 @@ void ConfigRevoNanoHWWidget::mainPortChanged(int index)
|
|||||||
m_ui->cbMainGPSProtocol->setVisible(false);
|
m_ui->cbMainGPSProtocol->setVisible(false);
|
||||||
m_ui->lbMainGPSProtocol->setVisible(false);
|
m_ui->lbMainGPSProtocol->setVisible(false);
|
||||||
|
|
||||||
switch (m_ui->cbMain->currentIndex()) {
|
switch (getComboboxSelectedOption(m_ui->cbMain)) {
|
||||||
case HwSettings::RM_MAINPORT_TELEMETRY:
|
case HwSettings::RM_MAINPORT_TELEMETRY:
|
||||||
m_ui->cbMainTelemSpeed->setVisible(true);
|
m_ui->cbMainTelemSpeed->setVisible(true);
|
||||||
if (m_ui->cbFlexi->currentIndex() == HwSettings::RM_FLEXIPORT_TELEMETRY) {
|
if (isComboboxOptionSelected(m_ui->cbFlexi, HwSettings::RM_FLEXIPORT_TELEMETRY)) {
|
||||||
m_ui->cbFlexi->setCurrentIndex(HwSettings::RM_FLEXIPORT_DISABLED);
|
setComboboxSelectedOption(m_ui->cbFlexi, HwSettings::RM_FLEXIPORT_DISABLED);
|
||||||
}
|
}
|
||||||
if (m_ui->cbRcvr->currentIndex() == HwSettings::RM_RCVRPORT_PPMTELEMETRY
|
if (isComboboxOptionSelected(m_ui->cbRcvr, HwSettings::RM_RCVRPORT_PPMTELEMETRY)
|
||||||
|| m_ui->cbRcvr->currentIndex() == HwSettings::RM_RCVRPORT_TELEMETRY) {
|
|| isComboboxOptionSelected(m_ui->cbRcvr, HwSettings::RM_RCVRPORT_TELEMETRY)) {
|
||||||
m_ui->cbRcvr->setCurrentIndex(HwSettings::RM_RCVRPORT_DISABLED);
|
setComboboxSelectedOption(m_ui->cbRcvr, HwSettings::RM_RCVRPORT_DISABLED);
|
||||||
}
|
}
|
||||||
break;
|
break;
|
||||||
case HwSettings::RM_MAINPORT_GPS:
|
case HwSettings::RM_MAINPORT_GPS:
|
||||||
@ -263,23 +269,26 @@ void ConfigRevoNanoHWWidget::mainPortChanged(int index)
|
|||||||
m_ui->lbMainGPSProtocol->setVisible(true);
|
m_ui->lbMainGPSProtocol->setVisible(true);
|
||||||
|
|
||||||
m_ui->cbMainGPSSpeed->setVisible(true);
|
m_ui->cbMainGPSSpeed->setVisible(true);
|
||||||
if (m_ui->cbFlexi->currentIndex() == HwSettings::RM_FLEXIPORT_GPS) {
|
if (isComboboxOptionSelected(m_ui->cbFlexi, HwSettings::RM_FLEXIPORT_GPS)) {
|
||||||
m_ui->cbFlexi->setCurrentIndex(HwSettings::RM_FLEXIPORT_DISABLED);
|
setComboboxSelectedOption(m_ui->cbFlexi, HwSettings::RM_FLEXIPORT_DISABLED);
|
||||||
}
|
}
|
||||||
break;
|
break;
|
||||||
case HwSettings::RM_MAINPORT_COMBRIDGE:
|
case HwSettings::RM_MAINPORT_COMBRIDGE:
|
||||||
m_ui->cbMainComSpeed->setVisible(true);
|
m_ui->cbMainComSpeed->setVisible(true);
|
||||||
if (m_ui->cbFlexi->currentIndex() == HwSettings::RM_FLEXIPORT_COMBRIDGE) {
|
if (isComboboxOptionSelected(m_ui->cbFlexi, HwSettings::RM_FLEXIPORT_COMBRIDGE)) {
|
||||||
m_ui->cbFlexi->setCurrentIndex(HwSettings::RM_FLEXIPORT_DISABLED);
|
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;
|
break;
|
||||||
case HwSettings::RM_MAINPORT_DEBUGCONSOLE:
|
case HwSettings::RM_MAINPORT_DEBUGCONSOLE:
|
||||||
m_ui->cbMainComSpeed->setVisible(true);
|
m_ui->cbMainComSpeed->setVisible(true);
|
||||||
if (m_ui->cbFlexi->currentIndex() == HwSettings::RM_FLEXIPORT_DEBUGCONSOLE) {
|
if (isComboboxOptionSelected(m_ui->cbFlexi, HwSettings::RM_FLEXIPORT_DEBUGCONSOLE)) {
|
||||||
m_ui->cbFlexi->setCurrentIndex(HwSettings::RM_FLEXIPORT_DISABLED);
|
setComboboxSelectedOption(m_ui->cbFlexi, HwSettings::RM_FLEXIPORT_DISABLED);
|
||||||
}
|
}
|
||||||
if (m_ui->cbUSBVCPFunction->currentIndex() == HwSettings::USB_VCPPORT_DEBUGCONSOLE) {
|
if (isComboboxOptionSelected(m_ui->cbUSBVCPFunction, HwSettings::USB_VCPPORT_DEBUGCONSOLE)) {
|
||||||
m_ui->cbUSBVCPFunction->setCurrentIndex(HwSettings::USB_VCPPORT_DISABLED);
|
setComboboxSelectedOption(m_ui->cbUSBVCPFunction, HwSettings::USB_VCPPORT_DISABLED);
|
||||||
}
|
}
|
||||||
break;
|
break;
|
||||||
default:
|
default:
|
||||||
@ -292,22 +301,33 @@ void ConfigRevoNanoHWWidget::rcvrPortChanged(int index)
|
|||||||
{
|
{
|
||||||
Q_UNUSED(index);
|
Q_UNUSED(index);
|
||||||
|
|
||||||
switch (m_ui->cbRcvr->currentIndex()) {
|
switch (getComboboxSelectedOption(m_ui->cbRcvr)) {
|
||||||
case HwSettings::RM_RCVRPORT_TELEMETRY:
|
case HwSettings::RM_RCVRPORT_TELEMETRY:
|
||||||
case HwSettings::RM_RCVRPORT_PPMTELEMETRY:
|
case HwSettings::RM_RCVRPORT_PPMTELEMETRY:
|
||||||
m_ui->lblRcvrSpeed->setVisible(true);
|
m_ui->lblRcvrSpeed->setVisible(true);
|
||||||
m_ui->cbRcvrTelemSpeed->setVisible(true);
|
m_ui->cbRcvrTelemSpeed->setVisible(true);
|
||||||
|
|
||||||
if (m_ui->cbFlexi->currentIndex() == HwSettings::RM_FLEXIPORT_TELEMETRY) {
|
if (isComboboxOptionSelected(m_ui->cbFlexi, HwSettings::RM_FLEXIPORT_TELEMETRY)) {
|
||||||
m_ui->cbFlexi->setCurrentIndex(HwSettings::RM_FLEXIPORT_DISABLED);
|
setComboboxSelectedOption(m_ui->cbFlexi, HwSettings::RM_FLEXIPORT_DISABLED);
|
||||||
}
|
}
|
||||||
if (m_ui->cbMain->currentIndex() == HwSettings::RM_FLEXIPORT_TELEMETRY) {
|
if (isComboboxOptionSelected(m_ui->cbMain, HwSettings::RM_FLEXIPORT_TELEMETRY)) {
|
||||||
m_ui->cbMain->setCurrentIndex(HwSettings::RM_FLEXIPORT_DISABLED);
|
setComboboxSelectedOption(m_ui->cbMain, HwSettings::RM_FLEXIPORT_DISABLED);
|
||||||
|
}
|
||||||
|
break;
|
||||||
|
case HwSettings::RM_RCVRPORT_COMBRIDGE:
|
||||||
|
m_ui->lblRcvrSpeed->setVisible(true);
|
||||||
|
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;
|
break;
|
||||||
default:
|
default:
|
||||||
m_ui->lblRcvrSpeed->setVisible(false);
|
m_ui->lblRcvrSpeed->setVisible(false);
|
||||||
m_ui->cbRcvrTelemSpeed->setVisible(false);
|
m_ui->cbRcvrTelemSpeed->setVisible(false);
|
||||||
|
m_ui->cbRcvrComSpeed->setVisible(false);
|
||||||
break;
|
break;
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
@ -232,7 +232,7 @@
|
|||||||
</spacer>
|
</spacer>
|
||||||
</item>
|
</item>
|
||||||
<item row="2" column="2">
|
<item row="2" column="2">
|
||||||
<layout class="QGridLayout" name="gridLayout" rowstretch="0,0,0,0,0,0,0,0,0,0,0,0,0,0">
|
<layout class="QGridLayout" name="gridLayout" rowstretch="0,0,0,0,0,0,0,0,0,0,0,0,0,0,0">
|
||||||
<item row="4" column="0">
|
<item row="4" column="0">
|
||||||
<widget class="QLabel" name="lblUSBVCPSpeed">
|
<widget class="QLabel" name="lblUSBVCPSpeed">
|
||||||
<property name="sizePolicy">
|
<property name="sizePolicy">
|
||||||
@ -302,6 +302,13 @@
|
|||||||
</property>
|
</property>
|
||||||
</widget>
|
</widget>
|
||||||
</item>
|
</item>
|
||||||
|
<item row="5" column="0">
|
||||||
|
<widget class="QComboBox" name="cbUSBVCPSpeed">
|
||||||
|
<property name="enabled">
|
||||||
|
<bool>true</bool>
|
||||||
|
</property>
|
||||||
|
</widget>
|
||||||
|
</item>
|
||||||
<item row="0" column="0">
|
<item row="0" column="0">
|
||||||
<widget class="QLabel" name="label_4">
|
<widget class="QLabel" name="label_4">
|
||||||
<property name="sizePolicy">
|
<property name="sizePolicy">
|
||||||
@ -334,19 +341,12 @@
|
|||||||
</property>
|
</property>
|
||||||
</widget>
|
</widget>
|
||||||
</item>
|
</item>
|
||||||
<item row="5" column="0">
|
|
||||||
<widget class="QComboBox" name="cbUSBVCPSpeed">
|
|
||||||
<property name="enabled">
|
|
||||||
<bool>true</bool>
|
|
||||||
</property>
|
|
||||||
</widget>
|
|
||||||
</item>
|
|
||||||
<item row="11" column="0" alignment="Qt::AlignTop">
|
|
||||||
<widget class="QComboBox" name="cbRcvrTelemSpeed"/>
|
|
||||||
</item>
|
|
||||||
<item row="9" column="0">
|
<item row="9" column="0">
|
||||||
<widget class="QComboBox" name="cbRcvr"/>
|
<widget class="QComboBox" name="cbRcvr"/>
|
||||||
</item>
|
</item>
|
||||||
|
<item row="9" column="2" colspan="2">
|
||||||
|
<widget class="QComboBox" name="cbMain"/>
|
||||||
|
</item>
|
||||||
<item row="2" column="0">
|
<item row="2" column="0">
|
||||||
<widget class="QLabel" name="label_8">
|
<widget class="QLabel" name="label_8">
|
||||||
<property name="sizePolicy">
|
<property name="sizePolicy">
|
||||||
@ -373,8 +373,8 @@
|
|||||||
</property>
|
</property>
|
||||||
</widget>
|
</widget>
|
||||||
</item>
|
</item>
|
||||||
<item row="9" column="2" colspan="2">
|
<item row="14" column="2" colspan="2">
|
||||||
<widget class="QComboBox" name="cbMain"/>
|
<widget class="QComboBox" name="cbMainGPSProtocol"/>
|
||||||
</item>
|
</item>
|
||||||
<item row="10" column="2" colspan="2">
|
<item row="10" column="2" colspan="2">
|
||||||
<widget class="QLabel" name="lblMainSpeed">
|
<widget class="QLabel" name="lblMainSpeed">
|
||||||
@ -406,7 +406,10 @@
|
|||||||
</item>
|
</item>
|
||||||
</layout>
|
</layout>
|
||||||
</item>
|
</item>
|
||||||
<item row="12" column="2" colspan="2">
|
<item row="5" column="1" colspan="2">
|
||||||
|
<widget class="QComboBox" name="cbFlexiGPSProtocol"/>
|
||||||
|
</item>
|
||||||
|
<item row="13" column="2" colspan="2">
|
||||||
<widget class="QLabel" name="lbMainGPSProtocol">
|
<widget class="QLabel" name="lbMainGPSProtocol">
|
||||||
<property name="text">
|
<property name="text">
|
||||||
<string>Protocol</string>
|
<string>Protocol</string>
|
||||||
@ -416,12 +419,6 @@
|
|||||||
</property>
|
</property>
|
||||||
</widget>
|
</widget>
|
||||||
</item>
|
</item>
|
||||||
<item row="13" column="2" colspan="2">
|
|
||||||
<widget class="QComboBox" name="cbMainGPSProtocol"/>
|
|
||||||
</item>
|
|
||||||
<item row="5" column="1" colspan="2">
|
|
||||||
<widget class="QComboBox" name="cbFlexiGPSProtocol"/>
|
|
||||||
</item>
|
|
||||||
<item row="4" column="1" colspan="2">
|
<item row="4" column="1" colspan="2">
|
||||||
<widget class="QLabel" name="lbFlexiGPSProtocol">
|
<widget class="QLabel" name="lbFlexiGPSProtocol">
|
||||||
<property name="text">
|
<property name="text">
|
||||||
@ -435,6 +432,9 @@
|
|||||||
</property>
|
</property>
|
||||||
</widget>
|
</widget>
|
||||||
</item>
|
</item>
|
||||||
|
<item row="1" column="1" colspan="2">
|
||||||
|
<widget class="QComboBox" name="cbFlexi"/>
|
||||||
|
</item>
|
||||||
<item row="3" column="1" colspan="2">
|
<item row="3" column="1" colspan="2">
|
||||||
<layout class="QVBoxLayout" name="verticalLayout_5">
|
<layout class="QVBoxLayout" name="verticalLayout_5">
|
||||||
<property name="spacing">
|
<property name="spacing">
|
||||||
@ -455,6 +455,16 @@
|
|||||||
</item>
|
</item>
|
||||||
</layout>
|
</layout>
|
||||||
</item>
|
</item>
|
||||||
|
<item row="0" column="1" colspan="2">
|
||||||
|
<widget class="QLabel" name="label_5">
|
||||||
|
<property name="text">
|
||||||
|
<string>Flexi Port</string>
|
||||||
|
</property>
|
||||||
|
<property name="alignment">
|
||||||
|
<set>Qt::AlignBottom|Qt::AlignHCenter</set>
|
||||||
|
</property>
|
||||||
|
</widget>
|
||||||
|
</item>
|
||||||
<item row="2" column="1" colspan="2">
|
<item row="2" column="1" colspan="2">
|
||||||
<widget class="QLabel" name="lblFlexiSpeed">
|
<widget class="QLabel" name="lblFlexiSpeed">
|
||||||
<property name="text">
|
<property name="text">
|
||||||
@ -465,18 +475,34 @@
|
|||||||
</property>
|
</property>
|
||||||
</widget>
|
</widget>
|
||||||
</item>
|
</item>
|
||||||
<item row="1" column="1" colspan="2">
|
<item row="11" column="0">
|
||||||
<widget class="QComboBox" name="cbFlexi"/>
|
<layout class="QVBoxLayout" name="verticalLayout_2">
|
||||||
</item>
|
<property name="spacing">
|
||||||
<item row="0" column="1" colspan="2">
|
<number>0</number>
|
||||||
<widget class="QLabel" name="label_5">
|
|
||||||
<property name="text">
|
|
||||||
<string>Flexi Port</string>
|
|
||||||
</property>
|
</property>
|
||||||
<property name="alignment">
|
<property name="topMargin">
|
||||||
<set>Qt::AlignBottom|Qt::AlignHCenter</set>
|
<number>0</number>
|
||||||
</property>
|
</property>
|
||||||
</widget>
|
<item>
|
||||||
|
<widget class="QComboBox" name="cbRcvrTelemSpeed"/>
|
||||||
|
</item>
|
||||||
|
<item alignment="Qt::AlignTop">
|
||||||
|
<widget class="QComboBox" name="cbRcvrComSpeed"/>
|
||||||
|
</item>
|
||||||
|
<item>
|
||||||
|
<spacer name="verticalSpacer_3">
|
||||||
|
<property name="orientation">
|
||||||
|
<enum>Qt::Vertical</enum>
|
||||||
|
</property>
|
||||||
|
<property name="sizeHint" stdset="0">
|
||||||
|
<size>
|
||||||
|
<width>20</width>
|
||||||
|
<height>40</height>
|
||||||
|
</size>
|
||||||
|
</property>
|
||||||
|
</spacer>
|
||||||
|
</item>
|
||||||
|
</layout>
|
||||||
</item>
|
</item>
|
||||||
</layout>
|
</layout>
|
||||||
</item>
|
</item>
|
||||||
@ -683,8 +709,8 @@ Beware of not locking yourself out!</string>
|
|||||||
</layout>
|
</layout>
|
||||||
</widget>
|
</widget>
|
||||||
<resources>
|
<resources>
|
||||||
<include location="configgadget.qrc"/>
|
|
||||||
<include location="../coreplugin/core.qrc"/>
|
<include location="../coreplugin/core.qrc"/>
|
||||||
|
<include location="configgadget.qrc"/>
|
||||||
</resources>
|
</resources>
|
||||||
<connections/>
|
<connections/>
|
||||||
</ui>
|
</ui>
|
||||||
|
Loading…
x
Reference in New Issue
Block a user