1
0
mirror of https://bitbucket.org/librepilot/librepilot.git synced 2024-11-29 07:24:13 +01:00

LP-239 This commit adds missing com protocols (GPS) to Revo Flexi IO (rcvrport) including proper GCS handling

This commit is contained in:
Vladimir Zidar 2016-08-06 03:15:15 +02:00
parent 73c96be4b7
commit 51151e6290
6 changed files with 310 additions and 16 deletions

View File

@ -973,6 +973,64 @@ static const struct pios_usart_cfg pios_usart_hkosd_flexi_cfg = {
},
};
static const struct pios_usart_cfg pios_usart_rcvrport_cfg = {
.regs = USART6,
.remap = GPIO_AF_USART6,
.init = {
.USART_BaudRate = 57600,
.USART_WordLength = USART_WordLength_8b,
.USART_Parity = USART_Parity_No,
.USART_StopBits = USART_StopBits_1,
.USART_HardwareFlowControl = USART_HardwareFlowControl_None,
.USART_Mode = USART_Mode_Rx | USART_Mode_Tx,
},
.irq = {
.init = {
.NVIC_IRQChannel = USART6_IRQn,
.NVIC_IRQChannelPreemptionPriority = PIOS_IRQ_PRIO_MID,
.NVIC_IRQChannelSubPriority = 0,
.NVIC_IRQChannelCmd = ENABLE,
},
},
.dtr = {
// FlexIO pin 9
.gpio = GPIOC,
.init = {
.GPIO_Pin = GPIO_Pin_8,
.GPIO_Speed = GPIO_Speed_25MHz,
.GPIO_Mode = GPIO_Mode_OUT,
.GPIO_OType = GPIO_OType_PP,
},
},
.tx = {
// * 7: PC6 = TIM8 CH1, USART6 TX
.gpio = GPIOC,
.init = {
.GPIO_Pin = GPIO_Pin_6,
.GPIO_Speed = GPIO_Speed_2MHz,
.GPIO_Mode = GPIO_Mode_AF,
.GPIO_OType = GPIO_OType_PP,
.GPIO_PuPd = GPIO_PuPd_UP
},
.pin_source = GPIO_PinSource6,
},
.rx = {
// * 8: PC7 = TIM8 CH2, USART6 RX
.gpio = GPIOC,
.init = {
.GPIO_Pin = GPIO_Pin_7,
.GPIO_Speed = GPIO_Speed_2MHz,
.GPIO_Mode = GPIO_Mode_AF,
.GPIO_OType = GPIO_OType_PP,
.GPIO_PuPd = GPIO_PuPd_UP
},
.pin_source = GPIO_PinSource7,
}
};
#if defined(PIOS_INCLUDE_COM)
#include <pios_com_priv.h>

View File

