diff --git a/src/main/drivers/serial.h b/src/main/drivers/serial.h index bb42cf709e..5d337a7290 100644 --- a/src/main/drivers/serial.h +++ b/src/main/drivers/serial.h @@ -55,8 +55,7 @@ typedef struct serialPort_s { uint32_t txBufferHead; uint32_t txBufferTail; - // FIXME rename member to rxCallback - serialReceiveCallbackPtr callback; + serialReceiveCallbackPtr rxCallback; } serialPort_t; struct serialPortVTable { diff --git a/src/main/drivers/serial_softserial.c b/src/main/drivers/serial_softserial.c index fa04943f43..0b5be52f51 100644 --- a/src/main/drivers/serial_softserial.c +++ b/src/main/drivers/serial_softserial.c @@ -177,7 +177,7 @@ static void resetBuffers(softSerial_t *softSerial) softSerial->port.txBufferHead = 0; } -serialPort_t *openSoftSerial(softSerialPortIndex_e portIndex, serialReceiveCallbackPtr callback, uint32_t baud, portOptions_t options) +serialPort_t *openSoftSerial(softSerialPortIndex_e portIndex, serialReceiveCallbackPtr rxCallback, uint32_t baud, portOptions_t options) { softSerial_t *softSerial = &(softSerialPorts[portIndex]); @@ -199,7 +199,7 @@ serialPort_t *openSoftSerial(softSerialPortIndex_e portIndex, serialReceiveCallb softSerial->port.baudRate = baud; softSerial->port.mode = MODE_RXTX; softSerial->port.options = options; - softSerial->port.callback = callback; + softSerial->port.rxCallback = rxCallback; resetBuffers(softSerial); @@ -315,8 +315,8 @@ void extractAndStoreRxByte(softSerial_t *softSerial) uint8_t rxByte = (softSerial->internalRxBuffer >> 1) & 0xFF; - if (softSerial->port.callback) { - softSerial->port.callback(rxByte); + if (softSerial->port.rxCallback) { + softSerial->port.rxCallback(rxByte); } else { softSerial->port.rxBuffer[softSerial->port.rxBufferHead] = rxByte; softSerial->port.rxBufferHead = (softSerial->port.rxBufferHead + 1) % softSerial->port.rxBufferSize; @@ -455,7 +455,7 @@ void softSerialWriteByte(serialPort_t *s, uint8_t ch) void softSerialSetBaudRate(serialPort_t *s, uint32_t baudRate) { softSerial_t *softSerial = (softSerial_t *)s; - openSoftSerial(softSerial->softSerialPortIndex, s->callback, baudRate, softSerial->port.options); + openSoftSerial(softSerial->softSerialPortIndex, s->rxCallback, baudRate, softSerial->port.options); } void softSerialSetMode(serialPort_t *instance, portMode_t mode) diff --git a/src/main/drivers/serial_uart.c b/src/main/drivers/serial_uart.c index 2b6eb8122a..c08eaf6579 100644 --- a/src/main/drivers/serial_uart.c +++ b/src/main/drivers/serial_uart.c @@ -93,7 +93,7 @@ static void uartReconfigure(uartPort_t *uartPort) USART_Cmd(uartPort->USARTx, ENABLE); } -serialPort_t *uartOpen(USART_TypeDef *USARTx, serialReceiveCallbackPtr callback, uint32_t baudRate, portMode_t mode, portOptions_t options) +serialPort_t *uartOpen(USART_TypeDef *USARTx, serialReceiveCallbackPtr rxCallback, uint32_t baudRate, portMode_t mode, portOptions_t options) { uartPort_t *s = NULL; @@ -129,7 +129,7 @@ serialPort_t *uartOpen(USART_TypeDef *USARTx, serialReceiveCallbackPtr callback, s->port.rxBufferHead = s->port.rxBufferTail = 0; s->port.txBufferHead = s->port.txBufferTail = 0; // callback works for IRQ-based RX ONLY - s->port.callback = callback; + s->port.rxCallback = rxCallback; s->port.mode = mode; s->port.baudRate = baudRate; s->port.options = options; diff --git a/src/main/drivers/serial_uart_stm32f10x.c b/src/main/drivers/serial_uart_stm32f10x.c index 4774ab33e6..8b422df008 100644 --- a/src/main/drivers/serial_uart_stm32f10x.c +++ b/src/main/drivers/serial_uart_stm32f10x.c @@ -55,8 +55,8 @@ void uartIrqCallback(uartPort_t *s) if (SR & USART_FLAG_RXNE && !s->rxDMAChannel) { // If we registered a callback, pass crap there - if (s->port.callback) { - s->port.callback(s->USARTx->DR); + if (s->port.rxCallback) { + s->port.rxCallback(s->USARTx->DR); } else { s->port.rxBuffer[s->port.rxBufferHead++] = s->USARTx->DR; if (s->port.rxBufferHead >= s->port.rxBufferSize) { diff --git a/src/main/drivers/serial_uart_stm32f30x.c b/src/main/drivers/serial_uart_stm32f30x.c index 29bebfb954..304c702d51 100644 --- a/src/main/drivers/serial_uart_stm32f30x.c +++ b/src/main/drivers/serial_uart_stm32f30x.c @@ -369,8 +369,8 @@ void usartIrqHandler(uartPort_t *s) uint32_t ISR = s->USARTx->ISR; if (!s->rxDMAChannel && (ISR & USART_FLAG_RXNE)) { - if (s->port.callback) { - s->port.callback(s->USARTx->RDR); + if (s->port.rxCallback) { + s->port.rxCallback(s->USARTx->RDR); } else { s->port.rxBuffer[s->port.rxBufferHead++] = s->USARTx->RDR; if (s->port.rxBufferHead >= s->port.rxBufferSize) { diff --git a/src/main/drivers/serial_uart_stm32f4xx.c b/src/main/drivers/serial_uart_stm32f4xx.c index d6bd58024e..eb20fc8ec8 100644 --- a/src/main/drivers/serial_uart_stm32f4xx.c +++ b/src/main/drivers/serial_uart_stm32f4xx.c @@ -237,8 +237,8 @@ static uartDevice_t* uartHardwareMap[] = { void uartIrqHandler(uartPort_t *s) { if (!s->rxDMAStream && (USART_GetITStatus(s->USARTx, USART_IT_RXNE) == SET)) { - if (s->port.callback) { - s->port.callback(s->USARTx->DR); + if (s->port.rxCallback) { + s->port.rxCallback(s->USARTx->DR); } else { s->port.rxBuffer[s->port.rxBufferHead] = s->USARTx->DR; s->port.rxBufferHead = (s->port.rxBufferHead + 1) % s->port.rxBufferSize; diff --git a/src/main/io/serial.c b/src/main/io/serial.c index 99f7cfcf3f..8330243599 100644 --- a/src/main/io/serial.c +++ b/src/main/io/serial.c @@ -357,7 +357,7 @@ void closeSerialPort(serialPort_t *serialPort) { // TODO wait until data has been transmitted. - serialPort->callback = NULL; + serialPort->rxCallback = NULL; serialPortUsage->function = FUNCTION_NONE; serialPortUsage->serialPort = NULL;