diff --git a/flight/modules/StateEstimation/stateestimation.c b/flight/modules/StateEstimation/stateestimation.c index 3ed9dfe02..60ed1149b 100644 --- a/flight/modules/StateEstimation/stateestimation.c +++ b/flight/modules/StateEstimation/stateestimation.c @@ -42,6 +42,7 @@ #include #include #include +#include #include #include @@ -254,7 +255,7 @@ static const filterPipeline *ekf13Queue = &(filterPipeline) { static void settingsUpdatedCb(UAVObjEvent *objEv); static void sensorUpdatedCb(UAVObjEvent *objEv); -static void homeLocationUpdatedCb(UAVObjEvent *objEv); +static void criticalConfigUpdatedCb(UAVObjEvent *objEv); static void StateEstimationCb(void); static inline int32_t maxint32_t(int32_t a, int32_t b) @@ -289,10 +290,12 @@ int32_t StateEstimationInitialize(void) AirspeedStateInitialize(); PositionStateInitialize(); VelocityStateInitialize(); + AuxMagSettingsInitialize(); RevoSettingsConnectCallback(&settingsUpdatedCb); - HomeLocationConnectCallback(&homeLocationUpdatedCb); + HomeLocationConnectCallback(&criticalConfigUpdatedCb); + AuxMagSettingsConnectCallback(&criticalConfigUpdatedCb); GyroSensorConnectCallback(&sensorUpdatedCb); AccelSensorConnectCallback(&sensorUpdatedCb); @@ -538,9 +541,9 @@ static void settingsUpdatedCb(__attribute__((unused)) UAVObjEvent *ev) } /** - * Callback for eventdispatcher when HomeLocation has been updated + * Callback for eventdispatcher when HomeLocation or other critical configs (auxmagsettings, ...) has been updated */ -static void homeLocationUpdatedCb(__attribute__((unused)) UAVObjEvent *ev) +static void criticalConfigUpdatedCb(__attribute__((unused)) UAVObjEvent *ev) { // Ask for a filter init (necessary for LLA filter) // Only possible if disarmed 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/ground/openpilotgcs/src/plugins/config/configrevonanohwwidget.cpp b/ground/openpilotgcs/src/plugins/config/configrevonanohwwidget.cpp index 51f92d04a..32e8199df 100644 --- a/ground/openpilotgcs/src/plugins/config/configrevonanohwwidget.cpp +++ b/ground/openpilotgcs/src/plugins/config/configrevonanohwwidget.cpp @@ -68,6 +68,7 @@ ConfigRevoNanoHWWidget::ConfigRevoNanoHWWidget(QWidget *parent) : ConfigTaskWidg 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); @@ -118,7 +119,8 @@ void ConfigRevoNanoHWWidget::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; @@ -131,38 +133,40 @@ void ConfigRevoNanoHWWidget::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 && 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 - 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); } } @@ -171,10 +175,9 @@ void ConfigRevoNanoHWWidget::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); } } @@ -191,15 +194,15 @@ void ConfigRevoNanoHWWidget::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: @@ -208,23 +211,26 @@ void ConfigRevoNanoHWWidget::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: @@ -246,15 +252,15 @@ void ConfigRevoNanoHWWidget::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: @@ -263,23 +269,26 @@ void ConfigRevoNanoHWWidget::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: @@ -292,22 +301,33 @@ void ConfigRevoNanoHWWidget::rcvrPortChanged(int index) { Q_UNUSED(index); - switch (m_ui->cbRcvr->currentIndex()) { + m_ui->lblRcvrSpeed->setVisible(true); + m_ui->cbRcvrTelemSpeed->setVisible(false); + m_ui->cbRcvrComSpeed->setVisible(false); + + 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/configrevonanohwwidget.ui b/ground/openpilotgcs/src/plugins/config/configrevonanohwwidget.ui index c0862ed64..1f7cb0a91 100644 --- a/ground/openpilotgcs/src/plugins/config/configrevonanohwwidget.ui +++ b/ground/openpilotgcs/src/plugins/config/configrevonanohwwidget.ui @@ -232,7 +232,7 @@ - + @@ -302,6 +302,13 @@ + + + + true + + + @@ -334,19 +341,12 @@ - - - - true - - - - - - + + + @@ -373,8 +373,8 @@ - - + + @@ -406,7 +406,10 @@ - + + + + Protocol @@ -416,12 +419,6 @@ - - - - - - @@ -435,6 +432,9 @@ + + + @@ -455,6 +455,16 @@ + + + + Flexi Port + + + Qt::AlignBottom|Qt::AlignHCenter + + + @@ -465,18 +475,34 @@ - - - - - - - Flexi Port + + + + 0 - - Qt::AlignBottom|Qt::AlignHCenter + + 0 - + + + + + + + + + + Qt::Vertical + + + + 20 + 40 + + + + + @@ -683,8 +709,8 @@ Beware of not locking yourself out! - + diff --git a/ground/openpilotgcs/src/plugins/uavobjectwidgetutils/configtaskwidget.cpp b/ground/openpilotgcs/src/plugins/uavobjectwidgetutils/configtaskwidget.cpp index eed01b3a9..6e246db32 100644 --- a/ground/openpilotgcs/src/plugins/uavobjectwidgetutils/configtaskwidget.cpp +++ b/ground/openpilotgcs/src/plugins/uavobjectwidgetutils/configtaskwidget.cpp @@ -209,6 +209,39 @@ ConfigTaskWidget::~ConfigTaskWidget() } } +bool ConfigTaskWidget::isComboboxOptionSelected(QComboBox *combo, int optionValue) +{ + bool ok; + int value = combo->currentData().toInt(&ok); + return ok ? value == optionValue : false; +} + +int ConfigTaskWidget::getComboboxSelectedOption(QComboBox *combo) +{ + bool ok; + int index = combo->currentData().toInt(&ok); + return ok ? index : -1; +} + +void ConfigTaskWidget::setComboboxSelectedOption(QComboBox *combo, int optionValue) +{ + int index = combo->findData(QVariant(optionValue)); + if (index != -1) { + combo->setCurrentIndex(index); + } +} + +int ConfigTaskWidget::getComboboxIndexForOption(QComboBox *combo, int optionValue) +{ + return combo->findData(QVariant(optionValue)); +} + +void ConfigTaskWidget::enableComboBoxOptionItem(QComboBox *combo, int optionValue, bool enable) +{ + combo->model()->setData(combo->model()->index(getComboboxIndexForOption(combo, optionValue), 0), + !enable ? QVariant(0) : QVariant(1 | 32), Qt::UserRole - 1); +} + void ConfigTaskWidget::saveObjectToSD(UAVObject *obj) { // saveObjectToSD is now handled by the UAVUtils plugin in one @@ -858,7 +891,7 @@ QVariant ConfigTaskWidget::getVariantFromWidget(QWidget *widget, WidgetBinding * if (QComboBox * cb = qobject_cast(widget)) { if (binding->isInteger()) { - return cb->currentIndex(); + return QVariant(getComboboxSelectedOption(cb)); } return (QString)cb->currentText(); } else if (QDoubleSpinBox * cb = qobject_cast(widget)) { @@ -889,7 +922,7 @@ bool ConfigTaskWidget::setWidgetFromVariant(QWidget *widget, QVariant value, Wid if (QComboBox * cb = qobject_cast(widget)) { bool ok = true; if (binding->isInteger()) { - cb->setCurrentIndex(value.toInt(&ok)); + setComboboxSelectedOption(cb, value.toInt(&ok)); } else { cb->setCurrentIndex(cb->findText(value.toString())); } @@ -1004,22 +1037,16 @@ void ConfigTaskWidget::loadWidgetLimits(QWidget *widget, UAVObjectField *field, } if (QComboBox * cb = qobject_cast(widget)) { cb->clear(); - QStringList option = field->getOptions(); - if (hasLimits) { - // Only add options to combo box if we have a board id to check limits for. - // We could enter this method while there is no board connected and without - // this check, we would add all the board dependent options whether they were - // valid or not. Ultimately this method will be called again when the connected - // signal is handled. - if (m_currentBoardId > -1) { - foreach(QString str, option) { - if (field->isWithinLimits(str, index, m_currentBoardId)) { - cb->addItem(str); - } + QStringList options = field->getOptions(); + + for(int optionIndex = 0; optionIndex < options.count(); optionIndex++) { + if (hasLimits) { + if (m_currentBoardId > -1 && field->isWithinLimits(options.at(optionIndex), index, m_currentBoardId)) { + cb->addItem(options.at(optionIndex), QVariant(optionIndex)); } + } else { + cb->addItem(options.at(optionIndex), QVariant(optionIndex)); } - } else { - cb->addItems(option); } } if (!hasLimits) { diff --git a/ground/openpilotgcs/src/plugins/uavobjectwidgetutils/configtaskwidget.h b/ground/openpilotgcs/src/plugins/uavobjectwidgetutils/configtaskwidget.h index ada25ec80..7809df602 100644 --- a/ground/openpilotgcs/src/plugins/uavobjectwidgetutils/configtaskwidget.h +++ b/ground/openpilotgcs/src/plugins/uavobjectwidgetutils/configtaskwidget.h @@ -104,6 +104,13 @@ public: ConfigTaskWidget(QWidget *parent = 0); virtual ~ConfigTaskWidget(); + // Combobox helper functions + static bool isComboboxOptionSelected(QComboBox *combo, int optionValue); + static int getComboboxSelectedOption(QComboBox *combo); + static void setComboboxSelectedOption(QComboBox *combo, int optionValue); + static int getComboboxIndexForOption(QComboBox *combo, int optionValue); + static void enableComboBoxOptionItem(QComboBox *combo, int optionValue, bool enable); + void disableMouseWheelEvents(); bool eventFilter(QObject *obj, QEvent *evt); 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;"/>