@@ -95,6 +95,7 @@ uint32_t pios_openlrs_id; /* OpenLRS handle */
9595uint32_t pios_com_hkosd_id ; /* HK OSD ?? */
9696uint32_t pios_com_msp_id ; /* MSP */
9797uint32_t pios_com_mavlink_id ; /* MAVLink */
98+ uint32_t pios_com_frsky_sensorhub_id ; /* Frsky Sensorhub */
9899uint32_t pios_com_vcp_id ; /* USB VCP */
99100
100101#ifdef PIOS_INCLUDE_DEBUG_CONSOLE
@@ -292,109 +293,116 @@ struct uart_function {
292293};
293294
294295static const struct uart_function uart_function_map [] = {
295- [PIOS_BOARD_IO_UART_TELEMETRY ] = {
296+ [PIOS_BOARD_IO_UART_TELEMETRY ] = {
296297 .com_id = & pios_com_telem_rf_id ,
297298 .com_rx_buf_len = PIOS_COM_TELEM_RF_RX_BUF_LEN ,
298299 .com_tx_buf_len = PIOS_COM_TELEM_RF_TX_BUF_LEN ,
299300 },
300301
301- [PIOS_BOARD_IO_UART_MAVLINK ] = {
302+ [PIOS_BOARD_IO_UART_MAVLINK ] = {
302303 .com_id = & pios_com_mavlink_id ,
303304 .com_rx_buf_len = PIOS_COM_MAVLINK_RX_BUF_LEN ,
304305 .com_tx_buf_len = PIOS_COM_MAVLINK_TX_BUF_LEN ,
305306 },
306307
307- [PIOS_BOARD_IO_UART_MSP ] = {
308+ [PIOS_BOARD_IO_UART_MSP ] = {
308309 .com_id = & pios_com_msp_id ,
309310 .com_rx_buf_len = PIOS_COM_MSP_RX_BUF_LEN ,
310311 .com_tx_buf_len = PIOS_COM_MSP_TX_BUF_LEN ,
311312 },
312313#ifdef PIOS_INCLUDE_GPS
313- [PIOS_BOARD_IO_UART_GPS ] = {
314+ [PIOS_BOARD_IO_UART_GPS ] = {
314315 .com_id = & pios_com_gps_id ,
315316 .com_rx_buf_len = PIOS_COM_GPS_RX_BUF_LEN ,
316317 .com_tx_buf_len = PIOS_COM_GPS_TX_BUF_LEN ,
317318 },
318319#endif
319- [PIOS_BOARD_IO_UART_OSDHK ] = {
320+ [PIOS_BOARD_IO_UART_OSDHK ] = {
320321 .com_id = & pios_com_hkosd_id ,
321322 .com_rx_buf_len = PIOS_COM_HKOSD_RX_BUF_LEN ,
322323 .com_tx_buf_len = PIOS_COM_HKOSD_TX_BUF_LEN ,
323324 },
325+ #ifdef PIOS_INCLUDE_FRSKY_SENSORHUB
326+ [PIOS_BOARD_IO_UART_FRSKY_SENSORHUB ] = {
327+ .com_id = & pios_com_frsky_sensorhub_id ,
328+ .com_rx_buf_len = PIOS_COM_FRSKY_SENSORHUB_RX_BUF_LEN ,
329+ .com_tx_buf_len = PIOS_COM_FRSKY_SENSORHUB_TX_BUF_LEN ,
330+ },
331+ #endif
324332#ifdef PIOS_INCLUDE_HOTT_BRIDGE
325- [PIOS_BOARD_IO_UART_HOTT_BRIDGE ] = {
333+ [PIOS_BOARD_IO_UART_HOTT_BRIDGE ] = {
326334 .com_id = & pios_com_hott_id ,
327335 .com_rx_buf_len = PIOS_COM_HOTT_BRIDGE_RX_BUF_LEN ,
328336 .com_tx_buf_len = PIOS_COM_HOTT_BRIDGE_TX_BUF_LEN ,
329337 },
330338#endif
331339#ifdef PIOS_INCLUDE_DEBUG_CONSOLE
332- [PIOS_BOARD_IO_UART_DEBUGCONSOLE ] = {
340+ [PIOS_BOARD_IO_UART_DEBUGCONSOLE ] = {
333341 .com_id = & pios_com_debug_id ,
334342 .com_tx_buf_len = PIOS_COM_DEBUGCONSOLE_TX_BUF_LEN ,
335343 },
336344#endif
337- [PIOS_BOARD_IO_UART_COMBRIDGE ] = {
345+ [PIOS_BOARD_IO_UART_COMBRIDGE ] = {
338346 .com_id = & pios_com_bridge_id ,
339347 .com_rx_buf_len = PIOS_COM_BRIDGE_RX_BUF_LEN ,
340348 .com_tx_buf_len = PIOS_COM_BRIDGE_TX_BUF_LEN ,
341349 },
342350#ifdef PIOS_INCLUDE_RCVR
343351# ifdef PIOS_INCLUDE_IBUS
344- [PIOS_BOARD_IO_UART_IBUS ] = {
352+ [PIOS_BOARD_IO_UART_IBUS ] = {
345353 .rcvr_init = & PIOS_IBUS_Init ,
346354 .rcvr_driver = & pios_ibus_rcvr_driver ,
347355 .rcvr_group = MANUALCONTROLSETTINGS_CHANNELGROUPS_IBUS ,
348356 },
349357# endif /* PIOS_INCLUDE_IBUS */
350358# ifdef PIOS_INCLUDE_EXBUS
351- [PIOS_BOARD_IO_UART_EXBUS ] = {
359+ [PIOS_BOARD_IO_UART_EXBUS ] = {
352360 .rcvr_init = & PIOS_EXBUS_Init ,
353361 .rcvr_driver = & pios_exbus_rcvr_driver ,
354362 .rcvr_group = MANUALCONTROLSETTINGS_CHANNELGROUPS_EXBUS ,
355363 },
356364# endif /* PIOS_INCLUDE_EXBUS */
357365# ifdef PIOS_INCLUDE_SRXL
358- [PIOS_BOARD_IO_UART_SRXL ] = {
366+ [PIOS_BOARD_IO_UART_SRXL ] = {
359367 .rcvr_init = & PIOS_SRXL_Init ,
360368 .rcvr_driver = & pios_srxl_rcvr_driver ,
361369 .rcvr_group = MANUALCONTROLSETTINGS_CHANNELGROUPS_SRXL ,
362370 },
363371# endif /* PIOS_INCLUDE_SRXL */
364372# ifdef PIOS_INCLUDE_HOTT
365- [PIOS_BOARD_IO_UART_HOTT_SUMD ] = {
373+ [PIOS_BOARD_IO_UART_HOTT_SUMD ] = {
366374 .rcvr_init = & PIOS_HOTT_Init_SUMD ,
367375 .rcvr_driver = & pios_hott_rcvr_driver ,
368376 .rcvr_group = MANUALCONTROLSETTINGS_CHANNELGROUPS_HOTT ,
369377 },
370378
371- [PIOS_BOARD_IO_UART_HOTT_SUMH ] = {
379+ [PIOS_BOARD_IO_UART_HOTT_SUMH ] = {
372380 .rcvr_init = & PIOS_HOTT_Init_SUMH ,
373381 .rcvr_driver = & pios_hott_rcvr_driver ,
374382 .rcvr_group = MANUALCONTROLSETTINGS_CHANNELGROUPS_HOTT ,
375383 },
376384# endif /* PIOS_INCLUDE_HOTT */
377385# ifdef PIOS_INCLUDE_DSM
378- [PIOS_BOARD_IO_UART_DSM_MAIN ] = {
386+ [PIOS_BOARD_IO_UART_DSM_MAIN ] = {
379387 .rcvr_init = & PIOS_DSM_Init_Helper ,
380388 .rcvr_driver = & pios_dsm_rcvr_driver ,
381389 .rcvr_group = MANUALCONTROLSETTINGS_CHANNELGROUPS_DSMMAINPORT ,
382390 },
383391
384- [PIOS_BOARD_IO_UART_DSM_FLEXI ] = {
392+ [PIOS_BOARD_IO_UART_DSM_FLEXI ] = {
385393 .rcvr_init = & PIOS_DSM_Init_Helper ,
386394 .rcvr_driver = & pios_dsm_rcvr_driver ,
387395 .rcvr_group = MANUALCONTROLSETTINGS_CHANNELGROUPS_DSMFLEXIPORT ,
388396 },
389397
390- [PIOS_BOARD_IO_UART_DSM_RCVR ] = {
398+ [PIOS_BOARD_IO_UART_DSM_RCVR ] = {
391399 .rcvr_init = & PIOS_DSM_Init_Helper ,
392400 .rcvr_driver = & pios_dsm_rcvr_driver ,
393401 .rcvr_group = MANUALCONTROLSETTINGS_CHANNELGROUPS_DSMRCVRPORT ,
394402 },
395403# endif /* PIOS_INCLUDE_DSM */
396404# ifdef PIOS_INCLUDE_SBUS
397- [PIOS_BOARD_IO_UART_SBUS ] = {
405+ [PIOS_BOARD_IO_UART_SBUS ] = {
398406 .rcvr_init = & PIOS_SBus_Init_Helper ,
399407 .rcvr_driver = & pios_sbus_rcvr_driver ,
400408 .rcvr_group = MANUALCONTROLSETTINGS_CHANNELGROUPS_SBUS ,
0 commit comments