mirror of
https://bitbucket.org/librepilot/librepilot.git
synced 2024-12-01 09:24:10 +01:00
Merge branch 'amorale/OP-1452_comusbbridge_improvements' into next
This commit is contained in:
commit
f69e476ed3
@ -42,7 +42,7 @@
|
||||
|
||||
static void com2UsbBridgeTask(void *parameters);
|
||||
static void usb2ComBridgeTask(void *parameters);
|
||||
static void updateSettings();
|
||||
static void updateSettings(UAVObjEvent *ev);
|
||||
|
||||
// ****************
|
||||
// Private constants
|
||||
@ -106,8 +106,7 @@ static int32_t comUsbBridgeInitialize(void)
|
||||
|
||||
HwSettingsOptionalModulesGet(&optionalModules);
|
||||
|
||||
if (usart_port && vcp_port &&
|
||||
(optionalModules.ComUsbBridge == HWSETTINGS_OPTIONALMODULES_ENABLED)) {
|
||||
if (usart_port && vcp_port) {
|
||||
bridge_enabled = true;
|
||||
} else {
|
||||
bridge_enabled = false;
|
||||
@ -119,8 +118,8 @@ static int32_t comUsbBridgeInitialize(void)
|
||||
PIOS_Assert(com2usb_buf);
|
||||
usb2com_buf = pios_malloc(BRIDGE_BUF_LEN);
|
||||
PIOS_Assert(usb2com_buf);
|
||||
|
||||
updateSettings();
|
||||
HwSettingsConnectCallback(&updateSettings);
|
||||
updateSettings(0);
|
||||
}
|
||||
|
||||
return 0;
|
||||
@ -170,7 +169,7 @@ static void usb2ComBridgeTask(__attribute__((unused)) void *parameters)
|
||||
}
|
||||
|
||||
|
||||
static void updateSettings()
|
||||
static void updateSettings(__attribute__((unused)) UAVObjEvent *ev)
|
||||
{
|
||||
if (usart_port) {
|
||||
// Retrieve settings
|
||||
|
@ -123,15 +123,6 @@ void ConfigRevoHWWidget::updateObjectsFromWidgets()
|
||||
data.OptionalModules[HwSettings::OPTIONALMODULES_GPS] = HwSettings::OPTIONALMODULES_DISABLED;
|
||||
}
|
||||
|
||||
// If any port is configured to be ComBridge port, enable UsbComBridge module if it is not enabled.
|
||||
// Otherwise disable UsbComBridge module.
|
||||
if (m_ui->cbFlexi->currentIndex() == HwSettings::RM_FLEXIPORT_COMBRIDGE || m_ui->cbMain->currentIndex() == HwSettings::RM_MAINPORT_COMBRIDGE ||
|
||||
m_ui->cbUSBVCPFunction->currentIndex() == HwSettings::USB_VCPPORT_COMBRIDGE) {
|
||||
data.OptionalModules[HwSettings::OPTIONALMODULES_COMUSBBRIDGE] = HwSettings::OPTIONALMODULES_ENABLED;
|
||||
} else {
|
||||
data.OptionalModules[HwSettings::OPTIONALMODULES_COMUSBBRIDGE] = HwSettings::OPTIONALMODULES_DISABLED;
|
||||
}
|
||||
|
||||
hwSettings->setData(data);
|
||||
}
|
||||
|
||||
|
@ -15,14 +15,14 @@
|
||||
<field name="RM_RcvrPort" units="function" type="enum" elements="1" options="Disabled,PWM,PPM,PPM+PWM,PPM+Outputs,Outputs" defaultvalue="PWM"/>
|
||||
<field name="RM_MainPort" units="function" type="enum" elements="1" options="Disabled,Telemetry,GPS,S.Bus,DSM2,DSMX (10bit),DSMX (11bit),DebugConsole,ComBridge,OsdHk" defaultvalue="Telemetry"/>
|
||||
<field name="RM_FlexiPort" units="function" type="enum" elements="1" options="Disabled,Telemetry,GPS,I2C,DSM2,DSMX (10bit),DSMX (11bit),DebugConsole,ComBridge,OsdHk" defaultvalue="Disabled"/>
|
||||
|
||||
|
||||
<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" defaultvalue="57600"/>
|
||||
<field name="ComUsbBridgeSpeed" 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"/>
|
||||
<field name="USB_VCPPort" units="function" type="enum" elements="1" options="USBTelemetry,ComBridge,DebugConsole,Disabled" defaultvalue="Disabled"/>
|
||||
|
||||
<field name="OptionalModules" units="" type="enum" elementnames="CameraStab,GPS,ComUsbBridge,Fault,Altitude,Airspeed,TxPID,Autotune,Battery,Overo,MagBaro,OsdHk" options="Disabled,Enabled" defaultvalue="Disabled"/>
|
||||
<field name="OptionalModules" units="" type="enum" elementnames="CameraStab,GPS,Fault,Altitude,Airspeed,TxPID,Autotune,Battery,Overo,MagBaro,OsdHk" options="Disabled,Enabled" defaultvalue="Disabled"/>
|
||||
<field name="ADCRouting" units="" type="enum" elementnames="adc0,adc1,adc2,adc3" options="Disabled,BatteryVoltage,BatteryCurrent,AnalogAirspeed,Generic" defaultvalue="Disabled"/>
|
||||
<field name="DSMxBind" units="" type="uint8" elements="1" defaultvalue="0"/>
|
||||
<field name="WS2811LED_Out" units="" type="enum" elements="1" options="ServoOut1,ServoOut2,ServoOut3,ServoOut4,ServoOut5,ServoOut6,FlexiPin3,FlexiPin4,Disabled" defaultvalue="Disabled" />
|
||||
|
Loading…
Reference in New Issue
Block a user