mirror of
https://bitbucket.org/librepilot/librepilot.git
synced 2025-01-19 04:52:12 +01:00
Merged in mindnever/librepilot/LP-377_ComBridge_Speed_settings_delete (pull request #301)
LP-377 USB ComBridge Speed settings delete
This commit is contained in:
commit
2e669fa322
@ -32,7 +32,6 @@
|
||||
|
||||
#include <openpilot.h>
|
||||
|
||||
#include "hwsettings.h"
|
||||
#include "taskinfo.h"
|
||||
|
||||
#include <stdbool.h>
|
||||
@ -42,8 +41,9 @@
|
||||
|
||||
static void com2UsbBridgeTask(void *parameters);
|
||||
static void usb2ComBridgeTask(void *parameters);
|
||||
static void updateSettings(UAVObjEvent *ev);
|
||||
static void usb2ComBridgeSetCtrlLine(uint32_t com_id, uint32_t mask, uint32_t state);
|
||||
static void usb2ComBridgeSetBaudRate(uint32_t com_id, uint32_t baud);
|
||||
|
||||
|
||||
// ****************
|
||||
// Private constants
|
||||
@ -105,15 +105,14 @@ static int32_t comUsbBridgeInitialize(void)
|
||||
PIOS_COM_RegisterCtrlLineCallback(vcp_port,
|
||||
usb2ComBridgeSetCtrlLine,
|
||||
usart_port);
|
||||
PIOS_COM_RegisterBaudRateCallback(vcp_port,
|
||||
usb2ComBridgeSetBaudRate,
|
||||
usart_port);
|
||||
}
|
||||
|
||||
#ifdef MODULE_COMUSBBRIDGE_BUILTIN
|
||||
bridge_enabled = true;
|
||||
#else
|
||||
HwSettingsInitialize();
|
||||
HwSettingsOptionalModulesData optionalModules;
|
||||
|
||||
HwSettingsOptionalModulesGet(&optionalModules);
|
||||
|
||||
if (usart_port && vcp_port) {
|
||||
bridge_enabled = true;
|
||||
@ -127,8 +126,6 @@ static int32_t comUsbBridgeInitialize(void)
|
||||
PIOS_Assert(com2usb_buf);
|
||||
usb2com_buf = pios_malloc(BRIDGE_BUF_LEN);
|
||||
PIOS_Assert(usb2com_buf);
|
||||
HwSettingsConnectCallback(&updateSettings);
|
||||
updateSettings(0);
|
||||
}
|
||||
|
||||
return 0;
|
||||
@ -186,36 +183,7 @@ static void usb2ComBridgeSetCtrlLine(uint32_t com_id, uint32_t mask, uint32_t st
|
||||
PIOS_COM_SetCtrlLine(com_id, mask, state);
|
||||
}
|
||||
|
||||
static void updateSettings(__attribute__((unused)) UAVObjEvent *ev)
|
||||
static void usb2ComBridgeSetBaudRate(uint32_t com_id, uint32_t baud)
|
||||
{
|
||||
if (usart_port) {
|
||||
// Retrieve settings
|
||||
uint8_t speed;
|
||||
HwSettingsComUsbBridgeSpeedGet(&speed);
|
||||
|
||||
// Set port speed
|
||||
switch (speed) {
|
||||
case HWSETTINGS_COMUSBBRIDGESPEED_2400:
|
||||
PIOS_COM_ChangeBaud(usart_port, 2400);
|
||||
break;
|
||||
case HWSETTINGS_COMUSBBRIDGESPEED_4800:
|
||||
PIOS_COM_ChangeBaud(usart_port, 4800);
|
||||
break;
|
||||
case HWSETTINGS_COMUSBBRIDGESPEED_9600:
|
||||
PIOS_COM_ChangeBaud(usart_port, 9600);
|
||||
break;
|
||||
case HWSETTINGS_COMUSBBRIDGESPEED_19200:
|
||||
PIOS_COM_ChangeBaud(usart_port, 19200);
|
||||
break;
|
||||
case HWSETTINGS_COMUSBBRIDGESPEED_38400:
|
||||
PIOS_COM_ChangeBaud(usart_port, 38400);
|
||||
break;
|
||||
case HWSETTINGS_COMUSBBRIDGESPEED_57600:
|
||||
PIOS_COM_ChangeBaud(usart_port, 57600);
|
||||
break;
|
||||
case HWSETTINGS_COMUSBBRIDGESPEED_115200:
|
||||
PIOS_COM_ChangeBaud(usart_port, 115200);
|
||||
break;
|
||||
}
|
||||
}
|
||||
PIOS_COM_ChangeBaud(com_id, baud);
|
||||
}
|
||||
|
@ -333,6 +333,30 @@ int32_t PIOS_COM_RegisterCtrlLineCallback(uint32_t com_id, pios_com_callback_ctr
|
||||
return 0;
|
||||
}
|
||||
|
||||
/**
|
||||
* Set baud rate callback associated with the port
|
||||
* \param[in] port COM port
|
||||
* \param[in] baud_rate_cb Callback function
|
||||
* \param[in] context context to pass to the callback function
|
||||
* \return -1 if port not available
|
||||
* \return 0 on success
|
||||
*/
|
||||
int32_t PIOS_COM_RegisterBaudRateCallback(uint32_t com_id, pios_com_callback_baud_rate baud_rate_cb, uint32_t context)
|
||||
{
|
||||
struct pios_com_dev *com_dev = (struct pios_com_dev *)com_id;
|
||||
|
||||
if (!PIOS_COM_validate(com_dev)) {
|
||||
/* Undefined COM port for this board (see pios_board.c) */
|
||||
return -1;
|
||||
}
|
||||
|
||||
/* Invoke the driver function if it exists */
|
||||
if (com_dev->driver->bind_baud_rate_cb) {
|
||||
com_dev->driver->bind_baud_rate_cb(com_dev->lower_id, baud_rate_cb, context);
|
||||
}
|
||||
|
||||
return 0;
|
||||
}
|
||||
|
||||
static int32_t PIOS_COM_SendBufferNonBlockingInternal(struct pios_com_dev *com_dev, const uint8_t *buffer, uint16_t len)
|
||||
{
|
||||
|
@ -37,6 +37,7 @@
|
||||
|
||||
typedef uint16_t (*pios_com_callback)(uint32_t context, uint8_t *buf, uint16_t buf_len, uint16_t *headroom, bool *task_woken);
|
||||
typedef void (*pios_com_callback_ctrl_line)(uint32_t context, uint32_t mask, uint32_t state);
|
||||
typedef void (*pios_com_callback_baud_rate)(uint32_t context, uint32_t baud);
|
||||
|
||||
struct pios_com_driver {
|
||||
void (*init)(uint32_t id);
|
||||
@ -47,6 +48,7 @@ struct pios_com_driver {
|
||||
void (*bind_rx_cb)(uint32_t id, pios_com_callback rx_in_cb, uint32_t context);
|
||||
void (*bind_tx_cb)(uint32_t id, pios_com_callback tx_out_cb, uint32_t context);
|
||||
void (*bind_ctrl_line_cb)(uint32_t id, pios_com_callback_ctrl_line ctrl_line_cb, uint32_t context);
|
||||
void (*bind_baud_rate_cb)(uint32_t id, pios_com_callback_baud_rate baud_rate_cb, uint32_t context);
|
||||
uint32_t (*available)(uint32_t id);
|
||||
};
|
||||
|
||||
@ -59,6 +61,7 @@ extern int32_t PIOS_COM_Init(uint32_t *com_id, const struct pios_com_driver *dri
|
||||
extern int32_t PIOS_COM_ChangeBaud(uint32_t com_id, uint32_t baud);
|
||||
extern int32_t PIOS_COM_SetCtrlLine(uint32_t com_id, uint32_t mask, uint32_t state);
|
||||
extern int32_t PIOS_COM_RegisterCtrlLineCallback(uint32_t usart_id, pios_com_callback_ctrl_line ctrl_line_cb, uint32_t context);
|
||||
extern int32_t PIOS_COM_RegisterBaudRateCallback(uint32_t usart_id, pios_com_callback_baud_rate baud_rate_cb, uint32_t context);
|
||||
extern int32_t PIOS_COM_SendCharNonBlocking(uint32_t com_id, char c);
|
||||
extern int32_t PIOS_COM_SendChar(uint32_t com_id, char c);
|
||||
extern int32_t PIOS_COM_SendBufferNonBlocking(uint32_t com_id, const uint8_t *buffer, uint16_t len);
|
||||
|
@ -83,6 +83,9 @@ enum usb_ep_attr {
|
||||
#define htousbl(v) (v)
|
||||
#endif
|
||||
|
||||
#define usbstoh(v) htousbs(v)
|
||||
#define usbltoh(v) htousbl(v)
|
||||
|
||||
#define USB_EP_IN(ep) ((uint8_t)(0x80 | ((ep) & 0xF)))
|
||||
#define USB_EP_OUT(ep) ((uint8_t)(0x00 | ((ep) & 0xF)))
|
||||
|
||||
|
@ -41,6 +41,7 @@
|
||||
|
||||
static void PIOS_USB_CDC_RegisterTxCallback(uint32_t usbcdc_id, pios_com_callback tx_out_cb, uint32_t context);
|
||||
static void PIOS_USB_CDC_RegisterRxCallback(uint32_t usbcdc_id, pios_com_callback rx_in_cb, uint32_t context);
|
||||
static void PIOS_USB_CDC_RegisterBaudRateCallback(uint32_t usbcdc_id, pios_com_callback_baud_rate baud_rate_cb, uint32_t context);
|
||||
static void PIOS_USB_CDC_TxStart(uint32_t usbcdc_id, uint16_t tx_bytes_avail);
|
||||
static void PIOS_USB_CDC_RxStart(uint32_t usbcdc_id, uint16_t rx_bytes_avail);
|
||||
static uint32_t PIOS_USB_CDC_Available(uint32_t usbcdc_id);
|
||||
@ -50,6 +51,7 @@ const struct pios_com_driver pios_usb_cdc_com_driver = {
|
||||
.rx_start = PIOS_USB_CDC_RxStart,
|
||||
.bind_tx_cb = PIOS_USB_CDC_RegisterTxCallback,
|
||||
.bind_rx_cb = PIOS_USB_CDC_RegisterRxCallback,
|
||||
.bind_baud_rate_cb = PIOS_USB_CDC_RegisterBaudRateCallback,
|
||||
.available = PIOS_USB_CDC_Available,
|
||||
};
|
||||
|
||||
@ -68,6 +70,9 @@ struct pios_usb_cdc_dev {
|
||||
pios_com_callback tx_out_cb;
|
||||
uint32_t tx_out_context;
|
||||
|
||||
pios_com_callback_baud_rate baud_rate_cb;
|
||||
uint32_t baud_rate_context;
|
||||
|
||||
uint8_t rx_packet_buffer[PIOS_USB_BOARD_CDC_DATA_LENGTH];
|
||||
/*
|
||||
* NOTE: This is -1 as somewhat of a hack. It ensures that we always send packets
|
||||
@ -450,4 +455,37 @@ static void PIOS_USB_CDC_CTRL_EP_IN_Callback(void)
|
||||
SetEPTxValid(usb_cdc_dev->cfg->ctrl_tx_ep);
|
||||
}
|
||||
|
||||
static void PIOS_USB_CDC_RegisterBaudRateCallback(uint32_t usbcdc_id, pios_com_callback_baud_rate baud_rate_cb, uint32_t context)
|
||||
{
|
||||
struct pios_usb_cdc_dev *usb_cdc_dev = (struct pios_usb_cdc_dev *)usbcdc_id;
|
||||
|
||||
bool valid = PIOS_USB_CDC_validate(usb_cdc_dev);
|
||||
|
||||
PIOS_Assert(valid);
|
||||
|
||||
/*
|
||||
* Order is important in these assignments since ISR uses _cb
|
||||
* field to determine if it's ok to dereference _cb and _context
|
||||
*/
|
||||
usb_cdc_dev->baud_rate_context = context;
|
||||
usb_cdc_dev->baud_rate_cb = baud_rate_cb;
|
||||
}
|
||||
|
||||
void PIOS_USB_CDC_SetLineCoding_Completed()
|
||||
{
|
||||
struct pios_usb_cdc_dev *usb_cdc_dev = (struct pios_usb_cdc_dev *)pios_usb_cdc_id;
|
||||
|
||||
bool valid = PIOS_USB_CDC_validate(usb_cdc_dev);
|
||||
|
||||
if (!valid) {
|
||||
/* No CDC interface is configured */
|
||||
return;
|
||||
}
|
||||
|
||||
if (usb_cdc_dev->baud_rate_cb) {
|
||||
usb_cdc_dev->baud_rate_cb(usb_cdc_dev->baud_rate_context, usbltoh(line_coding.dwDTERate));
|
||||
}
|
||||
}
|
||||
|
||||
|
||||
#endif /* PIOS_INCLUDE_USB_CDC */
|
||||
|
@ -42,6 +42,8 @@
|
||||
/* STM32 USB Library Definitions */
|
||||
#include "usb_lib.h"
|
||||
|
||||
static void (*ep0_rxready_cb)(void) = 0;
|
||||
|
||||
static ONE_DESCRIPTOR Device_Descriptor;
|
||||
|
||||
void PIOS_USBHOOK_RegisterDevice(const uint8_t *desc, uint16_t desc_size)
|
||||
@ -275,7 +277,13 @@ static void PIOS_USBHOOK_SetDeviceAddress(void)
|
||||
* Return : None.
|
||||
*******************************************************************************/
|
||||
static void PIOS_USBHOOK_Status_In(void)
|
||||
{}
|
||||
{
|
||||
/* this callback gets executed after sending ZLP and doing In0_Process(), to ack */
|
||||
if (ep0_rxready_cb) {
|
||||
ep0_rxready_cb();
|
||||
ep0_rxready_cb = 0;
|
||||
}
|
||||
}
|
||||
|
||||
/*******************************************************************************
|
||||
* Function Name : PIOS_USBHOOK_Status_Out
|
||||
@ -296,6 +304,7 @@ static void PIOS_USBHOOK_Status_Out(void)
|
||||
*******************************************************************************/
|
||||
extern uint8_t *PIOS_USB_CDC_SetLineCoding(uint16_t Length);
|
||||
extern const uint8_t *PIOS_USB_CDC_GetLineCoding(uint16_t Length);
|
||||
extern void PIOS_USB_CDC_SetLineCoding_Completed();
|
||||
|
||||
static RESULT PIOS_USBHOOK_Data_Setup(uint8_t RequestNo)
|
||||
{
|
||||
@ -305,6 +314,7 @@ static RESULT PIOS_USBHOOK_Data_Setup(uint8_t RequestNo)
|
||||
CopyInRoutine = NULL;
|
||||
CopyOutRoutine = NULL;
|
||||
|
||||
|
||||
switch (Type_Recipient) {
|
||||
case (STANDARD_REQUEST | INTERFACE_RECIPIENT):
|
||||
switch (pInformation->USBwIndex0) {
|
||||
@ -346,6 +356,7 @@ static RESULT PIOS_USBHOOK_Data_Setup(uint8_t RequestNo)
|
||||
switch (RequestNo) {
|
||||
case USB_CDC_REQ_SET_LINE_CODING:
|
||||
CopyOutRoutine = PIOS_USB_CDC_SetLineCoding;
|
||||
ep0_rxready_cb = PIOS_USB_CDC_SetLineCoding_Completed;
|
||||
break;
|
||||
case USB_CDC_REQ_GET_LINE_CODING:
|
||||
CopyInRoutine = PIOS_USB_CDC_GetLineCoding;
|
||||
|
@ -41,6 +41,7 @@
|
||||
static void PIOS_USB_CDC_RegisterTxCallback(uint32_t usbcdc_id, pios_com_callback tx_out_cb, uint32_t context);
|
||||
static void PIOS_USB_CDC_RegisterRxCallback(uint32_t usbcdc_id, pios_com_callback rx_in_cb, uint32_t context);
|
||||
static void PIOS_USB_CDC_RegisterCtrlLineCallback(uint32_t usbcdc_id, pios_com_callback_ctrl_line ctrl_line_cb, uint32_t context);
|
||||
static void PIOS_USB_CDC_RegisterBaudRateCallback(uint32_t usbcdc_id, pios_com_callback_baud_rate baud_rate_cb, uint32_t context);
|
||||
static void PIOS_USB_CDC_TxStart(uint32_t usbcdc_id, uint16_t tx_bytes_avail);
|
||||
static void PIOS_USB_CDC_RxStart(uint32_t usbcdc_id, uint16_t rx_bytes_avail);
|
||||
static uint32_t PIOS_USB_CDC_Available(uint32_t usbcdc_id);
|
||||
@ -51,6 +52,7 @@ const struct pios_com_driver pios_usb_cdc_com_driver = {
|
||||
.bind_tx_cb = PIOS_USB_CDC_RegisterTxCallback,
|
||||
.bind_rx_cb = PIOS_USB_CDC_RegisterRxCallback,
|
||||
.bind_ctrl_line_cb = PIOS_USB_CDC_RegisterCtrlLineCallback,
|
||||
.bind_baud_rate_cb = PIOS_USB_CDC_RegisterBaudRateCallback,
|
||||
.available = PIOS_USB_CDC_Available,
|
||||
};
|
||||
|
||||
@ -70,6 +72,8 @@ struct pios_usb_cdc_dev {
|
||||
uint32_t tx_out_context;
|
||||
pios_com_callback_ctrl_line ctrl_line_cb;
|
||||
uint32_t ctrl_line_context;
|
||||
pios_com_callback_baud_rate baud_rate_cb;
|
||||
uint32_t baud_rate_context;
|
||||
|
||||
bool usb_ctrl_if_enabled;
|
||||
bool usb_data_if_enabled;
|
||||
@ -343,6 +347,21 @@ static void PIOS_USB_CDC_RegisterCtrlLineCallback(uint32_t usbcdc_id, pios_com_c
|
||||
usb_cdc_dev->ctrl_line_cb = ctrl_line_cb;
|
||||
}
|
||||
|
||||
static void PIOS_USB_CDC_RegisterBaudRateCallback(uint32_t usbcdc_id, pios_com_callback_baud_rate baud_rate_cb, uint32_t context)
|
||||
{
|
||||
struct pios_usb_cdc_dev *usb_cdc_dev = (struct pios_usb_cdc_dev *)usbcdc_id;
|
||||
|
||||
bool valid = PIOS_USB_CDC_validate(usb_cdc_dev);
|
||||
|
||||
PIOS_Assert(valid);
|
||||
|
||||
/*
|
||||
* Order is important in these assignments since ISR uses _cb
|
||||
* field to determine if it's ok to dereference _cb and _context
|
||||
*/
|
||||
usb_cdc_dev->baud_rate_context = context;
|
||||
usb_cdc_dev->baud_rate_cb = baud_rate_cb;
|
||||
}
|
||||
|
||||
static bool PIOS_USB_CDC_CTRL_EP_IN_Callback(uint32_t usb_cdc_id, uint8_t epnum, uint16_t len);
|
||||
|
||||
@ -488,13 +507,9 @@ static void PIOS_USB_CDC_CTRL_IF_CtrlDataOut(uint32_t usb_cdc_id, const struct u
|
||||
case (USB_REQ_TYPE_CLASS | USB_REQ_RECIPIENT_INTERFACE):
|
||||
switch (req->bRequest) {
|
||||
case USB_CDC_REQ_SET_LINE_CODING:
|
||||
/*
|
||||
* If we cared to, this is where we would apply the new line coding
|
||||
* that is now stored in the line_coding struct. This could be used
|
||||
* to notify the upper COM layer that the baud rate has changed. This
|
||||
* may be useful in the case of a COM USB bridge where we would
|
||||
* auto-adjust the USART baud rate based on the line coding set here.
|
||||
*/
|
||||
if (usb_cdc_dev->baud_rate_cb) {
|
||||
usb_cdc_dev->baud_rate_cb(usb_cdc_dev->baud_rate_context, usbltoh(line_coding.dwDTERate));
|
||||
}
|
||||
break;
|
||||
default:
|
||||
/* Unhandled class request */
|
||||
|
@ -254,13 +254,6 @@
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
<item row="1" column="1">
|
||||
<widget class="QComboBox" name="comUsbBridgeSpeed">
|
||||
<property name="toolTip">
|
||||
<string>Select the speed here.</string>
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
<item row="2" column="1">
|
||||
<widget class="QComboBox" name="gpsSpeed">
|
||||
<property name="toolTip">
|
||||
@ -268,19 +261,6 @@
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
<item row="1" column="0">
|
||||
<widget class="QLabel" name="ComUsbBridgeSpeedLabel">
|
||||
<property name="minimumSize">
|
||||
<size>
|
||||
<width>55</width>
|
||||
<height>0</height>
|
||||
</size>
|
||||
</property>
|
||||
<property name="text">
|
||||
<string>ComUsbBridge speed:</string>
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
<item row="3" column="0">
|
||||
<widget class="QLabel" name="GpsProtocolLabel">
|
||||
<property name="text">
|
||||
|
@ -99,7 +99,6 @@ ConfigCCHWWidget::ConfigCCHWWidget(QWidget *parent) : ConfigTaskWidget(parent)
|
||||
addWidgetBinding("GPSSettings", "DataProtocol", m_telemetry->gpsProtocol);
|
||||
}
|
||||
|
||||
addWidgetBinding("HwSettings", "ComUsbBridgeSpeed", m_telemetry->comUsbBridgeSpeed);
|
||||
connect(m_telemetry->cchwHelp, SIGNAL(clicked()), this, SLOT(openHelp()));
|
||||
enableSaveButtons(false);
|
||||
populateWidgets();
|
||||
|
@ -59,19 +59,15 @@ ConfigRevoHWWidget::ConfigRevoHWWidget(QWidget *parent) : ConfigTaskWidget(paren
|
||||
|
||||
addWidgetBinding("HwSettings", "USB_HIDPort", m_ui->cbUSBHIDFunction);
|
||||
addWidgetBinding("HwSettings", "USB_VCPPort", m_ui->cbUSBVCPFunction);
|
||||
addWidgetBinding("HwSettings", "ComUsbBridgeSpeed", m_ui->cbUSBVCPSpeed);
|
||||
|
||||
addWidgetBinding("HwSettings", "TelemetrySpeed", m_ui->cbFlexiTelemSpeed);
|
||||
addWidgetBinding("HwSettings", "GPSSpeed", m_ui->cbFlexiGPSSpeed);
|
||||
addWidgetBinding("HwSettings", "ComUsbBridgeSpeed", m_ui->cbFlexiComSpeed);
|
||||
|
||||
addWidgetBinding("HwSettings", "TelemetrySpeed", m_ui->cbMainTelemSpeed);
|
||||
addWidgetBinding("HwSettings", "GPSSpeed", m_ui->cbMainGPSSpeed);
|
||||
addWidgetBinding("HwSettings", "ComUsbBridgeSpeed", m_ui->cbMainComSpeed);
|
||||
|
||||
addWidgetBinding("HwSettings", "TelemetrySpeed", m_ui->cbRcvrTelemSpeed);
|
||||
addWidgetBinding("HwSettings", "GPSSpeed", m_ui->cbRcvrGPSSpeed);
|
||||
addWidgetBinding("HwSettings", "ComUsbBridgeSpeed", m_ui->cbRcvrComSpeed);
|
||||
|
||||
// Add Gps protocol configuration
|
||||
addWidgetBinding("GPSSettings", "DataProtocol", m_ui->cbMainGPSProtocol);
|
||||
@ -144,9 +140,6 @@ void ConfigRevoHWWidget::usbVCPPortChanged(int index)
|
||||
|
||||
bool vcpComBridgeEnabled = isComboboxOptionSelected(m_ui->cbUSBVCPFunction, HwSettings::USB_VCPPORT_COMBRIDGE);
|
||||
|
||||
m_ui->lblUSBVCPSpeed->setVisible(vcpComBridgeEnabled);
|
||||
m_ui->cbUSBVCPSpeed->setVisible(vcpComBridgeEnabled);
|
||||
|
||||
if (!vcpComBridgeEnabled && isComboboxOptionSelected(m_ui->cbFlexi, HwSettings::RM_FLEXIPORT_COMBRIDGE)) {
|
||||
setComboboxSelectedOption(m_ui->cbFlexi, HwSettings::RM_FLEXIPORT_DISABLED);
|
||||
}
|
||||
@ -207,7 +200,6 @@ void ConfigRevoHWWidget::flexiPortChanged(int index)
|
||||
|
||||
m_ui->cbFlexiTelemSpeed->setVisible(false);
|
||||
m_ui->cbFlexiGPSSpeed->setVisible(false);
|
||||
m_ui->cbFlexiComSpeed->setVisible(false);
|
||||
m_ui->lblFlexiSpeed->setVisible(true);
|
||||
|
||||
// Add Gps protocol configuration
|
||||
@ -245,7 +237,7 @@ void ConfigRevoHWWidget::flexiPortChanged(int index)
|
||||
|
||||
break;
|
||||
case HwSettings::RM_FLEXIPORT_COMBRIDGE:
|
||||
m_ui->cbFlexiComSpeed->setVisible(true);
|
||||
m_ui->lblFlexiSpeed->setVisible(false);
|
||||
if (isComboboxOptionSelected(m_ui->cbMain, HwSettings::RM_MAINPORT_COMBRIDGE)) {
|
||||
setComboboxSelectedOption(m_ui->cbMain, HwSettings::RM_MAINPORT_DISABLED);
|
||||
}
|
||||
@ -257,7 +249,7 @@ void ConfigRevoHWWidget::flexiPortChanged(int index)
|
||||
}
|
||||
break;
|
||||
case HwSettings::RM_FLEXIPORT_DEBUGCONSOLE:
|
||||
m_ui->cbFlexiComSpeed->setVisible(true);
|
||||
m_ui->lblFlexiSpeed->setVisible(false);
|
||||
if (isComboboxOptionSelected(m_ui->cbMain, HwSettings::RM_MAINPORT_DEBUGCONSOLE)) {
|
||||
setComboboxSelectedOption(m_ui->cbMain, HwSettings::RM_MAINPORT_DISABLED);
|
||||
}
|
||||
@ -313,7 +305,6 @@ void ConfigRevoHWWidget::mainPortChanged(int index)
|
||||
|
||||
m_ui->cbMainTelemSpeed->setVisible(false);
|
||||
m_ui->cbMainGPSSpeed->setVisible(false);
|
||||
m_ui->cbMainComSpeed->setVisible(false);
|
||||
m_ui->lblMainSpeed->setVisible(true);
|
||||
|
||||
// Add Gps protocol configuration
|
||||
@ -350,7 +341,7 @@ void ConfigRevoHWWidget::mainPortChanged(int index)
|
||||
}
|
||||
break;
|
||||
case HwSettings::RM_MAINPORT_COMBRIDGE:
|
||||
m_ui->cbMainComSpeed->setVisible(true);
|
||||
m_ui->lblMainSpeed->setVisible(false);
|
||||
if (isComboboxOptionSelected(m_ui->cbFlexi, HwSettings::RM_FLEXIPORT_COMBRIDGE)) {
|
||||
setComboboxSelectedOption(m_ui->cbFlexi, HwSettings::RM_FLEXIPORT_DISABLED);
|
||||
}
|
||||
@ -362,7 +353,7 @@ void ConfigRevoHWWidget::mainPortChanged(int index)
|
||||
}
|
||||
break;
|
||||
case HwSettings::RM_MAINPORT_DEBUGCONSOLE:
|
||||
m_ui->cbMainComSpeed->setVisible(true);
|
||||
m_ui->lblMainSpeed->setVisible(false);
|
||||
if (isComboboxOptionSelected(m_ui->cbFlexi, HwSettings::RM_FLEXIPORT_DEBUGCONSOLE)) {
|
||||
setComboboxSelectedOption(m_ui->cbFlexi, HwSettings::RM_FLEXIPORT_DISABLED);
|
||||
}
|
||||
@ -417,14 +408,12 @@ void ConfigRevoHWWidget::rcvrPortChanged(int index)
|
||||
Q_UNUSED(index);
|
||||
m_ui->lblRcvrSpeed->setVisible(true);
|
||||
m_ui->cbRcvrTelemSpeed->setVisible(false);
|
||||
m_ui->cbRcvrComSpeed->setVisible(false);
|
||||
m_ui->cbRcvrGPSSpeed->setVisible(false);
|
||||
|
||||
// Add Gps protocol configuration
|
||||
m_ui->cbRcvrGPSProtocol->setVisible(false);
|
||||
m_ui->lblRcvrGPSProtocol->setVisible(false);
|
||||
|
||||
|
||||
switch (getComboboxSelectedOption(m_ui->cbRcvr)) {
|
||||
case HwSettings::RM_RCVRPORT_TELEMETRY:
|
||||
case HwSettings::RM_RCVRPORT_PPMTELEMETRY:
|
||||
@ -439,7 +428,7 @@ void ConfigRevoHWWidget::rcvrPortChanged(int index)
|
||||
break;
|
||||
case HwSettings::RM_RCVRPORT_COMBRIDGE:
|
||||
case HwSettings::RM_RCVRPORT_PPMCOMBRIDGE:
|
||||
m_ui->cbRcvrComSpeed->setVisible(true);
|
||||
m_ui->lblRcvrSpeed->setVisible(false);
|
||||
if (isComboboxOptionSelected(m_ui->cbFlexi, HwSettings::RM_FLEXIPORT_COMBRIDGE)) {
|
||||
setComboboxSelectedOption(m_ui->cbFlexi, HwSettings::RM_FLEXIPORT_DISABLED);
|
||||
}
|
||||
@ -449,7 +438,6 @@ void ConfigRevoHWWidget::rcvrPortChanged(int index)
|
||||
break;
|
||||
case HwSettings::RM_RCVRPORT_DEBUGCONSOLE:
|
||||
case HwSettings::RM_RCVRPORT_PPMDEBUGCONSOLE:
|
||||
m_ui->cbRcvrComSpeed->setVisible(true);
|
||||
if (isComboboxOptionSelected(m_ui->cbFlexi, HwSettings::RM_FLEXIPORT_DEBUGCONSOLE)) {
|
||||
setComboboxSelectedOption(m_ui->cbFlexi, HwSettings::RM_FLEXIPORT_DISABLED);
|
||||
}
|
||||
|
@ -248,9 +248,6 @@
|
||||
<item>
|
||||
<widget class="QComboBox" name="cbMainGPSSpeed"/>
|
||||
</item>
|
||||
<item>
|
||||
<widget class="QComboBox" name="cbMainComSpeed"/>
|
||||
</item>
|
||||
</layout>
|
||||
</item>
|
||||
<item row="2" column="0">
|
||||
@ -579,9 +576,6 @@
|
||||
<item alignment="Qt::AlignTop">
|
||||
<widget class="QComboBox" name="cbFlexiGPSSpeed"/>
|
||||
</item>
|
||||
<item alignment="Qt::AlignTop">
|
||||
<widget class="QComboBox" name="cbFlexiComSpeed"/>
|
||||
</item>
|
||||
</layout>
|
||||
</item>
|
||||
<item row="18" column="1">
|
||||
@ -652,9 +646,6 @@
|
||||
<item>
|
||||
<widget class="QComboBox" name="cbRcvrTelemSpeed"/>
|
||||
</item>
|
||||
<item>
|
||||
<widget class="QComboBox" name="cbRcvrComSpeed"/>
|
||||
</item>
|
||||
<item>
|
||||
<widget class="QComboBox" name="cbRcvrGPSSpeed"/>
|
||||
</item>
|
||||
@ -681,32 +672,9 @@
|
||||
</item>
|
||||
</layout>
|
||||
</item>
|
||||
<item row="9" column="0">
|
||||
<widget class="QComboBox" name="cbUSBVCPSpeed">
|
||||
<property name="enabled">
|
||||
<bool>true</bool>
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
<item row="7" column="0">
|
||||
<widget class="QComboBox" name="cbUSBVCPFunction"/>
|
||||
</item>
|
||||
<item row="8" column="0" alignment="Qt::AlignHCenter">
|
||||
<widget class="QLabel" name="lblUSBVCPSpeed">
|
||||
<property name="sizePolicy">
|
||||
<sizepolicy hsizetype="Preferred" vsizetype="Fixed">
|
||||
<horstretch>0</horstretch>
|
||||
<verstretch>0</verstretch>
|
||||
</sizepolicy>
|
||||
</property>
|
||||
<property name="text">
|
||||
<string>Speed</string>
|
||||
</property>
|
||||
<property name="alignment">
|
||||
<set>Qt::AlignBottom|Qt::AlignHCenter</set>
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
<item row="5" column="0">
|
||||
<widget class="QComboBox" name="cbUSBHIDFunction"/>
|
||||
</item>
|
||||
|
@ -61,18 +61,12 @@ ConfigRevoNanoHWWidget::ConfigRevoNanoHWWidget(QWidget *parent) : ConfigTaskWidg
|
||||
|
||||
addWidgetBinding("HwSettings", "USB_HIDPort", m_ui->cbUSBHIDFunction);
|
||||
addWidgetBinding("HwSettings", "USB_VCPPort", m_ui->cbUSBVCPFunction);
|
||||
addWidgetBinding("HwSettings", "ComUsbBridgeSpeed", m_ui->cbUSBVCPSpeed);
|
||||
|
||||
addWidgetBinding("HwSettings", "TelemetrySpeed", m_ui->cbFlexiTelemSpeed);
|
||||
addWidgetBinding("HwSettings", "GPSSpeed", m_ui->cbFlexiGPSSpeed);
|
||||
addWidgetBinding("HwSettings", "ComUsbBridgeSpeed", m_ui->cbFlexiComSpeed);
|
||||
|
||||
addWidgetBinding("HwSettings", "TelemetrySpeed", m_ui->cbMainTelemSpeed);
|
||||
addWidgetBinding("HwSettings", "GPSSpeed", m_ui->cbMainGPSSpeed);
|
||||
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);
|
||||
@ -139,9 +133,6 @@ void ConfigRevoNanoHWWidget::usbVCPPortChanged(int index)
|
||||
|
||||
bool vcpComBridgeEnabled = isComboboxOptionSelected(m_ui->cbUSBVCPFunction, HwSettings::USB_VCPPORT_COMBRIDGE);
|
||||
|
||||
m_ui->lblUSBVCPSpeed->setVisible(vcpComBridgeEnabled);
|
||||
m_ui->cbUSBVCPSpeed->setVisible(vcpComBridgeEnabled);
|
||||
|
||||
if (!vcpComBridgeEnabled && isComboboxOptionSelected(m_ui->cbFlexi, HwSettings::RM_FLEXIPORT_COMBRIDGE)) {
|
||||
setComboboxSelectedOption(m_ui->cbFlexi, HwSettings::RM_FLEXIPORT_DISABLED);
|
||||
}
|
||||
@ -152,11 +143,6 @@ void ConfigRevoNanoHWWidget::usbVCPPortChanged(int index)
|
||||
}
|
||||
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 (isComboboxOptionSelected(m_ui->cbUSBVCPFunction, HwSettings::USB_VCPPORT_DEBUGCONSOLE)) {
|
||||
if (isComboboxOptionSelected(m_ui->cbMain, HwSettings::RM_MAINPORT_DEBUGCONSOLE)) {
|
||||
@ -191,7 +177,6 @@ void ConfigRevoNanoHWWidget::flexiPortChanged(int index)
|
||||
|
||||
m_ui->cbFlexiTelemSpeed->setVisible(false);
|
||||
m_ui->cbFlexiGPSSpeed->setVisible(false);
|
||||
m_ui->cbFlexiComSpeed->setVisible(false);
|
||||
m_ui->lblFlexiSpeed->setVisible(true);
|
||||
|
||||
// Add Gps protocol configuration
|
||||
@ -204,10 +189,6 @@ void ConfigRevoNanoHWWidget::flexiPortChanged(int index)
|
||||
if (isComboboxOptionSelected(m_ui->cbMain, HwSettings::RM_MAINPORT_TELEMETRY)) {
|
||||
setComboboxSelectedOption(m_ui->cbMain, HwSettings::RM_MAINPORT_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:
|
||||
// Add Gps protocol configuration
|
||||
@ -220,16 +201,13 @@ void ConfigRevoNanoHWWidget::flexiPortChanged(int index)
|
||||
}
|
||||
break;
|
||||
case HwSettings::RM_FLEXIPORT_COMBRIDGE:
|
||||
m_ui->cbFlexiComSpeed->setVisible(true);
|
||||
m_ui->lblFlexiSpeed->setVisible(false);
|
||||
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);
|
||||
m_ui->lblFlexiSpeed->setVisible(false);
|
||||
if (isComboboxOptionSelected(m_ui->cbMain, HwSettings::RM_MAINPORT_DEBUGCONSOLE)) {
|
||||
setComboboxSelectedOption(m_ui->cbMain, HwSettings::RM_MAINPORT_DISABLED);
|
||||
}
|
||||
@ -249,7 +227,6 @@ void ConfigRevoNanoHWWidget::mainPortChanged(int index)
|
||||
|
||||
m_ui->cbMainTelemSpeed->setVisible(false);
|
||||
m_ui->cbMainGPSSpeed->setVisible(false);
|
||||
m_ui->cbMainComSpeed->setVisible(false);
|
||||
m_ui->lblMainSpeed->setVisible(true);
|
||||
|
||||
// Add Gps protocol configuration
|
||||
@ -262,10 +239,6 @@ void ConfigRevoNanoHWWidget::mainPortChanged(int index)
|
||||
if (isComboboxOptionSelected(m_ui->cbFlexi, HwSettings::RM_FLEXIPORT_TELEMETRY)) {
|
||||
setComboboxSelectedOption(m_ui->cbFlexi, HwSettings::RM_FLEXIPORT_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:
|
||||
// Add Gps protocol configuration
|
||||
@ -278,16 +251,13 @@ void ConfigRevoNanoHWWidget::mainPortChanged(int index)
|
||||
}
|
||||
break;
|
||||
case HwSettings::RM_MAINPORT_COMBRIDGE:
|
||||
m_ui->cbMainComSpeed->setVisible(true);
|
||||
m_ui->lblMainSpeed->setVisible(false);
|
||||
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);
|
||||
m_ui->lblMainSpeed->setVisible(false);
|
||||
if (isComboboxOptionSelected(m_ui->cbFlexi, HwSettings::RM_FLEXIPORT_DEBUGCONSOLE)) {
|
||||
setComboboxSelectedOption(m_ui->cbFlexi, HwSettings::RM_FLEXIPORT_DISABLED);
|
||||
}
|
||||
@ -304,36 +274,7 @@ void ConfigRevoNanoHWWidget::mainPortChanged(int index)
|
||||
void ConfigRevoNanoHWWidget::rcvrPortChanged(int index)
|
||||
{
|
||||
Q_UNUSED(index);
|
||||
|
||||
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->cbRcvrTelemSpeed->setVisible(true);
|
||||
|
||||
if (isComboboxOptionSelected(m_ui->cbFlexi, HwSettings::RM_FLEXIPORT_TELEMETRY)) {
|
||||
setComboboxSelectedOption(m_ui->cbFlexi, HwSettings::RM_FLEXIPORT_DISABLED);
|
||||
}
|
||||
if (isComboboxOptionSelected(m_ui->cbMain, HwSettings::RM_MAINPORT_TELEMETRY)) {
|
||||
setComboboxSelectedOption(m_ui->cbMain, HwSettings::RM_MAINPORT_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);
|
||||
break;
|
||||
}
|
||||
/* Nano has no USART at rcvrPort */
|
||||
}
|
||||
|
||||
void ConfigRevoNanoHWWidget::openHelp()
|
||||
|
@ -233,22 +233,6 @@
|
||||
</item>
|
||||
<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,0">
|
||||
<item row="4" column="0">
|
||||
<widget class="QLabel" name="lblUSBVCPSpeed">
|
||||
<property name="sizePolicy">
|
||||
<sizepolicy hsizetype="Preferred" vsizetype="Fixed">
|
||||
<horstretch>0</horstretch>
|
||||
<verstretch>0</verstretch>
|
||||
</sizepolicy>
|
||||
</property>
|
||||
<property name="text">
|
||||
<string>Speed</string>
|
||||
</property>
|
||||
<property name="alignment">
|
||||
<set>Qt::AlignBottom|Qt::AlignHCenter</set>
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
<item row="3" column="0" alignment="Qt::AlignTop">
|
||||
<widget class="QComboBox" name="cbUSBVCPFunction"/>
|
||||
</item>
|
||||
@ -302,13 +286,6 @@
|
||||
</property>
|
||||
</widget>
|
||||
</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">
|
||||
<widget class="QLabel" name="label_4">
|
||||
<property name="sizePolicy">
|
||||
@ -325,22 +302,6 @@
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
<item row="10" column="0" alignment="Qt::AlignHCenter">
|
||||
<widget class="QLabel" name="lblRcvrSpeed">
|
||||
<property name="sizePolicy">
|
||||
<sizepolicy hsizetype="Preferred" vsizetype="Fixed">
|
||||
<horstretch>0</horstretch>
|
||||
<verstretch>0</verstretch>
|
||||
</sizepolicy>
|
||||
</property>
|
||||
<property name="text">
|
||||
<string>Speed</string>
|
||||
</property>
|
||||
<property name="alignment">
|
||||
<set>Qt::AlignBottom|Qt::AlignLeading|Qt::AlignLeft</set>
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
<item row="9" column="0">
|
||||
<widget class="QComboBox" name="cbRcvr"/>
|
||||
</item>
|
||||
@ -401,12 +362,9 @@
|
||||
<item>
|
||||
<widget class="QComboBox" name="cbMainGPSSpeed"/>
|
||||
</item>
|
||||
<item>
|
||||
<widget class="QComboBox" name="cbMainComSpeed"/>
|
||||
</item>
|
||||
</layout>
|
||||
</item>
|
||||
<item row="5" column="1" colspan="2">
|
||||
<item row="3" column="3" colspan="2">
|
||||
<widget class="QComboBox" name="cbFlexiGPSProtocol"/>
|
||||
</item>
|
||||
<item row="13" column="2" colspan="2">
|
||||
@ -419,7 +377,7 @@
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
<item row="4" column="1" colspan="2">
|
||||
<item row="2" column="3" colspan="2">
|
||||
<widget class="QLabel" name="lbFlexiGPSProtocol">
|
||||
<property name="text">
|
||||
<string>Protocol</string>
|
||||
@ -450,9 +408,6 @@
|
||||
<item alignment="Qt::AlignTop">
|
||||
<widget class="QComboBox" name="cbFlexiGPSSpeed"/>
|
||||
</item>
|
||||
<item alignment="Qt::AlignTop">
|
||||
<widget class="QComboBox" name="cbFlexiComSpeed"/>
|
||||
</item>
|
||||
</layout>
|
||||
</item>
|
||||
<item row="0" column="1" colspan="2">
|
||||
@ -475,35 +430,6 @@
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
<item row="11" column="0">
|
||||
<layout class="QVBoxLayout" name="verticalLayout_2">
|
||||
<property name="spacing">
|
||||
<number>0</number>
|
||||
</property>
|
||||
<property name="topMargin">
|
||||
<number>0</number>
|
||||
</property>
|
||||
<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>
|
||||
</layout>
|
||||
</item>
|
||||
</layout>
|
||||
|
@ -60,15 +60,12 @@ ConfigSparky2HWWidget::ConfigSparky2HWWidget(QWidget *parent) : ConfigTaskWidget
|
||||
|
||||
addWidgetBinding("HwSettings", "USB_HIDPort", m_ui->cbUSBHIDFunction);
|
||||
addWidgetBinding("HwSettings", "USB_VCPPort", m_ui->cbUSBVCPFunction);
|
||||
addWidgetBinding("HwSettings", "ComUsbBridgeSpeed", m_ui->cbUSBVCPSpeed);
|
||||
|
||||
addWidgetBinding("HwSettings", "TelemetrySpeed", m_ui->cbFlexiTelemSpeed);
|
||||
addWidgetBinding("HwSettings", "GPSSpeed", m_ui->cbFlexiGPSSpeed);
|
||||
addWidgetBinding("HwSettings", "ComUsbBridgeSpeed", m_ui->cbFlexiComSpeed);
|
||||
|
||||
addWidgetBinding("HwSettings", "TelemetrySpeed", m_ui->cbMainTelemSpeed);
|
||||
addWidgetBinding("HwSettings", "GPSSpeed", m_ui->cbMainGPSSpeed);
|
||||
addWidgetBinding("HwSettings", "ComUsbBridgeSpeed", m_ui->cbMainComSpeed);
|
||||
|
||||
// Add Gps protocol configuration
|
||||
addWidgetBinding("GPSSettings", "DataProtocol", m_ui->cbMainGPSProtocol);
|
||||
@ -138,9 +135,6 @@ void ConfigSparky2HWWidget::usbVCPPortChanged(int index)
|
||||
|
||||
bool vcpComBridgeEnabled = isComboboxOptionSelected(m_ui->cbUSBVCPFunction, HwSettings::USB_VCPPORT_COMBRIDGE);
|
||||
|
||||
m_ui->lblUSBVCPSpeed->setVisible(vcpComBridgeEnabled);
|
||||
m_ui->cbUSBVCPSpeed->setVisible(vcpComBridgeEnabled);
|
||||
|
||||
if (!vcpComBridgeEnabled && isComboboxOptionSelected(m_ui->cbFlexi, HwSettings::SPK2_FLEXIPORT_COMBRIDGE)) {
|
||||
setComboboxSelectedOption(m_ui->cbFlexi, HwSettings::SPK2_FLEXIPORT_DISABLED);
|
||||
}
|
||||
@ -185,7 +179,6 @@ void ConfigSparky2HWWidget::flexiPortChanged(int index)
|
||||
|
||||
m_ui->cbFlexiTelemSpeed->setVisible(false);
|
||||
m_ui->cbFlexiGPSSpeed->setVisible(false);
|
||||
m_ui->cbFlexiComSpeed->setVisible(false);
|
||||
m_ui->lblFlexiSpeed->setVisible(true);
|
||||
|
||||
// Add Gps protocol configuration
|
||||
@ -210,13 +203,13 @@ void ConfigSparky2HWWidget::flexiPortChanged(int index)
|
||||
}
|
||||
break;
|
||||
case HwSettings::SPK2_FLEXIPORT_COMBRIDGE:
|
||||
m_ui->cbFlexiComSpeed->setVisible(true);
|
||||
m_ui->lblFlexiSpeed->setVisible(false);
|
||||
if (isComboboxOptionSelected(m_ui->cbMain, HwSettings::SPK2_MAINPORT_COMBRIDGE)) {
|
||||
setComboboxSelectedOption(m_ui->cbMain, HwSettings::SPK2_MAINPORT_DISABLED);
|
||||
}
|
||||
break;
|
||||
case HwSettings::SPK2_FLEXIPORT_DEBUGCONSOLE:
|
||||
m_ui->cbFlexiComSpeed->setVisible(true);
|
||||
m_ui->lblFlexiSpeed->setVisible(false);
|
||||
if (isComboboxOptionSelected(m_ui->cbMain, HwSettings::SPK2_MAINPORT_DEBUGCONSOLE)) {
|
||||
setComboboxSelectedOption(m_ui->cbMain, HwSettings::SPK2_MAINPORT_DISABLED);
|
||||
}
|
||||
@ -236,7 +229,6 @@ void ConfigSparky2HWWidget::mainPortChanged(int index)
|
||||
|
||||
m_ui->cbMainTelemSpeed->setVisible(false);
|
||||
m_ui->cbMainGPSSpeed->setVisible(false);
|
||||
m_ui->cbMainComSpeed->setVisible(false);
|
||||
m_ui->lblMainSpeed->setVisible(true);
|
||||
|
||||
// Add Gps protocol configuration
|
||||
@ -261,13 +253,13 @@ void ConfigSparky2HWWidget::mainPortChanged(int index)
|
||||
}
|
||||
break;
|
||||
case HwSettings::SPK2_MAINPORT_COMBRIDGE:
|
||||
m_ui->cbMainComSpeed->setVisible(true);
|
||||
m_ui->lblMainSpeed->setVisible(false);
|
||||
if (isComboboxOptionSelected(m_ui->cbFlexi, HwSettings::SPK2_FLEXIPORT_COMBRIDGE)) {
|
||||
setComboboxSelectedOption(m_ui->cbFlexi, HwSettings::SPK2_FLEXIPORT_DISABLED);
|
||||
}
|
||||
break;
|
||||
case HwSettings::SPK2_MAINPORT_DEBUGCONSOLE:
|
||||
m_ui->cbMainComSpeed->setVisible(true);
|
||||
m_ui->lblMainSpeed->setVisible(false);
|
||||
if (isComboboxOptionSelected(m_ui->cbFlexi, HwSettings::SPK2_FLEXIPORT_DEBUGCONSOLE)) {
|
||||
setComboboxSelectedOption(m_ui->cbFlexi, HwSettings::SPK2_FLEXIPORT_DISABLED);
|
||||
}
|
||||
|
@ -377,39 +377,13 @@
|
||||
<item>
|
||||
<widget class="QComboBox" name="cbMainGPSSpeed"/>
|
||||
</item>
|
||||
<item>
|
||||
<widget class="QComboBox" name="cbMainComSpeed"/>
|
||||
</item>
|
||||
</layout>
|
||||
</item>
|
||||
</layout>
|
||||
</item>
|
||||
<item row="16" column="0">
|
||||
<widget class="QComboBox" name="cbUSBVCPSpeed">
|
||||
<property name="enabled">
|
||||
<bool>true</bool>
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
<item row="12" column="0">
|
||||
<widget class="QComboBox" name="cbUSBHIDFunction"/>
|
||||
</item>
|
||||
<item row="15" column="0" alignment="Qt::AlignHCenter">
|
||||
<widget class="QLabel" name="lblUSBVCPSpeed">
|
||||
<property name="sizePolicy">
|
||||
<sizepolicy hsizetype="Preferred" vsizetype="Fixed">
|
||||
<horstretch>0</horstretch>
|
||||
<verstretch>0</verstretch>
|
||||
</sizepolicy>
|
||||
</property>
|
||||
<property name="text">
|
||||
<string>Speed</string>
|
||||
</property>
|
||||
<property name="alignment">
|
||||
<set>Qt::AlignBottom|Qt::AlignHCenter</set>
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
<item row="13" column="0" alignment="Qt::AlignHCenter">
|
||||
<widget class="QLabel" name="label_8">
|
||||
<property name="sizePolicy">
|
||||
@ -504,13 +478,6 @@
|
||||
<item>
|
||||
<widget class="QComboBox" name="cbFlexiGPSSpeed"/>
|
||||
</item>
|
||||
<item>
|
||||
<widget class="QComboBox" name="cbFlexiComSpeed">
|
||||
<property name="enabled">
|
||||
<bool>true</bool>
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
</layout>
|
||||
</item>
|
||||
<item row="2" column="1">
|
||||
|
@ -24,7 +24,7 @@
|
||||
|
||||
<field name="TelemetrySpeed" units="bps" type="enum" elements="1" options="2400,4800,9600,19200,38400,57600,115200" defaultvalue="57600"/>
|
||||
<field name="GPSSpeed" units="bps" type="enum" elements="1" options="2400,4800,9600,19200,38400,57600,115200,230400" defaultvalue="57600"/>
|
||||
<field name="ComUsbBridgeSpeed" units="bps" type="enum" elements="1" options="2400,4800,9600,19200,38400,57600,115200" defaultvalue="57600"/>
|
||||
<field name="DebugConsoleSpeed" units="bps" type="enum" elements="1" options="2400,4800,9600,19200,38400,57600,115200" defaultvalue="57600"/>
|
||||
<field name="MSPSpeed" units="bps" type="enum" elements="1" options="2400,4800,9600,19200,38400,57600,115200" defaultvalue="115200"/>
|
||||
<field name="MAVLinkSpeed" units="bps" type="enum" elements="1" options="2400,4800,9600,19200,38400,57600,115200" defaultvalue="57600"/>
|
||||
<field name="USB_HIDPort" units="function" type="enum" elements="1" options="USBTelemetry,RCTransmitter,Disabled" defaultvalue="USBTelemetry"/>
|
||||
|
Loading…
x
Reference in New Issue
Block a user