@ -235,7 +235,8 @@ uint32_t pios_rcvr_group_map[MANUALCONTROLSETTINGS_CHANNELGROUPS_NONE];
#define PIOS_COM_TELEM_RF_RX_BUF_LEN 512
#define PIOS_COM_TELEM_RF_TX_BUF_LEN 512
#define PIOS_COM_GPS_RX_BUF_LEN 32
#define PIOS_COM_GPS_RX_BUF_LEN 128
#define PIOS_COM_GPS_TX_BUF_LEN 32
#define PIOS_COM_TELEM_USB_RX_BUF_LEN 65
#define PIOS_COM_TELEM_USB_TX_BUF_LEN 65
@ -626,7 +627,7 @@ void PIOS_Board_Init(void)
PIOS_Board_configure_com(&pios_usart_main_cfg, PIOS_COM_TELEM_RF_RX_BUF_LEN, PIOS_COM_TELEM_RF_TX_BUF_LEN, &pios_usart_com_driver, &pios_com_telem_rf_id);
break;
case HWSETTINGS_RM_MAINPORT_GPS:
PIOS_Board_configure_com(&pios_usart_main_cfg, PIOS_COM_GPS_RX_BUF_LEN, -1, &pios_usart_com_driver, &pios_com_gps_id);
PIOS_Board_configure_com(&pios_usart_main_cfg, PIOS_COM_GPS_RX_BUF_LEN, PIOS_COM_GPS_TX_BUF_LEN, &pios_usart_com_driver, &pios_com_gps_id);
break;
case HWSETTINGS_RM_MAINPORT_SBUS:
#if defined(PIOS_INCLUDE_SBUS)
@ -731,7 +732,7 @@ void PIOS_Board_Init(void)
#endif /* PIOS_INCLUDE_I2C */
break;
case HWSETTINGS_RM_FLEXIPORT_GPS:
PIOS_Board_configure_com(&pios_usart_flexi_cfg, PIOS_COM_GPS_RX_BUF_LEN, -1, &pios_usart_com_driver, &pios_com_gps_id);
PIOS_Board_configure_com(&pios_usart_flexi_cfg, PIOS_COM_GPS_RX_BUF_LEN, PIOS_COM_GPS_TX_BUF_LEN, &pios_usart_com_driver, &pios_com_gps_id);
break;
case HWSETTINGS_RM_FLEXIPORT_DSM:
// TODO: Define the various Channelgroup for Revo dsm inputs and handle here
@ -895,6 +896,12 @@ void PIOS_Board_Init(void)
case HWSETTINGS_RM_RCVRPORT_PPM:
case HWSETTINGS_RM_RCVRPORT_PPMOUTPUTS:
case HWSETTINGS_RM_RCVRPORT_PPMPWM:
case HWSETTINGS_RM_RCVRPORT_PPMTELEMETRY:
case HWSETTINGS_RM_RCVRPORT_PPMDEBUGCONSOLE:
case HWSETTINGS_RM_RCVRPORT_PPMCOMBRIDGE:
case HWSETTINGS_RM_RCVRPORT_PPMMSP:
case HWSETTINGS_RM_RCVRPORT_PPMMAVLINK:
case HWSETTINGS_RM_RCVRPORT_PPMGPS:
#if defined(PIOS_INCLUDE_PPM)
if (hwsettings_rcvrport == HWSETTINGS_RM_RCVRPORT_PPMOUTPUTS) {
// configure servo outputs and the remaining 5 inputs as outputs
@ -916,6 +923,35 @@ void PIOS_Board_Init(void)
break;
}
// Configure rcvrport usart
switch (hwsettings_rcvrport) {
case HWSETTINGS_RM_RCVRPORT_TELEMETRY:
case HWSETTINGS_RM_RCVRPORT_PPMTELEMETRY:
PIOS_Board_configure_com(&pios_usart_rcvrport_cfg, PIOS_COM_TELEM_RF_RX_BUF_LEN, PIOS_COM_TELEM_RF_TX_BUF_LEN, &pios_usart_com_driver, &pios_com_telem_rf_id);
break;
case HWSETTINGS_RM_RCVRPORT_DEBUGCONSOLE:
case HWSETTINGS_RM_RCVRPORT_PPMDEBUGCONSOLE:
#if defined(PIOS_INCLUDE_DEBUG_CONSOLE)
PIOS_Board_configure_com(&pios_usart_rcvrport_cfg, 0, PIOS_COM_DEBUGCONSOLE_TX_BUF_LEN, &pios_usart_com_driver, &pios_com_debug_id);
#endif /* PIOS_INCLUDE_DEBUG_CONSOLE */
break;
case HWSETTINGS_RM_RCVRPORT_COMBRIDGE:
case HWSETTINGS_RM_RCVRPORT_PPMCOMBRIDGE:
PIOS_Board_configure_com(&pios_usart_rcvrport_cfg, PIOS_COM_BRIDGE_RX_BUF_LEN, PIOS_COM_BRIDGE_TX_BUF_LEN, &pios_usart_com_driver, &pios_com_bridge_id);
break;
case HWSETTINGS_RM_RCVRPORT_MSP:
case HWSETTINGS_RM_RCVRPORT_PPMMSP:
PIOS_Board_configure_com(&pios_usart_rcvrport_cfg, PIOS_COM_MSP_RX_BUF_LEN, PIOS_COM_MSP_TX_BUF_LEN, &pios_usart_com_driver, &pios_com_msp_id);
break;
case HWSETTINGS_RM_RCVRPORT_MAVLINK:
case HWSETTINGS_RM_RCVRPORT_PPMMAVLINK:
PIOS_Board_configure_com(&pios_usart_rcvrport_cfg, 0, PIOS_COM_MAVLINK_TX_BUF_LEN, &pios_usart_com_driver, &pios_com_mavlink_id);
break;
case HWSETTINGS_RM_RCVRPORT_GPS:
case HWSETTINGS_RM_RCVRPORT_PPMGPS:
PIOS_Board_configure_com(&pios_usart_rcvrport_cfg, PIOS_COM_GPS_RX_BUF_LEN, PIOS_COM_GPS_TX_BUF_LEN, &pios_usart_com_driver, &pios_com_gps_id);
break;
}
#if defined(PIOS_INCLUDE_GCSRCVR)
GCSReceiverInitialize();

