Merge pull request #3054 from jflyper/bfdev-refactor-uartOpen-serialUART
Remove reference to USARTx in io layer, refactor uart_open and serialUART
This commit is contained in:
commit
4ee7a330d6
|
@ -100,40 +100,13 @@ static void uartReconfigure(uartPort_t *uartPort)
|
||||||
USART_Cmd(uartPort->USARTx, ENABLE);
|
USART_Cmd(uartPort->USARTx, ENABLE);
|
||||||
}
|
}
|
||||||
|
|
||||||
serialPort_t *uartOpen(USART_TypeDef *USARTx, serialReceiveCallbackPtr rxCallback, uint32_t baudRate, portMode_t mode, portOptions_t options)
|
serialPort_t *uartOpen(UARTDevice device, serialReceiveCallbackPtr rxCallback, uint32_t baudRate, portMode_t mode, portOptions_t options)
|
||||||
{
|
{
|
||||||
uartPort_t *s = NULL;
|
uartPort_t *s = serialUART(device, baudRate, mode, options);
|
||||||
|
|
||||||
if (false) {
|
if (!s)
|
||||||
#ifdef USE_UART1
|
|
||||||
} else if (USARTx == USART1) {
|
|
||||||
s = serialUART1(baudRate, mode, options);
|
|
||||||
|
|
||||||
#endif
|
|
||||||
#ifdef USE_UART2
|
|
||||||
} else if (USARTx == USART2) {
|
|
||||||
s = serialUART2(baudRate, mode, options);
|
|
||||||
#endif
|
|
||||||
#ifdef USE_UART3
|
|
||||||
} else if (USARTx == USART3) {
|
|
||||||
s = serialUART3(baudRate, mode, options);
|
|
||||||
#endif
|
|
||||||
#ifdef USE_UART4
|
|
||||||
} else if (USARTx == UART4) {
|
|
||||||
s = serialUART4(baudRate, mode, options);
|
|
||||||
#endif
|
|
||||||
#ifdef USE_UART5
|
|
||||||
} else if (USARTx == UART5) {
|
|
||||||
s = serialUART5(baudRate, mode, options);
|
|
||||||
#endif
|
|
||||||
#ifdef USE_UART6
|
|
||||||
} else if (USARTx == USART6) {
|
|
||||||
s = serialUART6(baudRate, mode, options);
|
|
||||||
#endif
|
|
||||||
|
|
||||||
} else {
|
|
||||||
return (serialPort_t *)s;
|
return (serialPort_t *)s;
|
||||||
}
|
|
||||||
s->txDMAEmpty = true;
|
s->txDMAEmpty = true;
|
||||||
|
|
||||||
// common serial initialisation code should move to serialPort::init()
|
// common serial initialisation code should move to serialPort::init()
|
||||||
|
|
|
@ -40,6 +40,17 @@
|
||||||
#define UART8_RX_BUFFER_SIZE 256
|
#define UART8_RX_BUFFER_SIZE 256
|
||||||
#define UART8_TX_BUFFER_SIZE 256
|
#define UART8_TX_BUFFER_SIZE 256
|
||||||
|
|
||||||
|
typedef enum UARTDevice {
|
||||||
|
UARTDEV_1 = 0,
|
||||||
|
UARTDEV_2 = 1,
|
||||||
|
UARTDEV_3 = 2,
|
||||||
|
UARTDEV_4 = 3,
|
||||||
|
UARTDEV_5 = 4,
|
||||||
|
UARTDEV_6 = 5,
|
||||||
|
UARTDEV_7 = 6,
|
||||||
|
UARTDEV_8 = 7
|
||||||
|
} UARTDevice;
|
||||||
|
|
||||||
typedef struct {
|
typedef struct {
|
||||||
serialPort_t port;
|
serialPort_t port;
|
||||||
|
|
||||||
|
@ -72,7 +83,7 @@ typedef struct {
|
||||||
USART_TypeDef *USARTx;
|
USART_TypeDef *USARTx;
|
||||||
} uartPort_t;
|
} uartPort_t;
|
||||||
|
|
||||||
serialPort_t *uartOpen(USART_TypeDef *USARTx, serialReceiveCallbackPtr rxCallback, uint32_t baudRate, portMode_t mode, portOptions_t options);
|
serialPort_t *uartOpen(UARTDevice device, serialReceiveCallbackPtr rxCallback, uint32_t baudRate, portMode_t mode, portOptions_t options);
|
||||||
|
|
||||||
// serialPort API
|
// serialPort API
|
||||||
void uartWrite(serialPort_t *instance, uint8_t ch);
|
void uartWrite(serialPort_t *instance, uint8_t ch);
|
||||||
|
|
|
@ -176,48 +176,14 @@ static void uartReconfigure(uartPort_t *uartPort)
|
||||||
return;
|
return;
|
||||||
}
|
}
|
||||||
|
|
||||||
serialPort_t *uartOpen(USART_TypeDef *USARTx, serialReceiveCallbackPtr callback, uint32_t baudRate, portMode_t mode, portOptions_t options)
|
serialPort_t *uartOpen(UARTDevice device, serialReceiveCallbackPtr callback, uint32_t baudRate, portMode_t mode, portOptions_t options)
|
||||||
{
|
{
|
||||||
uartPort_t *s = NULL;
|
uartPort_t *s = serialUART(device, baudRate, mode, options);
|
||||||
|
|
||||||
if (false) {
|
if (!s) {
|
||||||
#ifdef USE_UART1
|
|
||||||
} else if (USARTx == USART1) {
|
|
||||||
s = serialUART1(baudRate, mode, options);
|
|
||||||
#endif
|
|
||||||
#ifdef USE_UART2
|
|
||||||
} else if (USARTx == USART2) {
|
|
||||||
s = serialUART2(baudRate, mode, options);
|
|
||||||
#endif
|
|
||||||
#ifdef USE_UART3
|
|
||||||
} else if (USARTx == USART3) {
|
|
||||||
s = serialUART3(baudRate, mode, options);
|
|
||||||
#endif
|
|
||||||
#ifdef USE_UART4
|
|
||||||
} else if (USARTx == UART4) {
|
|
||||||
s = serialUART4(baudRate, mode, options);
|
|
||||||
#endif
|
|
||||||
#ifdef USE_UART5
|
|
||||||
} else if (USARTx == UART5) {
|
|
||||||
s = serialUART5(baudRate, mode, options);
|
|
||||||
#endif
|
|
||||||
#ifdef USE_UART6
|
|
||||||
} else if (USARTx == USART6) {
|
|
||||||
s = serialUART6(baudRate, mode, options);
|
|
||||||
#endif
|
|
||||||
#ifdef USE_UART7
|
|
||||||
} else if (USARTx == UART7) {
|
|
||||||
s = serialUART7(baudRate, mode, options);
|
|
||||||
#endif
|
|
||||||
#ifdef USE_UART8
|
|
||||||
} else if (USARTx == UART8) {
|
|
||||||
s = serialUART8(baudRate, mode, options);
|
|
||||||
#endif
|
|
||||||
} else {
|
|
||||||
return (serialPort_t *)s;
|
return (serialPort_t *)s;
|
||||||
}
|
}
|
||||||
|
|
||||||
|
|
||||||
s->txDMAEmpty = true;
|
s->txDMAEmpty = true;
|
||||||
|
|
||||||
// common serial initialisation code should move to serialPort::init()
|
// common serial initialisation code should move to serialPort::init()
|
||||||
|
|
|
@ -23,12 +23,4 @@ extern const struct serialPortVTable uartVTable[];
|
||||||
|
|
||||||
void uartStartTxDMA(uartPort_t *s);
|
void uartStartTxDMA(uartPort_t *s);
|
||||||
|
|
||||||
uartPort_t *serialUART1(uint32_t baudRate, portMode_t mode, portOptions_t options);
|
uartPort_t *serialUART(UARTDevice device, uint32_t baudRate, portMode_t mode, portOptions_t options);
|
||||||
uartPort_t *serialUART2(uint32_t baudRate, portMode_t mode, portOptions_t options);
|
|
||||||
uartPort_t *serialUART3(uint32_t baudRate, portMode_t mode, portOptions_t options);
|
|
||||||
uartPort_t *serialUART4(uint32_t baudRate, portMode_t mode, portOptions_t options);
|
|
||||||
uartPort_t *serialUART5(uint32_t baudRate, portMode_t mode, portOptions_t options);
|
|
||||||
uartPort_t *serialUART6(uint32_t baudRate, portMode_t mode, portOptions_t options);
|
|
||||||
uartPort_t *serialUART7(uint32_t baudRate, portMode_t mode, portOptions_t options);
|
|
||||||
uartPort_t *serialUART8(uint32_t baudRate, portMode_t mode, portOptions_t options);
|
|
||||||
|
|
||||||
|
|
|
@ -286,3 +286,25 @@ void USART3_IRQHandler(void)
|
||||||
uartIrqCallback(s);
|
uartIrqCallback(s);
|
||||||
}
|
}
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
|
// Temporary solution until serialUARTx() are refactored/consolidated
|
||||||
|
|
||||||
|
uartPort_t *serialUART(UARTDevice device, uint32_t baudRate, portMode_t mode, portOptions_t options)
|
||||||
|
{
|
||||||
|
switch (device) {
|
||||||
|
#ifdef USE_UART1
|
||||||
|
case UARTDEV_1:
|
||||||
|
return serialUART1(baudRate, mode, options);
|
||||||
|
#endif
|
||||||
|
#ifdef USE_UART2
|
||||||
|
case UARTDEV_2:
|
||||||
|
return serialUART2(baudRate, mode, options);
|
||||||
|
#endif
|
||||||
|
#ifdef USE_UART3
|
||||||
|
case UARTDEV_3:
|
||||||
|
return serialUART3(baudRate, mode, options);
|
||||||
|
#endif
|
||||||
|
default:
|
||||||
|
return NULL;
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
|
@ -378,6 +378,36 @@ uartPort_t *serialUART5(uint32_t baudRate, portMode_t mode, portOptions_t option
|
||||||
}
|
}
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
|
// Temporary solution until serialUARTx() are refactored/consolidated
|
||||||
|
|
||||||
|
uartPort_t *serialUART(UARTDevice device, uint32_t baudRate, portMode_t mode, portOptions_t options)
|
||||||
|
{
|
||||||
|
switch (device) {
|
||||||
|
#ifdef USE_UART1
|
||||||
|
case UARTDEV_1:
|
||||||
|
return serialUART1(baudRate, mode, options);
|
||||||
|
#endif
|
||||||
|
#ifdef USE_UART2
|
||||||
|
case UARTDEV_2:
|
||||||
|
return serialUART2(baudRate, mode, options);
|
||||||
|
#endif
|
||||||
|
#ifdef USE_UART3
|
||||||
|
case UARTDEV_3:
|
||||||
|
return serialUART3(baudRate, mode, options);
|
||||||
|
#endif
|
||||||
|
#ifdef USE_UART4
|
||||||
|
case UARTDEV_4:
|
||||||
|
return serialUART4(baudRate, mode, options);
|
||||||
|
#endif
|
||||||
|
#ifdef USE_UART5
|
||||||
|
case UARTDEV_5:
|
||||||
|
return serialUART5(baudRate, mode, options);
|
||||||
|
#endif
|
||||||
|
default:
|
||||||
|
return NULL;
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
void usartIrqHandler(uartPort_t *s)
|
void usartIrqHandler(uartPort_t *s)
|
||||||
{
|
{
|
||||||
uint32_t ISR = s->USARTx->ISR;
|
uint32_t ISR = s->USARTx->ISR;
|
||||||
|
|
|
@ -33,15 +33,6 @@
|
||||||
#define UART_RX_BUFFER_SIZE 512
|
#define UART_RX_BUFFER_SIZE 512
|
||||||
#define UART_TX_BUFFER_SIZE 512
|
#define UART_TX_BUFFER_SIZE 512
|
||||||
|
|
||||||
typedef enum UARTDevice {
|
|
||||||
UARTDEV_1 = 0,
|
|
||||||
UARTDEV_2 = 1,
|
|
||||||
UARTDEV_3 = 2,
|
|
||||||
UARTDEV_4 = 3,
|
|
||||||
UARTDEV_5 = 4,
|
|
||||||
UARTDEV_6 = 5
|
|
||||||
} UARTDevice;
|
|
||||||
|
|
||||||
typedef struct uartDevice_s {
|
typedef struct uartDevice_s {
|
||||||
USART_TypeDef* dev;
|
USART_TypeDef* dev;
|
||||||
uartPort_t port;
|
uartPort_t port;
|
||||||
|
@ -352,11 +343,6 @@ uartPort_t *serialUART(UARTDevice device, uint32_t baudRate, portMode_t mode, po
|
||||||
}
|
}
|
||||||
|
|
||||||
#ifdef USE_UART1
|
#ifdef USE_UART1
|
||||||
uartPort_t *serialUART1(uint32_t baudRate, portMode_t mode, portOptions_t options)
|
|
||||||
{
|
|
||||||
return serialUART(UARTDEV_1, baudRate, mode, options);
|
|
||||||
}
|
|
||||||
|
|
||||||
// USART1 Rx/Tx IRQ Handler
|
// USART1 Rx/Tx IRQ Handler
|
||||||
void USART1_IRQHandler(void)
|
void USART1_IRQHandler(void)
|
||||||
{
|
{
|
||||||
|
@ -367,12 +353,6 @@ void USART1_IRQHandler(void)
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
#ifdef USE_UART2
|
#ifdef USE_UART2
|
||||||
// USART2 - GPS or Spektrum or ?? (RX + TX by IRQ)
|
|
||||||
uartPort_t *serialUART2(uint32_t baudRate, portMode_t mode, portOptions_t options)
|
|
||||||
{
|
|
||||||
return serialUART(UARTDEV_2, baudRate, mode, options);
|
|
||||||
}
|
|
||||||
|
|
||||||
void USART2_IRQHandler(void)
|
void USART2_IRQHandler(void)
|
||||||
{
|
{
|
||||||
uartPort_t *s = &(uartHardwareMap[UARTDEV_2]->port);
|
uartPort_t *s = &(uartHardwareMap[UARTDEV_2]->port);
|
||||||
|
@ -382,11 +362,6 @@ void USART2_IRQHandler(void)
|
||||||
|
|
||||||
#ifdef USE_UART3
|
#ifdef USE_UART3
|
||||||
// USART3
|
// USART3
|
||||||
uartPort_t *serialUART3(uint32_t baudRate, portMode_t mode, portOptions_t options)
|
|
||||||
{
|
|
||||||
return serialUART(UARTDEV_3, baudRate, mode, options);
|
|
||||||
}
|
|
||||||
|
|
||||||
void USART3_IRQHandler(void)
|
void USART3_IRQHandler(void)
|
||||||
{
|
{
|
||||||
uartPort_t *s = &(uartHardwareMap[UARTDEV_3]->port);
|
uartPort_t *s = &(uartHardwareMap[UARTDEV_3]->port);
|
||||||
|
@ -396,11 +371,6 @@ void USART3_IRQHandler(void)
|
||||||
|
|
||||||
#ifdef USE_UART4
|
#ifdef USE_UART4
|
||||||
// UART4
|
// UART4
|
||||||
uartPort_t *serialUART4(uint32_t baudRate, portMode_t mode, portOptions_t options)
|
|
||||||
{
|
|
||||||
return serialUART(UARTDEV_4, baudRate, mode, options);
|
|
||||||
}
|
|
||||||
|
|
||||||
void UART4_IRQHandler(void)
|
void UART4_IRQHandler(void)
|
||||||
{
|
{
|
||||||
uartPort_t *s = &(uartHardwareMap[UARTDEV_4]->port);
|
uartPort_t *s = &(uartHardwareMap[UARTDEV_4]->port);
|
||||||
|
@ -410,11 +380,6 @@ void UART4_IRQHandler(void)
|
||||||
|
|
||||||
#ifdef USE_UART5
|
#ifdef USE_UART5
|
||||||
// UART5
|
// UART5
|
||||||
uartPort_t *serialUART5(uint32_t baudRate, portMode_t mode, portOptions_t options)
|
|
||||||
{
|
|
||||||
return serialUART(UARTDEV_5, baudRate, mode, options);
|
|
||||||
}
|
|
||||||
|
|
||||||
void UART5_IRQHandler(void)
|
void UART5_IRQHandler(void)
|
||||||
{
|
{
|
||||||
uartPort_t *s = &(uartHardwareMap[UARTDEV_5]->port);
|
uartPort_t *s = &(uartHardwareMap[UARTDEV_5]->port);
|
||||||
|
@ -424,11 +389,6 @@ void UART5_IRQHandler(void)
|
||||||
|
|
||||||
#ifdef USE_UART6
|
#ifdef USE_UART6
|
||||||
// USART6
|
// USART6
|
||||||
uartPort_t *serialUART6(uint32_t baudRate, portMode_t mode, portOptions_t options)
|
|
||||||
{
|
|
||||||
return serialUART(UARTDEV_6, baudRate, mode, options);
|
|
||||||
}
|
|
||||||
|
|
||||||
void USART6_IRQHandler(void)
|
void USART6_IRQHandler(void)
|
||||||
{
|
{
|
||||||
uartPort_t *s = &(uartHardwareMap[UARTDEV_6]->port);
|
uartPort_t *s = &(uartHardwareMap[UARTDEV_6]->port);
|
||||||
|
|
|
@ -35,17 +35,6 @@ static void handleUsartTxDma(uartPort_t *s);
|
||||||
#define UART_RX_BUFFER_SIZE UART1_RX_BUFFER_SIZE
|
#define UART_RX_BUFFER_SIZE UART1_RX_BUFFER_SIZE
|
||||||
#define UART_TX_BUFFER_SIZE UART1_TX_BUFFER_SIZE
|
#define UART_TX_BUFFER_SIZE UART1_TX_BUFFER_SIZE
|
||||||
|
|
||||||
typedef enum UARTDevice {
|
|
||||||
UARTDEV_1 = 0,
|
|
||||||
UARTDEV_2 = 1,
|
|
||||||
UARTDEV_3 = 2,
|
|
||||||
UARTDEV_4 = 3,
|
|
||||||
UARTDEV_5 = 4,
|
|
||||||
UARTDEV_6 = 5,
|
|
||||||
UARTDEV_7 = 6,
|
|
||||||
UARTDEV_8 = 7
|
|
||||||
} UARTDevice;
|
|
||||||
|
|
||||||
typedef struct uartDevice_s {
|
typedef struct uartDevice_s {
|
||||||
USART_TypeDef* dev;
|
USART_TypeDef* dev;
|
||||||
uartPort_t port;
|
uartPort_t port;
|
||||||
|
@ -439,11 +428,6 @@ uartPort_t *serialUART(UARTDevice device, uint32_t baudRate, portMode_t mode, po
|
||||||
}
|
}
|
||||||
|
|
||||||
#ifdef USE_UART1
|
#ifdef USE_UART1
|
||||||
uartPort_t *serialUART1(uint32_t baudRate, portMode_t mode, portOptions_t options)
|
|
||||||
{
|
|
||||||
return serialUART(UARTDEV_1, baudRate, mode, options);
|
|
||||||
}
|
|
||||||
|
|
||||||
// USART1 Rx/Tx IRQ Handler
|
// USART1 Rx/Tx IRQ Handler
|
||||||
void USART1_IRQHandler(void)
|
void USART1_IRQHandler(void)
|
||||||
{
|
{
|
||||||
|
@ -453,11 +437,6 @@ void USART1_IRQHandler(void)
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
#ifdef USE_UART2
|
#ifdef USE_UART2
|
||||||
uartPort_t *serialUART2(uint32_t baudRate, portMode_t mode, portOptions_t options)
|
|
||||||
{
|
|
||||||
return serialUART(UARTDEV_2, baudRate, mode, options);
|
|
||||||
}
|
|
||||||
|
|
||||||
// USART2 Rx/Tx IRQ Handler
|
// USART2 Rx/Tx IRQ Handler
|
||||||
void USART2_IRQHandler(void)
|
void USART2_IRQHandler(void)
|
||||||
{
|
{
|
||||||
|
@ -467,11 +446,6 @@ void USART2_IRQHandler(void)
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
#ifdef USE_UART3
|
#ifdef USE_UART3
|
||||||
uartPort_t *serialUART3(uint32_t baudRate, portMode_t mode, portOptions_t options)
|
|
||||||
{
|
|
||||||
return serialUART(UARTDEV_3, baudRate, mode, options);
|
|
||||||
}
|
|
||||||
|
|
||||||
// USART3 Rx/Tx IRQ Handler
|
// USART3 Rx/Tx IRQ Handler
|
||||||
void USART3_IRQHandler(void)
|
void USART3_IRQHandler(void)
|
||||||
{
|
{
|
||||||
|
@ -481,11 +455,6 @@ void USART3_IRQHandler(void)
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
#ifdef USE_UART4
|
#ifdef USE_UART4
|
||||||
uartPort_t *serialUART4(uint32_t baudRate, portMode_t mode, portOptions_t options)
|
|
||||||
{
|
|
||||||
return serialUART(UARTDEV_4, baudRate, mode, options);
|
|
||||||
}
|
|
||||||
|
|
||||||
// UART4 Rx/Tx IRQ Handler
|
// UART4 Rx/Tx IRQ Handler
|
||||||
void UART4_IRQHandler(void)
|
void UART4_IRQHandler(void)
|
||||||
{
|
{
|
||||||
|
@ -495,11 +464,6 @@ void UART4_IRQHandler(void)
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
#ifdef USE_UART5
|
#ifdef USE_UART5
|
||||||
uartPort_t *serialUART5(uint32_t baudRate, portMode_t mode, portOptions_t options)
|
|
||||||
{
|
|
||||||
return serialUART(UARTDEV_5, baudRate, mode, options);
|
|
||||||
}
|
|
||||||
|
|
||||||
// UART5 Rx/Tx IRQ Handler
|
// UART5 Rx/Tx IRQ Handler
|
||||||
void UART5_IRQHandler(void)
|
void UART5_IRQHandler(void)
|
||||||
{
|
{
|
||||||
|
@ -509,11 +473,6 @@ void UART5_IRQHandler(void)
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
#ifdef USE_UART6
|
#ifdef USE_UART6
|
||||||
uartPort_t *serialUART6(uint32_t baudRate, portMode_t mode, portOptions_t options)
|
|
||||||
{
|
|
||||||
return serialUART(UARTDEV_6, baudRate, mode, options);
|
|
||||||
}
|
|
||||||
|
|
||||||
// USART6 Rx/Tx IRQ Handler
|
// USART6 Rx/Tx IRQ Handler
|
||||||
void USART6_IRQHandler(void)
|
void USART6_IRQHandler(void)
|
||||||
{
|
{
|
||||||
|
@ -523,11 +482,6 @@ void USART6_IRQHandler(void)
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
#ifdef USE_UART7
|
#ifdef USE_UART7
|
||||||
uartPort_t *serialUART7(uint32_t baudRate, portMode_t mode, portOptions_t options)
|
|
||||||
{
|
|
||||||
return serialUART(UARTDEV_7, baudRate, mode, options);
|
|
||||||
}
|
|
||||||
|
|
||||||
// UART7 Rx/Tx IRQ Handler
|
// UART7 Rx/Tx IRQ Handler
|
||||||
void UART7_IRQHandler(void)
|
void UART7_IRQHandler(void)
|
||||||
{
|
{
|
||||||
|
@ -537,11 +491,6 @@ void UART7_IRQHandler(void)
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
#ifdef USE_UART8
|
#ifdef USE_UART8
|
||||||
uartPort_t *serialUART8(uint32_t baudRate, portMode_t mode, portOptions_t options)
|
|
||||||
{
|
|
||||||
return serialUART(UARTDEV_8, baudRate, mode, options);
|
|
||||||
}
|
|
||||||
|
|
||||||
// UART8 Rx/Tx IRQ Handler
|
// UART8 Rx/Tx IRQ Handler
|
||||||
void UART8_IRQHandler(void)
|
void UART8_IRQHandler(void)
|
||||||
{
|
{
|
||||||
|
|
|
@ -36,7 +36,11 @@
|
||||||
#include "drivers/serial_softserial.h"
|
#include "drivers/serial_softserial.h"
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
#if defined(USE_UART1) || defined(USE_UART2) || defined(USE_UART3) || defined(USE_UART4) || defined(USE_UART5) || defined(USE_UART6)
|
#define USE_UART (defined(USE_UART1) || defined(USE_UART2) || defined(USE_UART3) || defined(USE_UART4) || defined(USE_UART5) || defined(USE_UART6) || defined(USE_UART7) || defined(USE_UART8))
|
||||||
|
|
||||||
|
#define USE_SERIAL (USE_UART || defined(USE_SOFTSERIAL1) || defined(USE_SOFTSERIAL2))
|
||||||
|
|
||||||
|
#if USE_UART
|
||||||
#include "drivers/serial_uart.h"
|
#include "drivers/serial_uart.h"
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
|
@ -328,7 +332,7 @@ serialPort_t *openSerialPort(
|
||||||
portMode_t mode,
|
portMode_t mode,
|
||||||
portOptions_t options)
|
portOptions_t options)
|
||||||
{
|
{
|
||||||
#if (!defined(USE_UART1) && !defined(USE_UART2) && !defined(USE_UART3) && !defined(USE_UART4) && !defined(USE_UART5) && !defined(USE_UART6) && !defined(USE_SOFTSERIAL1) && !defined(USE_SOFTSERIAL2))
|
#if !(USE_SERIAL)
|
||||||
UNUSED(rxCallback);
|
UNUSED(rxCallback);
|
||||||
UNUSED(baudRate);
|
UNUSED(baudRate);
|
||||||
UNUSED(mode);
|
UNUSED(mode);
|
||||||
|
@ -349,46 +353,36 @@ serialPort_t *openSerialPort(
|
||||||
serialPort = usbVcpOpen();
|
serialPort = usbVcpOpen();
|
||||||
break;
|
break;
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
|
#if defined(USE_UART)
|
||||||
#ifdef USE_UART1
|
#ifdef USE_UART1
|
||||||
case SERIAL_PORT_USART1:
|
case SERIAL_PORT_USART1:
|
||||||
serialPort = uartOpen(USART1, rxCallback, baudRate, mode, options);
|
|
||||||
break;
|
|
||||||
#endif
|
#endif
|
||||||
#ifdef USE_UART2
|
#ifdef USE_UART2
|
||||||
case SERIAL_PORT_USART2:
|
case SERIAL_PORT_USART2:
|
||||||
serialPort = uartOpen(USART2, rxCallback, baudRate, mode, options);
|
|
||||||
break;
|
|
||||||
#endif
|
#endif
|
||||||
#ifdef USE_UART3
|
#ifdef USE_UART3
|
||||||
case SERIAL_PORT_USART3:
|
case SERIAL_PORT_USART3:
|
||||||
serialPort = uartOpen(USART3, rxCallback, baudRate, mode, options);
|
|
||||||
break;
|
|
||||||
#endif
|
#endif
|
||||||
#ifdef USE_UART4
|
#ifdef USE_UART4
|
||||||
case SERIAL_PORT_UART4:
|
case SERIAL_PORT_UART4:
|
||||||
serialPort = uartOpen(UART4, rxCallback, baudRate, mode, options);
|
|
||||||
break;
|
|
||||||
#endif
|
#endif
|
||||||
#ifdef USE_UART5
|
#ifdef USE_UART5
|
||||||
case SERIAL_PORT_UART5:
|
case SERIAL_PORT_UART5:
|
||||||
serialPort = uartOpen(UART5, rxCallback, baudRate, mode, options);
|
|
||||||
break;
|
|
||||||
#endif
|
#endif
|
||||||
#ifdef USE_UART6
|
#ifdef USE_UART6
|
||||||
case SERIAL_PORT_USART6:
|
case SERIAL_PORT_USART6:
|
||||||
serialPort = uartOpen(USART6, rxCallback, baudRate, mode, options);
|
|
||||||
break;
|
|
||||||
#endif
|
#endif
|
||||||
#ifdef USE_UART7
|
#ifdef USE_UART7
|
||||||
case SERIAL_PORT_USART7:
|
case SERIAL_PORT_USART7:
|
||||||
serialPort = uartOpen(UART7, rxCallback, baudRate, mode, options);
|
|
||||||
break;
|
|
||||||
#endif
|
#endif
|
||||||
#ifdef USE_UART8
|
#ifdef USE_UART8
|
||||||
case SERIAL_PORT_USART8:
|
case SERIAL_PORT_USART8:
|
||||||
serialPort = uartOpen(UART8, rxCallback, baudRate, mode, options);
|
#endif
|
||||||
|
serialPort = uartOpen(SERIAL_PORT_IDENTIFIER_TO_UARTDEV(identifier), rxCallback, baudRate, mode, options);
|
||||||
break;
|
break;
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
#ifdef USE_SOFTSERIAL1
|
#ifdef USE_SOFTSERIAL1
|
||||||
case SERIAL_PORT_SOFTSERIAL1:
|
case SERIAL_PORT_SOFTSERIAL1:
|
||||||
serialPort = openSoftSerial(SOFTSERIAL1, rxCallback, baudRate, mode, options);
|
serialPort = openSoftSerial(SOFTSERIAL1, rxCallback, baudRate, mode, options);
|
||||||
|
|
|
@ -87,6 +87,8 @@ extern const serialPortIdentifier_e serialPortIdentifiers[SERIAL_PORT_COUNT];
|
||||||
|
|
||||||
#define SERIAL_PORT_IDENTIFIER_TO_INDEX(x) (((x) <= SERIAL_PORT_USART8) ? (x) : (RESOURCE_SOFT_OFFSET + ((x) - SERIAL_PORT_SOFTSERIAL1)))
|
#define SERIAL_PORT_IDENTIFIER_TO_INDEX(x) (((x) <= SERIAL_PORT_USART8) ? (x) : (RESOURCE_SOFT_OFFSET + ((x) - SERIAL_PORT_SOFTSERIAL1)))
|
||||||
|
|
||||||
|
#define SERIAL_PORT_IDENTIFIER_TO_UARTDEV(x) ((x) - SERIAL_PORT_USART1 + UARTDEV_1)
|
||||||
|
|
||||||
//
|
//
|
||||||
// runtime
|
// runtime
|
||||||
//
|
//
|
||||||
|
|
Loading…
Reference in New Issue