1
0
mirror of https://bitbucket.org/librepilot/librepilot.git synced 2025-02-20 10:54:14 +01:00

LP-512 Added missing HoTT Bridge and Frsky Sensor Hub to list of protocols on PikoBlx, Spracingf3 and Spracingf3 evo

This commit is contained in:
Vladimir Zidar 2017-05-30 00:54:05 +02:00
parent 916188dd11
commit e8bccefb9d
6 changed files with 45 additions and 39 deletions

View File

@ -194,18 +194,20 @@ void PIOS_Board_Init(void)
static const PIOS_BOARD_IO_UART_Function uart_function_map[] = {
[HWPIKOBLXSETTINGS_UARTPORT_TELEMETRY] = PIOS_BOARD_IO_UART_TELEMETRY,
[HWPIKOBLXSETTINGS_UARTPORT_GPS] = PIOS_BOARD_IO_UART_GPS,
[HWPIKOBLXSETTINGS_UARTPORT_SBUS] = PIOS_BOARD_IO_UART_SBUS,
[HWPIKOBLXSETTINGS_UARTPORT_DSM] = PIOS_BOARD_IO_UART_DSM_MAIN, // single DSM instance? ok.
[HWPIKOBLXSETTINGS_UARTPORT_EXBUS] = PIOS_BOARD_IO_UART_EXBUS,
[HWPIKOBLXSETTINGS_UARTPORT_HOTTSUMD] = PIOS_BOARD_IO_UART_HOTT_SUMD,
[HWPIKOBLXSETTINGS_UARTPORT_HOTTSUMH] = PIOS_BOARD_IO_UART_HOTT_SUMH,
[HWPIKOBLXSETTINGS_UARTPORT_SRXL] = PIOS_BOARD_IO_UART_SRXL,
[HWPIKOBLXSETTINGS_UARTPORT_IBUS] = PIOS_BOARD_IO_UART_IBUS,
[HWPIKOBLXSETTINGS_UARTPORT_DEBUGCONSOLE] = PIOS_BOARD_IO_UART_DEBUGCONSOLE,
[HWPIKOBLXSETTINGS_UARTPORT_COMBRIDGE] = PIOS_BOARD_IO_UART_COMBRIDGE,
[HWPIKOBLXSETTINGS_UARTPORT_MSP] = PIOS_BOARD_IO_UART_MSP,
[HWPIKOBLXSETTINGS_UARTPORT_MAVLINK] = PIOS_BOARD_IO_UART_MAVLINK,
[HWPIKOBLXSETTINGS_UARTPORT_GPS] = PIOS_BOARD_IO_UART_GPS,
[HWPIKOBLXSETTINGS_UARTPORT_SBUS] = PIOS_BOARD_IO_UART_SBUS,
[HWPIKOBLXSETTINGS_UARTPORT_DSM] = PIOS_BOARD_IO_UART_DSM_MAIN, // single DSM instance? ok.
[HWPIKOBLXSETTINGS_UARTPORT_EXBUS] = PIOS_BOARD_IO_UART_EXBUS,
[HWPIKOBLXSETTINGS_UARTPORT_HOTTSUMD] = PIOS_BOARD_IO_UART_HOTT_SUMD,
[HWPIKOBLXSETTINGS_UARTPORT_HOTTSUMH] = PIOS_BOARD_IO_UART_HOTT_SUMH,
[HWPIKOBLXSETTINGS_UARTPORT_SRXL] = PIOS_BOARD_IO_UART_SRXL,
[HWPIKOBLXSETTINGS_UARTPORT_IBUS] = PIOS_BOARD_IO_UART_IBUS,
[HWPIKOBLXSETTINGS_UARTPORT_DEBUGCONSOLE] = PIOS_BOARD_IO_UART_DEBUGCONSOLE,
[HWPIKOBLXSETTINGS_UARTPORT_COMBRIDGE] = PIOS_BOARD_IO_UART_COMBRIDGE,
[HWPIKOBLXSETTINGS_UARTPORT_MSP] = PIOS_BOARD_IO_UART_MSP,
[HWPIKOBLXSETTINGS_UARTPORT_MAVLINK] = PIOS_BOARD_IO_UART_MAVLINK,
[HWPIKOBLXSETTINGS_UARTPORT_HOTTTELEMETRY] = PIOS_BOARD_IO_UART_HOTT_BRIDGE,
[HWPIKOBLXSETTINGS_UARTPORT_FRSKYSENSORHUB] = PIOS_BOARD_IO_UART_FRSKY_SENSORHUB,
};
for (unsigned int i = 0; i < HWPIKOBLXSETTINGS_UARTPORT_NUMELEM; ++i) {

View File

@ -184,18 +184,20 @@ void PIOS_Board_Init(void)
static const PIOS_BOARD_IO_UART_Function uart_function_map[] = {
[HWSPRACINGF3SETTINGS_UARTPORT_TELEMETRY] = PIOS_BOARD_IO_UART_TELEMETRY,
[HWSPRACINGF3SETTINGS_UARTPORT_GPS] = PIOS_BOARD_IO_UART_GPS,
[HWSPRACINGF3SETTINGS_UARTPORT_SBUS] = PIOS_BOARD_IO_UART_SBUS,
[HWSPRACINGF3SETTINGS_UARTPORT_DSM] = PIOS_BOARD_IO_UART_DSM_MAIN, // single DSM instance? ok.
[HWSPRACINGF3SETTINGS_UARTPORT_EXBUS] = PIOS_BOARD_IO_UART_EXBUS,
[HWSPRACINGF3SETTINGS_UARTPORT_HOTTSUMD] = PIOS_BOARD_IO_UART_HOTT_SUMD,
[HWSPRACINGF3SETTINGS_UARTPORT_HOTTSUMH] = PIOS_BOARD_IO_UART_HOTT_SUMH,
[HWSPRACINGF3SETTINGS_UARTPORT_SRXL] = PIOS_BOARD_IO_UART_SRXL,
[HWSPRACINGF3SETTINGS_UARTPORT_IBUS] = PIOS_BOARD_IO_UART_IBUS,
[HWSPRACINGF3SETTINGS_UARTPORT_DEBUGCONSOLE] = PIOS_BOARD_IO_UART_DEBUGCONSOLE,
[HWSPRACINGF3SETTINGS_UARTPORT_COMBRIDGE] = PIOS_BOARD_IO_UART_COMBRIDGE,
[HWSPRACINGF3SETTINGS_UARTPORT_MSP] = PIOS_BOARD_IO_UART_MSP,
[HWSPRACINGF3SETTINGS_UARTPORT_MAVLINK] = PIOS_BOARD_IO_UART_MAVLINK,
[HWSPRACINGF3SETTINGS_UARTPORT_GPS] = PIOS_BOARD_IO_UART_GPS,
[HWSPRACINGF3SETTINGS_UARTPORT_SBUS] = PIOS_BOARD_IO_UART_SBUS,
[HWSPRACINGF3SETTINGS_UARTPORT_DSM] = PIOS_BOARD_IO_UART_DSM_MAIN, // single DSM instance? ok.
[HWSPRACINGF3SETTINGS_UARTPORT_EXBUS] = PIOS_BOARD_IO_UART_EXBUS,
[HWSPRACINGF3SETTINGS_UARTPORT_HOTTSUMD] = PIOS_BOARD_IO_UART_HOTT_SUMD,
[HWSPRACINGF3SETTINGS_UARTPORT_HOTTSUMH] = PIOS_BOARD_IO_UART_HOTT_SUMH,
[HWSPRACINGF3SETTINGS_UARTPORT_SRXL] = PIOS_BOARD_IO_UART_SRXL,
[HWSPRACINGF3SETTINGS_UARTPORT_IBUS] = PIOS_BOARD_IO_UART_IBUS,
[HWSPRACINGF3SETTINGS_UARTPORT_DEBUGCONSOLE] = PIOS_BOARD_IO_UART_DEBUGCONSOLE,
[HWSPRACINGF3SETTINGS_UARTPORT_COMBRIDGE] = PIOS_BOARD_IO_UART_COMBRIDGE,
[HWSPRACINGF3SETTINGS_UARTPORT_MSP] = PIOS_BOARD_IO_UART_MSP,
[HWSPRACINGF3SETTINGS_UARTPORT_MAVLINK] = PIOS_BOARD_IO_UART_MAVLINK,
[HWSPRACINGF3SETTINGS_UARTPORT_HOTTTELEMETRY] = PIOS_BOARD_IO_UART_HOTT_BRIDGE,
[HWSPRACINGF3SETTINGS_UARTPORT_FRSKYSENSORHUB] = PIOS_BOARD_IO_UART_FRSKY_SENSORHUB,
};
for (unsigned int i = 0; i < HWSPRACINGF3SETTINGS_UARTPORT_NUMELEM; ++i) {

View File

@ -200,18 +200,20 @@ void PIOS_Board_Init(void)
static const PIOS_BOARD_IO_UART_Function uart_function_map[] = {
[HWSPRACINGF3EVOSETTINGS_UARTPORT_TELEMETRY] = PIOS_BOARD_IO_UART_TELEMETRY,
[HWSPRACINGF3EVOSETTINGS_UARTPORT_GPS] = PIOS_BOARD_IO_UART_GPS,
[HWSPRACINGF3EVOSETTINGS_UARTPORT_SBUS] = PIOS_BOARD_IO_UART_SBUS,
[HWSPRACINGF3EVOSETTINGS_UARTPORT_DSM] = PIOS_BOARD_IO_UART_DSM_MAIN, // single DSM instance? ok.
[HWSPRACINGF3EVOSETTINGS_UARTPORT_EXBUS] = PIOS_BOARD_IO_UART_EXBUS,
[HWSPRACINGF3EVOSETTINGS_UARTPORT_HOTTSUMD] = PIOS_BOARD_IO_UART_HOTT_SUMD,
[HWSPRACINGF3EVOSETTINGS_UARTPORT_HOTTSUMH] = PIOS_BOARD_IO_UART_HOTT_SUMH,
[HWSPRACINGF3EVOSETTINGS_UARTPORT_SRXL] = PIOS_BOARD_IO_UART_SRXL,
[HWSPRACINGF3EVOSETTINGS_UARTPORT_IBUS] = PIOS_BOARD_IO_UART_IBUS,
[HWSPRACINGF3EVOSETTINGS_UARTPORT_DEBUGCONSOLE] = PIOS_BOARD_IO_UART_DEBUGCONSOLE,
[HWSPRACINGF3EVOSETTINGS_UARTPORT_COMBRIDGE] = PIOS_BOARD_IO_UART_COMBRIDGE,
[HWSPRACINGF3EVOSETTINGS_UARTPORT_MSP] = PIOS_BOARD_IO_UART_MSP,
[HWSPRACINGF3EVOSETTINGS_UARTPORT_MAVLINK] = PIOS_BOARD_IO_UART_MAVLINK,
[HWSPRACINGF3EVOSETTINGS_UARTPORT_GPS] = PIOS_BOARD_IO_UART_GPS,
[HWSPRACINGF3EVOSETTINGS_UARTPORT_SBUS] = PIOS_BOARD_IO_UART_SBUS,
[HWSPRACINGF3EVOSETTINGS_UARTPORT_DSM] = PIOS_BOARD_IO_UART_DSM_MAIN, // single DSM instance? ok.
[HWSPRACINGF3EVOSETTINGS_UARTPORT_EXBUS] = PIOS_BOARD_IO_UART_EXBUS,
[HWSPRACINGF3EVOSETTINGS_UARTPORT_HOTTSUMD] = PIOS_BOARD_IO_UART_HOTT_SUMD,
[HWSPRACINGF3EVOSETTINGS_UARTPORT_HOTTSUMH] = PIOS_BOARD_IO_UART_HOTT_SUMH,
[HWSPRACINGF3EVOSETTINGS_UARTPORT_SRXL] = PIOS_BOARD_IO_UART_SRXL,
[HWSPRACINGF3EVOSETTINGS_UARTPORT_IBUS] = PIOS_BOARD_IO_UART_IBUS,
[HWSPRACINGF3EVOSETTINGS_UARTPORT_DEBUGCONSOLE] = PIOS_BOARD_IO_UART_DEBUGCONSOLE,
[HWSPRACINGF3EVOSETTINGS_UARTPORT_COMBRIDGE] = PIOS_BOARD_IO_UART_COMBRIDGE,
[HWSPRACINGF3EVOSETTINGS_UARTPORT_MSP] = PIOS_BOARD_IO_UART_MSP,
[HWSPRACINGF3EVOSETTINGS_UARTPORT_MAVLINK] = PIOS_BOARD_IO_UART_MAVLINK,
[HWSPRACINGF3EVOSETTINGS_UARTPORT_HOTTTELEMETRY] = PIOS_BOARD_IO_UART_HOTT_BRIDGE,
[HWSPRACINGF3EVOSETTINGS_UARTPORT_FRSKYSENSORHUB] = PIOS_BOARD_IO_UART_FRSKY_SENSORHUB,
};
for (unsigned int i = 0; i < HWSPRACINGF3EVOSETTINGS_UARTPORT_NUMELEM; ++i) {

View File

@ -1,7 +1,7 @@
<xml>
<object name="HwPikoBLXSettings" singleinstance="true" settings="true" category="System">
<description>Furious FPV Piko BLX Micro Flight Controller hardware configuration</description>
<field name="UARTPort" units="function" type="enum" elements="3" options="Disabled,Telemetry,GPS,S.Bus,DSM,EX.Bus,HoTT SUMD,HoTT SUMH,SRXL,IBus,DebugConsole,ComBridge,MSP,MAVLink" defaultvalue="Disabled"/>
<field name="UARTPort" units="function" type="enum" elements="3" options="Disabled,Telemetry,GPS,S.Bus,DSM,EX.Bus,HoTT SUMD,HoTT SUMH,SRXL,IBus,DebugConsole,ComBridge,MSP,MAVLink,HoTT Telemetry,FrskySensorHub" defaultvalue="Disabled"/>
<field name="LEDPort" units="function" type="enum" elements="1" options="Disabled,WS2811,Output" defaultvalue="Disabled"/>
<field name="TransponderPort" units="function" type="enum" elements="1" options="Disabled,Enabled" defaultvalue="Disabled"/>
<field name="BuzzerPort" units="function" type="enum" elements="1" options="Disabled,Enabled" defaultvalue="Disabled"/>

View File

@ -1,7 +1,7 @@
<xml>
<object name="HwSPRacingF3EVOSettings" singleinstance="true" settings="true" category="System">
<description>Seriously Pro SPRacingF3 EVO hardware configuration.</description>
<field name="UARTPort" units="function" type="enum" elements="3" options="Disabled,Telemetry,GPS,S.Bus,DSM,EX.Bus,HoTT SUMD,HoTT SUMH,SRXL,IBus,DebugConsole,ComBridge,MSP,MAVLink,PPM" defaultvalue="Disabled" limits="%NE:PPM;;%NE:PPM"/>
<field name="UARTPort" units="function" type="enum" elements="3" options="Disabled,Telemetry,GPS,S.Bus,DSM,EX.Bus,HoTT SUMD,HoTT SUMH,SRXL,IBus,DebugConsole,ComBridge,MSP,MAVLink,HoTT Telemetry,FrskySensorHub,PPM" defaultvalue="Disabled" limits="%NE:PPM;;%NE:PPM"/>
<field name="I2CPort" units="function" type="enum" elements="1" options="Disabled,I2C" defaultvalue="Disabled"/>
<field name="LEDPort" units="function" type="enum" elements="1" options="Disabled,WS2811,Output" defaultvalue="Disabled"/>
<field name="BuzzerPort" units="function" type="enum" elements="1" options="Disabled,Output" defaultvalue="Disabled"/>

View File

@ -1,7 +1,7 @@
<xml>
<object name="HwSPRacingF3Settings" singleinstance="true" settings="true" category="System">
<description>Seriously Pro SPRacingF3 hardware configuration.</description>
<field name="UARTPort" units="function" type="enum" elements="3" options="Disabled,Telemetry,GPS,S.Bus,DSM,EX.Bus,HoTT SUMD,HoTT SUMH,SRXL,IBus,DebugConsole,ComBridge,MSP,MAVLink" defaultvalue="Disabled"/>
<field name="UARTPort" units="function" type="enum" elements="3" options="Disabled,Telemetry,GPS,S.Bus,DSM,EX.Bus,HoTT SUMD,HoTT SUMH,SRXL,IBus,DebugConsole,ComBridge,MSP,MAVLink,HoTT Telemetry,FrskySensorHub" defaultvalue="Disabled"/>
<field name="I2CPort" units="function" type="enum" elements="1" options="Disabled,I2C" defaultvalue="Disabled"/>
<field name="LEDPort" units="function" type="enum" elements="1" options="Disabled,WS2811,Output" defaultvalue="Disabled"/>
<field name="BuzzerPort" units="function" type="enum" elements="1" options="Disabled,Output" defaultvalue="Disabled"/>