View File

@ -985,10 +985,9 @@ void PIOS_Board_Init(void)
/* Configure the receiver port*/
uint8_t hwsettings_rcvrport;
HwSettingsRM_RcvrPortGet(&hwsettings_rcvrport);
//
// Configure rcvrport PPM/PWM/OUTPUTS
switch (hwsettings_rcvrport) {
case HWSETTINGS_RM_RCVRPORT_DISABLED:
break;
case HWSETTINGS_RM_RCVRPORT_PWM:
#if defined(PIOS_INCLUDE_PWM)
/* Set up the receiver port. Later this should be optional */
@ -999,6 +998,11 @@ void PIOS_Board_Init(void)
case HWSETTINGS_RM_RCVRPORT_PPMOUTPUTS:
case HWSETTINGS_RM_RCVRPORT_PPMPWM:
case HWSETTINGS_RM_RCVRPORT_PPMTELEMETRY:
case HWSETTINGS_RM_RCVRPORT_PPMDEBUGCONSOLE:
case HWSETTINGS_RM_RCVRPORT_PPMCOMBRIDGE:
case HWSETTINGS_RM_RCVRPORT_PPMMSP:
case HWSETTINGS_RM_RCVRPORT_PPMMAVLINK:
case HWSETTINGS_RM_RCVRPORT_PPMGPS:
#if defined(PIOS_INCLUDE_PPM)
PIOS_Board_configure_ppm(&pios_ppm_cfg);
@ -1012,28 +1016,42 @@ void PIOS_Board_Init(void)
PIOS_Board_configure_pwm(&pios_pwm_ppm_cfg);
}
if (hwsettings_rcvrport == HWSETTINGS_RM_RCVRPORT_PPMTELEMETRY) {
PIOS_Board_configure_com(&pios_usart_rcvrport_cfg, PIOS_COM_TELEM_RF_RX_BUF_LEN, PIOS_COM_TELEM_RF_TX_BUF_LEN, &pios_usart_com_driver, &pios_com_telem_rf_id);
}
break;
#endif /* PIOS_INCLUDE_PPM */
case HWSETTINGS_RM_RCVRPORT_OUTPUTS:
// configure only the servo outputs
pios_servo_cfg = &pios_servo_cfg_out_in;
break;
}
// Configure rcvrport usart
switch (hwsettings_rcvrport) {
case HWSETTINGS_RM_RCVRPORT_TELEMETRY:
case HWSETTINGS_RM_RCVRPORT_PPMTELEMETRY:
PIOS_Board_configure_com(&pios_usart_rcvrport_cfg, PIOS_COM_TELEM_RF_RX_BUF_LEN, PIOS_COM_TELEM_RF_TX_BUF_LEN, &pios_usart_com_driver, &pios_com_telem_rf_id);
break;
case HWSETTINGS_RM_RCVRPORT_DEBUGCONSOLE:
case HWSETTINGS_RM_RCVRPORT_PPMDEBUGCONSOLE:
#if defined(PIOS_INCLUDE_DEBUG_CONSOLE)
PIOS_Board_configure_com(&pios_usart_rcvrport_cfg, 0, PIOS_COM_DEBUGCONSOLE_TX_BUF_LEN, &pios_usart_com_driver, &pios_com_debug_id);
#endif /* PIOS_INCLUDE_DEBUG_CONSOLE */
break;
case HWSETTINGS_RM_RCVRPORT_COMBRIDGE:
case HWSETTINGS_RM_RCVRPORT_PPMCOMBRIDGE:
PIOS_Board_configure_com(&pios_usart_rcvrport_cfg, PIOS_COM_BRIDGE_RX_BUF_LEN, PIOS_COM_BRIDGE_TX_BUF_LEN, &pios_usart_com_driver, &pios_com_bridge_id);
break;
case HWSETTINGS_RM_RCVRPORT_MSP:
case HWSETTINGS_RM_RCVRPORT_PPMMSP:
PIOS_Board_configure_com(&pios_usart_rcvrport_cfg, PIOS_COM_MSP_RX_BUF_LEN, PIOS_COM_MSP_TX_BUF_LEN, &pios_usart_com_driver, &pios_com_msp_id);
break;
case HWSETTINGS_RM_RCVRPORT_MAVLINK:
case HWSETTINGS_RM_RCVRPORT_PPMMAVLINK:
PIOS_Board_configure_com(&pios_usart_rcvrport_cfg, 0, PIOS_COM_MAVLINK_TX_BUF_LEN, &pios_usart_com_driver, &pios_com_mavlink_id);
break;
case HWSETTINGS_RM_RCVRPORT_GPS:
case HWSETTINGS_RM_RCVRPORT_PPMGPS:
PIOS_Board_configure_com(&pios_usart_rcvrport_cfg, PIOS_COM_GPS_RX_BUF_LEN, PIOS_COM_GPS_TX_BUF_LEN, &pios_usart_com_driver, &pios_com_gps_id);
break;
}
#if defined(PIOS_INCLUDE_GCSRCVR)

