mirror of
https://bitbucket.org/librepilot/librepilot.git
synced 2025-01-18 03:52:11 +01:00
LP-500 Allow HoTT Telemetry on all USARTS (Rcvr, Flexi and Main) (trivial)
This commit is contained in:
parent
c5ea323770
commit
cae5668e64
@ -632,6 +632,9 @@ void PIOS_Board_Init(void)
|
||||
}
|
||||
#endif /* PIOS_INCLUDE_HOTT */
|
||||
break;
|
||||
case HWSETTINGS_RM_FLEXIPORT_HOTTTELEMETRY:
|
||||
PIOS_Board_configure_com(&pios_usart_hott_flexi_cfg, PIOS_COM_HOTT_RX_BUF_LEN, PIOS_COM_HOTT_TX_BUF_LEN, &pios_usart_com_driver, &pios_com_hott_id);
|
||||
break;
|
||||
|
||||
case HWSETTINGS_RM_FLEXIPORT_EXBUS:
|
||||
#if defined(PIOS_INCLUDE_EXBUS)
|
||||
@ -844,6 +847,9 @@ void PIOS_Board_Init(void)
|
||||
}
|
||||
#endif /* PIOS_INCLUDE_DEBUG_CONSOLE */
|
||||
break;
|
||||
case HWSETTINGS_RM_MAINPORT_HOTTTELEMETRY:
|
||||
PIOS_Board_configure_com(&pios_usart_main_cfg, PIOS_COM_HOTT_RX_BUF_LEN, PIOS_COM_HOTT_TX_BUF_LEN, &pios_usart_com_driver, &pios_com_hott_id);
|
||||
break;
|
||||
case HWSETTINGS_RM_MAINPORT_COMBRIDGE:
|
||||
PIOS_Board_configure_com(&pios_usart_main_cfg, PIOS_COM_BRIDGE_RX_BUF_LEN, PIOS_COM_BRIDGE_TX_BUF_LEN, &pios_usart_com_driver, &pios_com_bridge_id);
|
||||
break;
|
||||
@ -1048,7 +1054,7 @@ void PIOS_Board_Init(void)
|
||||
case HWSETTINGS_RM_RCVRPORT_PPMMSP:
|
||||
case HWSETTINGS_RM_RCVRPORT_PPMMAVLINK:
|
||||
case HWSETTINGS_RM_RCVRPORT_PPMGPS:
|
||||
case HWSETTINGS_RM_RCVRPORT_PPMHOTT:
|
||||
case HWSETTINGS_RM_RCVRPORT_PPMHOTTTELEMETRY:
|
||||
#if defined(PIOS_INCLUDE_PPM)
|
||||
PIOS_Board_configure_ppm(&pios_ppm_cfg);
|
||||
|
||||
@ -1098,8 +1104,8 @@ void PIOS_Board_Init(void)
|
||||
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;
|
||||
case HWSETTINGS_RM_RCVRPORT_HOTT:
|
||||
case HWSETTINGS_RM_RCVRPORT_PPMHOTT:
|
||||
case HWSETTINGS_RM_RCVRPORT_HOTTTELEMETRY:
|
||||
case HWSETTINGS_RM_RCVRPORT_PPMHOTTTELEMETRY:
|
||||
PIOS_Board_configure_com(&pios_usart_rcvrport_cfg, PIOS_COM_HOTT_RX_BUF_LEN, PIOS_COM_HOTT_TX_BUF_LEN, &pios_usart_com_driver, &pios_com_hott_id);
|
||||
break;
|
||||
case HWSETTINGS_RM_RCVRPORT_IBUS:
|
||||
|
@ -11,11 +11,11 @@
|
||||
<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+Outputs,PPM+Telemetry,PPM+DebugConsole,PPM+ComBridge,PPM+MSP,PPM+MAVLink,PPM+GPS,PPM+HoTT,Outputs,Telemetry,DebugConsole,ComBridge,MSP,MAVLink,GPS,HoTT,IBus"
|
||||
<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,PPM+HoTT Telemetry,Outputs,Telemetry,DebugConsole,ComBridge,MSP,MAVLink,GPS,HoTT Telemetry,IBus"
|
||||
defaultvalue="PWM"
|
||||
limits="%0905NE:PPM+PWM:PPM+Telemetry:PPM+DebugConsole:PPM+ComBridge:PPM+MSP:PPM+MAVLink:PPM+GPS:PPM+HoTT:Telemetry:DebugConsole:ComBridge:MSP:MAVLink:GPS:HoTT:IBus;"/>
|
||||
<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,IBus,DebugConsole,ComBridge,OsdHk,MSP,MAVLink" defaultvalue="Disabled"/>
|
||||
limits="%0905NE:PPM+PWM:PPM+Telemetry:PPM+DebugConsole:PPM+ComBridge:PPM+MSP:PPM+MAVLink:PPM+GPS:PPM+HoTT Telemetry:Telemetry:DebugConsole:ComBridge:MSP:MAVLink:GPS:HoTT Telemetry:IBus;"/>
|
||||
<field name="RM_MainPort" units="function" type="enum" elements="1" options="Disabled,Telemetry,GPS,S.Bus,DSM,HoTT Telemetry,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,HoTT Telemetry,SRXL,IBus,DebugConsole,ComBridge,OsdHk,MSP,MAVLink" defaultvalue="Disabled"/>
|
||||
|
||||
<field name="SPK2_RcvrPort" units="function" type="enum" elements="1" options="Disabled,PPM,S.Bus,DSM,SRXL,IBus,EX.Bus,HoTT SUMD,HoTT SUMH" defaultvalue="PPM"/>
|
||||
<field name="SPK2_MainPort" units="function" type="enum" elements="1" options="Disabled,Telemetry,GPS,DSM,DebugConsole,ComBridge,OsdHk,MSP,MAVLink" defaultvalue="Disabled"/>
|
||||
|
Loading…
x
Reference in New Issue
Block a user