@@ -73,6 +73,7 @@ static const PIOS_BOARD_IO_UART_Function flexiio_function_map[] = {
7373 [HWSETTINGS_RM_RCVRPORT_GPS ] = PIOS_BOARD_IO_UART_GPS ,
7474 [HWSETTINGS_RM_RCVRPORT_IBUS ] = PIOS_BOARD_IO_UART_IBUS ,
7575 [HWSETTINGS_RM_RCVRPORT_FRSKYSENSORHUB ] = PIOS_BOARD_IO_UART_FRSKY_SENSORHUB ,
76+ [HWSETTINGS_RM_RCVRPORT_HOTTTELEMETRY ] = PIOS_BOARD_IO_UART_HOTT_BRIDGE ,
7677};
7778
7879static const PIOS_BOARD_IO_UART_Function main_function_map [] = {
@@ -86,6 +87,7 @@ static const PIOS_BOARD_IO_UART_Function main_function_map[] = {
8687 [HWSETTINGS_RM_MAINPORT_MSP ] = PIOS_BOARD_IO_UART_MSP ,
8788 [HWSETTINGS_RM_MAINPORT_MAVLINK ] = PIOS_BOARD_IO_UART_MAVLINK ,
8889 [HWSETTINGS_RM_MAINPORT_FRSKYSENSORHUB ] = PIOS_BOARD_IO_UART_FRSKY_SENSORHUB ,
90+ [HWSETTINGS_RM_MAINPORT_HOTTTELEMETRY ] = PIOS_BOARD_IO_UART_HOTT_BRIDGE ,
8991};
9092
9193static const PIOS_BOARD_IO_UART_Function flexi_function_map [] = {
@@ -103,6 +105,7 @@ static const PIOS_BOARD_IO_UART_Function flexi_function_map[] = {
103105 [HWSETTINGS_RM_FLEXIPORT_MSP ] = PIOS_BOARD_IO_UART_MSP ,
104106 [HWSETTINGS_RM_FLEXIPORT_MAVLINK ] = PIOS_BOARD_IO_UART_MAVLINK ,
105107 [HWSETTINGS_RM_FLEXIPORT_FRSKYSENSORHUB ] = PIOS_BOARD_IO_UART_FRSKY_SENSORHUB ,
108+ [HWSETTINGS_RM_FLEXIPORT_HOTTTELEMETRY ] = PIOS_BOARD_IO_UART_HOTT_BRIDGE ,
106109};
107110
108111/**
0 commit comments