View File

@ -70,11 +70,13 @@ ConfigRevoHWWidget::ConfigRevoHWWidget(QWidget *parent) : ConfigTaskWidget(paren
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);
addWidgetBinding("GPSSettings", "DataProtocol", m_ui->cbFlexiGPSProtocol);
addWidgetBinding("GPSSettings", "DataProtocol", m_ui->cbRcvrGPSProtocol);
connect(m_ui->cchwHelp, SIGNAL(clicked()), this, SLOT(openHelp()));
@ -158,7 +160,12 @@ void ConfigRevoHWWidget::usbVCPPortChanged(int index)
if (!vcpComBridgeEnabled && isComboboxOptionSelected(m_ui->cbRcvr, HwSettings::RM_RCVRPORT_COMBRIDGE)) {
setComboboxSelectedOption(m_ui->cbRcvr, HwSettings::RM_RCVRPORT_DISABLED);
}
if (!vcpComBridgeEnabled && isComboboxOptionSelected(m_ui->cbRcvr, HwSettings::RM_RCVRPORT_PPMCOMBRIDGE)) {
setComboboxSelectedOption(m_ui->cbRcvr, HwSettings::RM_RCVRPORT_PPM);
}
enableComboBoxOptionItem(m_ui->cbRcvr, HwSettings::RM_RCVRPORT_COMBRIDGE, vcpComBridgeEnabled);
enableComboBoxOptionItem(m_ui->cbRcvr, HwSettings::RM_RCVRPORT_PPMCOMBRIDGE, vcpComBridgeEnabled);
// _DEBUGCONSOLE modes are mutual exclusive
if (isComboboxOptionSelected(m_ui->cbUSBVCPFunction, HwSettings::USB_VCPPORT_DEBUGCONSOLE)) {
@ -168,6 +175,12 @@ void ConfigRevoHWWidget::usbVCPPortChanged(int index)
if (isComboboxOptionSelected(m_ui->cbFlexi, HwSettings::RM_FLEXIPORT_DEBUGCONSOLE)) {
setComboboxSelectedOption(m_ui->cbFlexi, HwSettings::RM_FLEXIPORT_DISABLED);
}
if (isComboboxOptionSelected(m_ui->cbRcvr, HwSettings::RM_RCVRPORT_DEBUGCONSOLE)) {
setComboboxSelectedOption(m_ui->cbRcvr, HwSettings::RM_RCVRPORT_DISABLED);
}
if (isComboboxOptionSelected(m_ui->cbRcvr, HwSettings::RM_RCVRPORT_PPMDEBUGCONSOLE)) {
setComboboxSelectedOption(m_ui->cbRcvr, HwSettings::RM_RCVRPORT_PPM);
}
}
// _USBTELEMETRY modes are mutual exclusive
@ -207,8 +220,10 @@ void ConfigRevoHWWidget::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)) {
if (isComboboxOptionSelected(m_ui->cbRcvr, HwSettings::RM_RCVRPORT_PPMTELEMETRY)) {
setComboboxSelectedOption(m_ui->cbRcvr, HwSettings::RM_RCVRPORT_PPM);
}
if (isComboboxOptionSelected(m_ui->cbRcvr, HwSettings::RM_RCVRPORT_TELEMETRY)) {
setComboboxSelectedOption(m_ui->cbRcvr, HwSettings::RM_RCVRPORT_DISABLED);
}
break;
@ -221,6 +236,13 @@ void ConfigRevoHWWidget::flexiPortChanged(int index)
if (isComboboxOptionSelected(m_ui->cbMain, HwSettings::RM_MAINPORT_GPS)) {
setComboboxSelectedOption(m_ui->cbMain, HwSettings::RM_MAINPORT_DISABLED);
}
if (isComboboxOptionSelected(m_ui->cbRcvr, HwSettings::RM_RCVRPORT_PPMGPS)) {
setComboboxSelectedOption(m_ui->cbRcvr, HwSettings::RM_RCVRPORT_PPM);
}
if (isComboboxOptionSelected(m_ui->cbRcvr, HwSettings::RM_RCVRPORT_GPS)) {
setComboboxSelectedOption(m_ui->cbRcvr, HwSettings::RM_RCVRPORT_DISABLED);
}
break;
case HwSettings::RM_FLEXIPORT_COMBRIDGE:
m_ui->cbFlexiComSpeed->setVisible(true);
@ -230,6 +252,9 @@ void ConfigRevoHWWidget::flexiPortChanged(int index)
if (isComboboxOptionSelected(m_ui->cbRcvr, HwSettings::RM_RCVRPORT_COMBRIDGE)) {
setComboboxSelectedOption(m_ui->cbRcvr, HwSettings::RM_RCVRPORT_DISABLED);
}
if (isComboboxOptionSelected(m_ui->cbRcvr, HwSettings::RM_RCVRPORT_PPMCOMBRIDGE)) {
setComboboxSelectedOption(m_ui->cbRcvr, HwSettings::RM_RCVRPORT_PPM);
}
break;
case HwSettings::RM_FLEXIPORT_DEBUGCONSOLE:
m_ui->cbFlexiComSpeed->setVisible(true);
@ -239,6 +264,42 @@ void ConfigRevoHWWidget::flexiPortChanged(int index)
if (isComboboxOptionSelected(m_ui->cbUSBVCPFunction, HwSettings::USB_VCPPORT_DEBUGCONSOLE)) {
setComboboxSelectedOption(m_ui->cbUSBVCPFunction, HwSettings::USB_VCPPORT_DISABLED);
}
if (isComboboxOptionSelected(m_ui->cbRcvr, HwSettings::RM_RCVRPORT_PPMDEBUGCONSOLE)) {
setComboboxSelectedOption(m_ui->cbRcvr, HwSettings::RM_RCVRPORT_PPM);
}
if (isComboboxOptionSelected(m_ui->cbRcvr, HwSettings::RM_RCVRPORT_DEBUGCONSOLE)) {
setComboboxSelectedOption(m_ui->cbRcvr, HwSettings::RM_RCVRPORT_DISABLED);
}
break;
case HwSettings::RM_FLEXIPORT_OSDHK:
m_ui->lblFlexiSpeed->setVisible(false);
if (isComboboxOptionSelected(m_ui->cbMain, HwSettings::RM_MAINPORT_OSDHK)) {
setComboboxSelectedOption(m_ui->cbMain, HwSettings::RM_MAINPORT_DISABLED);
}
break;
case HwSettings::RM_FLEXIPORT_MSP:
m_ui->lblFlexiSpeed->setVisible(false);
if (isComboboxOptionSelected(m_ui->cbMain, HwSettings::RM_MAINPORT_MSP)) {
setComboboxSelectedOption(m_ui->cbMain, HwSettings::RM_MAINPORT_DISABLED);
}
if (isComboboxOptionSelected(m_ui->cbRcvr, HwSettings::RM_RCVRPORT_MSP)) {
setComboboxSelectedOption(m_ui->cbRcvr, HwSettings::RM_RCVRPORT_DISABLED);
}
if (isComboboxOptionSelected(m_ui->cbRcvr, HwSettings::RM_RCVRPORT_PPMMSP)) {
setComboboxSelectedOption(m_ui->cbRcvr, HwSettings::RM_RCVRPORT_PPM);
}
break;
case HwSettings::RM_FLEXIPORT_MAVLINK:
m_ui->lblFlexiSpeed->setVisible(false);
if (isComboboxOptionSelected(m_ui->cbMain, HwSettings::RM_MAINPORT_MAVLINK)) {
setComboboxSelectedOption(m_ui->cbMain, HwSettings::RM_MAINPORT_DISABLED);
}
if (isComboboxOptionSelected(m_ui->cbRcvr, HwSettings::RM_RCVRPORT_MAVLINK)) {
setComboboxSelectedOption(m_ui->cbRcvr, HwSettings::RM_RCVRPORT_DISABLED);
}
if (isComboboxOptionSelected(m_ui->cbRcvr, HwSettings::RM_RCVRPORT_PPMMAVLINK)) {
setComboboxSelectedOption(m_ui->cbRcvr, HwSettings::RM_RCVRPORT_PPM);
}
break;
default:
m_ui->lblFlexiSpeed->setVisible(false);
@ -265,8 +326,10 @@ void ConfigRevoHWWidget::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)) {
if (isComboboxOptionSelected(m_ui->cbRcvr, HwSettings::RM_RCVRPORT_PPMTELEMETRY)) {
setComboboxSelectedOption(m_ui->cbRcvr, HwSettings::RM_RCVRPORT_PPM);
}
if (isComboboxOptionSelected(m_ui->cbRcvr, HwSettings::RM_RCVRPORT_TELEMETRY)) {
setComboboxSelectedOption(m_ui->cbRcvr, HwSettings::RM_RCVRPORT_DISABLED);
}
break;
@ -279,6 +342,12 @@ void ConfigRevoHWWidget::mainPortChanged(int index)
if (isComboboxOptionSelected(m_ui->cbFlexi, HwSettings::RM_FLEXIPORT_GPS)) {
setComboboxSelectedOption(m_ui->cbFlexi, HwSettings::RM_FLEXIPORT_DISABLED);
}
if (isComboboxOptionSelected(m_ui->cbRcvr, HwSettings::RM_RCVRPORT_PPMGPS)) {
setComboboxSelectedOption(m_ui->cbRcvr, HwSettings::RM_RCVRPORT_PPM);
}
if (isComboboxOptionSelected(m_ui->cbRcvr, HwSettings::RM_RCVRPORT_GPS)) {
setComboboxSelectedOption(m_ui->cbRcvr, HwSettings::RM_RCVRPORT_DISABLED);
}
break;
case HwSettings::RM_MAINPORT_COMBRIDGE:
m_ui->cbMainComSpeed->setVisible(true);
@ -288,6 +357,9 @@ void ConfigRevoHWWidget::mainPortChanged(int index)
if (isComboboxOptionSelected(m_ui->cbRcvr, HwSettings::RM_RCVRPORT_COMBRIDGE)) {
setComboboxSelectedOption(m_ui->cbRcvr, HwSettings::RM_RCVRPORT_DISABLED);
}
if (isComboboxOptionSelected(m_ui->cbRcvr, HwSettings::RM_RCVRPORT_PPMCOMBRIDGE)) {
setComboboxSelectedOption(m_ui->cbRcvr, HwSettings::RM_RCVRPORT_PPM);
}
break;
case HwSettings::RM_MAINPORT_DEBUGCONSOLE:
m_ui->cbMainComSpeed->setVisible(true);
@ -297,6 +369,42 @@ void ConfigRevoHWWidget::mainPortChanged(int index)
if (isComboboxOptionSelected(m_ui->cbUSBVCPFunction, HwSettings::USB_VCPPORT_DEBUGCONSOLE)) {
setComboboxSelectedOption(m_ui->cbUSBVCPFunction, HwSettings::USB_VCPPORT_DISABLED);
}
if (isComboboxOptionSelected(m_ui->cbRcvr, HwSettings::RM_RCVRPORT_PPMDEBUGCONSOLE)) {
setComboboxSelectedOption(m_ui->cbRcvr, HwSettings::RM_RCVRPORT_PPM);
}
if (isComboboxOptionSelected(m_ui->cbRcvr, HwSettings::RM_RCVRPORT_DEBUGCONSOLE)) {
setComboboxSelectedOption(m_ui->cbRcvr, HwSettings::RM_RCVRPORT_DISABLED);
}
break;
case HwSettings::RM_MAINPORT_OSDHK:
m_ui->lblMainSpeed->setVisible(false);
if (isComboboxOptionSelected(m_ui->cbFlexi, HwSettings::RM_FLEXIPORT_OSDHK)) {
setComboboxSelectedOption(m_ui->cbFlexi, HwSettings::RM_FLEXIPORT_DISABLED);
}
break;
case HwSettings::RM_MAINPORT_MSP:
m_ui->lblMainSpeed->setVisible(false);
if (isComboboxOptionSelected(m_ui->cbFlexi, HwSettings::RM_FLEXIPORT_MSP)) {
setComboboxSelectedOption(m_ui->cbFlexi, HwSettings::RM_FLEXIPORT_DISABLED);
}
if (isComboboxOptionSelected(m_ui->cbRcvr, HwSettings::RM_RCVRPORT_MSP)) {
setComboboxSelectedOption(m_ui->cbRcvr, HwSettings::RM_RCVRPORT_DISABLED);
}
if (isComboboxOptionSelected(m_ui->cbRcvr, HwSettings::RM_RCVRPORT_PPMMSP)) {
setComboboxSelectedOption(m_ui->cbRcvr, HwSettings::RM_RCVRPORT_PPM);
}
break;
case HwSettings::RM_MAINPORT_MAVLINK:
m_ui->lblMainSpeed->setVisible(false);
if (isComboboxOptionSelected(m_ui->cbFlexi, HwSettings::RM_FLEXIPORT_MAVLINK)) {
setComboboxSelectedOption(m_ui->cbFlexi, HwSettings::RM_FLEXIPORT_DISABLED);
}
if (isComboboxOptionSelected(m_ui->cbRcvr, HwSettings::RM_RCVRPORT_MAVLINK)) {
setComboboxSelectedOption(m_ui->cbRcvr, HwSettings::RM_RCVRPORT_DISABLED);
}
if (isComboboxOptionSelected(m_ui->cbRcvr, HwSettings::RM_RCVRPORT_PPMMAVLINK)) {
setComboboxSelectedOption(m_ui->cbRcvr, HwSettings::RM_RCVRPORT_PPM);
}
break;
default:
m_ui->lblMainSpeed->setVisible(false);
@ -310,6 +418,12 @@ void ConfigRevoHWWidget::rcvrPortChanged(int 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:
@ -324,6 +438,7 @@ void ConfigRevoHWWidget::rcvrPortChanged(int index)
}
break;
case HwSettings::RM_RCVRPORT_COMBRIDGE:
case HwSettings::RM_RCVRPORT_PPMCOMBRIDGE:
m_ui->cbRcvrComSpeed->setVisible(true);
if (isComboboxOptionSelected(m_ui->cbFlexi, HwSettings::RM_FLEXIPORT_COMBRIDGE)) {
setComboboxSelectedOption(m_ui->cbFlexi, HwSettings::RM_FLEXIPORT_DISABLED);
@ -332,6 +447,51 @@ void ConfigRevoHWWidget::rcvrPortChanged(int index)
setComboboxSelectedOption(m_ui->cbMain, HwSettings::RM_MAINPORT_DISABLED);
}
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);
}
if (isComboboxOptionSelected(m_ui->cbMain, HwSettings::RM_MAINPORT_DEBUGCONSOLE)) {
setComboboxSelectedOption(m_ui->cbMain, HwSettings::RM_MAINPORT_DISABLED);
}
break;
case HwSettings::RM_RCVRPORT_GPS:
case HwSettings::RM_RCVRPORT_PPMGPS:
// Add Gps protocol configuration
m_ui->cbRcvrGPSProtocol->setVisible(true);
m_ui->lblRcvrGPSProtocol->setVisible(true);
m_ui->cbRcvrGPSSpeed->setVisible(true);
if (isComboboxOptionSelected(m_ui->cbFlexi, HwSettings::RM_FLEXIPORT_GPS)) {
setComboboxSelectedOption(m_ui->cbFlexi, HwSettings::RM_FLEXIPORT_DISABLED);
}
if (isComboboxOptionSelected(m_ui->cbMain, HwSettings::RM_MAINPORT_GPS)) {
setComboboxSelectedOption(m_ui->cbMain, HwSettings::RM_MAINPORT_DISABLED);
}
break;
case HwSettings::RM_RCVRPORT_MSP:
case HwSettings::RM_RCVRPORT_PPMMSP:
m_ui->lblRcvrSpeed->setVisible(false);
if (isComboboxOptionSelected(m_ui->cbFlexi, HwSettings::RM_FLEXIPORT_MSP)) {
setComboboxSelectedOption(m_ui->cbFlexi, HwSettings::RM_FLEXIPORT_DISABLED);
}
if (isComboboxOptionSelected(m_ui->cbMain, HwSettings::RM_MAINPORT_MSP)) {
setComboboxSelectedOption(m_ui->cbMain, HwSettings::RM_MAINPORT_DISABLED);
}
break;
case HwSettings::RM_RCVRPORT_MAVLINK:
case HwSettings::RM_RCVRPORT_PPMMAVLINK:
m_ui->lblRcvrSpeed->setVisible(false);
if (isComboboxOptionSelected(m_ui->cbFlexi, HwSettings::RM_FLEXIPORT_MAVLINK)) {
setComboboxSelectedOption(m_ui->cbFlexi, HwSettings::RM_FLEXIPORT_DISABLED);
}
if (isComboboxOptionSelected(m_ui->cbMain, HwSettings::RM_MAINPORT_MAVLINK)) {
setComboboxSelectedOption(m_ui->cbMain, HwSettings::RM_MAINPORT_DISABLED);
}
break;
default:
m_ui->lblRcvrSpeed->setVisible(false);
break;

View File

@ -655,6 +655,28 @@
<item>
<widget class="QComboBox" name="cbRcvrComSpeed"/>
</item>
<item>
<widget class="QComboBox" name="cbRcvrGPSSpeed"/>
</item>
<item alignment="Qt::AlignHCenter">
<widget class="QLabel" name="lblRcvrGPSProtocol">
<property name="sizePolicy">
<sizepolicy hsizetype="Preferred" vsizetype="Fixed">
<horstretch>0</horstretch>
<verstretch>0</verstretch>
</sizepolicy>
</property>
<property name="text">
<string>Protocol</string>
</property>
<property name="alignment">
<set>Qt::AlignBottom|Qt::AlignLeading|Qt::AlignLeft</set>
</property>
</widget>
</item>
<item>
<widget class="QComboBox" name="cbRcvrGPSProtocol"/>
</item>
</layout>
</item>
</layout>

View File

@ -11,9 +11,9 @@
<field name="RV_TelemetryPort" units="function" type="enum" elements="1" options="Disabled,Telemetry,ComAux,ComBridge,MSP,MAVLink" defaultvalue="Telemetry"/>
<field name="RV_GPSPort" units="function" type="enum" elements="1" options="Disabled,Telemetry,GPS,ComAux,ComBridge,MSP,MAVLink" defaultvalue="GPS"/>
<field name="RM_RcvrPort" units="function" type="enum" elements="1" options="Disabled,PWM,PPM,PPM+PWM,PPM+Telemetry,PPM+Outputs,Outputs,Telemetry,ComBridge,MSP,MAVLink"
<field name="RM_RcvrPort" units="function" type="enum" elements="1" options="Disabled,PWM,PPM,PPM+PWM,PPM+Outputs,PPM+Telemetry,PPM+DebugConsole,PPM+ComBridge,PPM+MSP,PPM+MAVLink,PPM+GPS,Outputs,Telemetry,DebugConsole,ComBridge,MSP,MAVLink,GPS"
defaultvalue="PWM"
limits="%0905NE:PPM+PWM:PPM+Telemetry:Telemetry:ComBridge:MSP:MAVLink;"/>
limits="%0905NE:PPM+PWM:PPM+Telemetry:PPM+ComBridge:PPM+MSP:PPM+MAVLink:PPM+GPS:Telemetry:ComBridge:MSP:MAVLink:GPS;"/>
<field name="RM_MainPort" units="function" type="enum" elements="1" options="Disabled,Telemetry,GPS,S.Bus,DSM,DebugConsole,ComBridge,OsdHk,MSP,MAVLink" defaultvalue="Disabled"/>
<field name="RM_FlexiPort" units="function" type="enum" elements="1" options="Disabled,Telemetry,GPS,I2C,DSM,EX.Bus,HoTT SUMD,HoTT SUMH,SRXL,DebugConsole,ComBridge,OsdHk,MSP,MAVLink" defaultvalue="Disabled"/>