mirror of
https://github.com/betaflight/betaflight.git
synced 2025-07-17 05:15:25 +03:00
Merge pull request #1305 from martinbudden/bf_serial_callback_rename
Renamed serial port callback
This commit is contained in:
commit
855e0a9f90
10 changed files with 30 additions and 30 deletions
|
@ -55,8 +55,7 @@ typedef struct serialPort_s {
|
||||||
uint32_t txBufferHead;
|
uint32_t txBufferHead;
|
||||||
uint32_t txBufferTail;
|
uint32_t txBufferTail;
|
||||||
|
|
||||||
// FIXME rename member to rxCallback
|
serialReceiveCallbackPtr rxCallback;
|
||||||
serialReceiveCallbackPtr callback;
|
|
||||||
} serialPort_t;
|
} serialPort_t;
|
||||||
|
|
||||||
struct serialPortVTable {
|
struct serialPortVTable {
|
||||||
|
|
|
@ -177,7 +177,7 @@ static void resetBuffers(softSerial_t *softSerial)
|
||||||
softSerial->port.txBufferHead = 0;
|
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]);
|
softSerial_t *softSerial = &(softSerialPorts[portIndex]);
|
||||||
|
|
||||||
|
@ -199,7 +199,7 @@ serialPort_t *openSoftSerial(softSerialPortIndex_e portIndex, serialReceiveCallb
|
||||||
softSerial->port.baudRate = baud;
|
softSerial->port.baudRate = baud;
|
||||||
softSerial->port.mode = MODE_RXTX;
|
softSerial->port.mode = MODE_RXTX;
|
||||||
softSerial->port.options = options;
|
softSerial->port.options = options;
|
||||||
softSerial->port.callback = callback;
|
softSerial->port.rxCallback = rxCallback;
|
||||||
|
|
||||||
resetBuffers(softSerial);
|
resetBuffers(softSerial);
|
||||||
|
|
||||||
|
@ -315,8 +315,8 @@ void extractAndStoreRxByte(softSerial_t *softSerial)
|
||||||
|
|
||||||
uint8_t rxByte = (softSerial->internalRxBuffer >> 1) & 0xFF;
|
uint8_t rxByte = (softSerial->internalRxBuffer >> 1) & 0xFF;
|
||||||
|
|
||||||
if (softSerial->port.callback) {
|
if (softSerial->port.rxCallback) {
|
||||||
softSerial->port.callback(rxByte);
|
softSerial->port.rxCallback(rxByte);
|
||||||
} else {
|
} else {
|
||||||
softSerial->port.rxBuffer[softSerial->port.rxBufferHead] = rxByte;
|
softSerial->port.rxBuffer[softSerial->port.rxBufferHead] = rxByte;
|
||||||
softSerial->port.rxBufferHead = (softSerial->port.rxBufferHead + 1) % softSerial->port.rxBufferSize;
|
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)
|
void softSerialSetBaudRate(serialPort_t *s, uint32_t baudRate)
|
||||||
{
|
{
|
||||||
softSerial_t *softSerial = (softSerial_t *)s;
|
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)
|
void softSerialSetMode(serialPort_t *instance, portMode_t mode)
|
||||||
|
|
|
@ -24,7 +24,7 @@ typedef enum {
|
||||||
SOFTSERIAL2
|
SOFTSERIAL2
|
||||||
} softSerialPortIndex_e;
|
} softSerialPortIndex_e;
|
||||||
|
|
||||||
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);
|
||||||
|
|
||||||
// serialPort API
|
// serialPort API
|
||||||
void softSerialWriteByte(serialPort_t *instance, uint8_t ch);
|
void softSerialWriteByte(serialPort_t *instance, uint8_t ch);
|
||||||
|
|
|
@ -93,7 +93,7 @@ static void uartReconfigure(uartPort_t *uartPort)
|
||||||
USART_Cmd(uartPort->USARTx, ENABLE);
|
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;
|
uartPort_t *s = NULL;
|
||||||
|
|
||||||
|
@ -133,7 +133,7 @@ serialPort_t *uartOpen(USART_TypeDef *USARTx, serialReceiveCallbackPtr callback,
|
||||||
s->port.rxBufferHead = s->port.rxBufferTail = 0;
|
s->port.rxBufferHead = s->port.rxBufferTail = 0;
|
||||||
s->port.txBufferHead = s->port.txBufferTail = 0;
|
s->port.txBufferHead = s->port.txBufferTail = 0;
|
||||||
// callback works for IRQ-based RX ONLY
|
// callback works for IRQ-based RX ONLY
|
||||||
s->port.callback = callback;
|
s->port.rxCallback = rxCallback;
|
||||||
s->port.mode = mode;
|
s->port.mode = mode;
|
||||||
s->port.baudRate = baudRate;
|
s->port.baudRate = baudRate;
|
||||||
s->port.options = options;
|
s->port.options = options;
|
||||||
|
|
|
@ -61,7 +61,7 @@ typedef struct {
|
||||||
USART_TypeDef *USARTx;
|
USART_TypeDef *USARTx;
|
||||||
} uartPort_t;
|
} uartPort_t;
|
||||||
|
|
||||||
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);
|
||||||
|
|
||||||
// serialPort API
|
// serialPort API
|
||||||
void uartWrite(serialPort_t *instance, uint8_t ch);
|
void uartWrite(serialPort_t *instance, uint8_t ch);
|
||||||
|
|
|
@ -55,8 +55,8 @@ void uartIrqCallback(uartPort_t *s)
|
||||||
|
|
||||||
if (SR & USART_FLAG_RXNE && !s->rxDMAChannel) {
|
if (SR & USART_FLAG_RXNE && !s->rxDMAChannel) {
|
||||||
// If we registered a callback, pass crap there
|
// If we registered a callback, pass crap there
|
||||||
if (s->port.callback) {
|
if (s->port.rxCallback) {
|
||||||
s->port.callback(s->USARTx->DR);
|
s->port.rxCallback(s->USARTx->DR);
|
||||||
} else {
|
} else {
|
||||||
s->port.rxBuffer[s->port.rxBufferHead++] = s->USARTx->DR;
|
s->port.rxBuffer[s->port.rxBufferHead++] = s->USARTx->DR;
|
||||||
if (s->port.rxBufferHead >= s->port.rxBufferSize) {
|
if (s->port.rxBufferHead >= s->port.rxBufferSize) {
|
||||||
|
|
|
@ -369,8 +369,8 @@ void usartIrqHandler(uartPort_t *s)
|
||||||
uint32_t ISR = s->USARTx->ISR;
|
uint32_t ISR = s->USARTx->ISR;
|
||||||
|
|
||||||
if (!s->rxDMAChannel && (ISR & USART_FLAG_RXNE)) {
|
if (!s->rxDMAChannel && (ISR & USART_FLAG_RXNE)) {
|
||||||
if (s->port.callback) {
|
if (s->port.rxCallback) {
|
||||||
s->port.callback(s->USARTx->RDR);
|
s->port.rxCallback(s->USARTx->RDR);
|
||||||
} else {
|
} else {
|
||||||
s->port.rxBuffer[s->port.rxBufferHead++] = s->USARTx->RDR;
|
s->port.rxBuffer[s->port.rxBufferHead++] = s->USARTx->RDR;
|
||||||
if (s->port.rxBufferHead >= s->port.rxBufferSize) {
|
if (s->port.rxBufferHead >= s->port.rxBufferSize) {
|
||||||
|
|
|
@ -237,8 +237,8 @@ static uartDevice_t* uartHardwareMap[] = {
|
||||||
void uartIrqHandler(uartPort_t *s)
|
void uartIrqHandler(uartPort_t *s)
|
||||||
{
|
{
|
||||||
if (!s->rxDMAStream && (USART_GetITStatus(s->USARTx, USART_IT_RXNE) == SET)) {
|
if (!s->rxDMAStream && (USART_GetITStatus(s->USARTx, USART_IT_RXNE) == SET)) {
|
||||||
if (s->port.callback) {
|
if (s->port.rxCallback) {
|
||||||
s->port.callback(s->USARTx->DR);
|
s->port.rxCallback(s->USARTx->DR);
|
||||||
} else {
|
} else {
|
||||||
s->port.rxBuffer[s->port.rxBufferHead] = s->USARTx->DR;
|
s->port.rxBuffer[s->port.rxBufferHead] = s->USARTx->DR;
|
||||||
s->port.rxBufferHead = (s->port.rxBufferHead + 1) % s->port.rxBufferSize;
|
s->port.rxBufferHead = (s->port.rxBufferHead + 1) % s->port.rxBufferSize;
|
||||||
|
|
|
@ -264,13 +264,13 @@ bool doesConfigurationUsePort(serialPortIdentifier_e identifier)
|
||||||
serialPort_t *openSerialPort(
|
serialPort_t *openSerialPort(
|
||||||
serialPortIdentifier_e identifier,
|
serialPortIdentifier_e identifier,
|
||||||
serialPortFunction_e function,
|
serialPortFunction_e function,
|
||||||
serialReceiveCallbackPtr callback,
|
serialReceiveCallbackPtr rxCallback,
|
||||||
uint32_t baudRate,
|
uint32_t baudRate,
|
||||||
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 (!defined(USE_UART1) && !defined(USE_UART2) && !defined(USE_UART3) && !defined(USE_UART4) && !defined(USE_UART5) && !defined(USE_UART6) && !defined(USE_SOFTSERIAL1) && !defined(USE_SOFTSERIAL2))
|
||||||
UNUSED(callback);
|
UNUSED(rxCallback);
|
||||||
UNUSED(baudRate);
|
UNUSED(baudRate);
|
||||||
UNUSED(mode);
|
UNUSED(mode);
|
||||||
UNUSED(options);
|
UNUSED(options);
|
||||||
|
@ -292,43 +292,43 @@ serialPort_t *openSerialPort(
|
||||||
#endif
|
#endif
|
||||||
#ifdef USE_UART1
|
#ifdef USE_UART1
|
||||||
case SERIAL_PORT_USART1:
|
case SERIAL_PORT_USART1:
|
||||||
serialPort = uartOpen(USART1, callback, baudRate, mode, options);
|
serialPort = uartOpen(USART1, rxCallback, baudRate, mode, options);
|
||||||
break;
|
break;
|
||||||
#endif
|
#endif
|
||||||
#ifdef USE_UART2
|
#ifdef USE_UART2
|
||||||
case SERIAL_PORT_USART2:
|
case SERIAL_PORT_USART2:
|
||||||
serialPort = uartOpen(USART2, callback, baudRate, mode, options);
|
serialPort = uartOpen(USART2, rxCallback, baudRate, mode, options);
|
||||||
break;
|
break;
|
||||||
#endif
|
#endif
|
||||||
#ifdef USE_UART3
|
#ifdef USE_UART3
|
||||||
case SERIAL_PORT_USART3:
|
case SERIAL_PORT_USART3:
|
||||||
serialPort = uartOpen(USART3, callback, baudRate, mode, options);
|
serialPort = uartOpen(USART3, rxCallback, baudRate, mode, options);
|
||||||
break;
|
break;
|
||||||
#endif
|
#endif
|
||||||
#ifdef USE_UART4
|
#ifdef USE_UART4
|
||||||
case SERIAL_PORT_USART4:
|
case SERIAL_PORT_USART4:
|
||||||
serialPort = uartOpen(UART4, callback, baudRate, mode, options);
|
serialPort = uartOpen(UART4, rxCallback, baudRate, mode, options);
|
||||||
break;
|
break;
|
||||||
#endif
|
#endif
|
||||||
#ifdef USE_UART5
|
#ifdef USE_UART5
|
||||||
case SERIAL_PORT_USART5:
|
case SERIAL_PORT_USART5:
|
||||||
serialPort = uartOpen(UART5, callback, baudRate, mode, options);
|
serialPort = uartOpen(UART5, rxCallback, baudRate, mode, options);
|
||||||
break;
|
break;
|
||||||
#endif
|
#endif
|
||||||
#ifdef USE_UART6
|
#ifdef USE_UART6
|
||||||
case SERIAL_PORT_USART6:
|
case SERIAL_PORT_USART6:
|
||||||
serialPort = uartOpen(USART6, callback, baudRate, mode, options);
|
serialPort = uartOpen(USART6, 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, callback, baudRate, options);
|
serialPort = openSoftSerial(SOFTSERIAL1, rxCallback, baudRate, options);
|
||||||
serialSetMode(serialPort, mode);
|
serialSetMode(serialPort, mode);
|
||||||
break;
|
break;
|
||||||
#endif
|
#endif
|
||||||
#ifdef USE_SOFTSERIAL2
|
#ifdef USE_SOFTSERIAL2
|
||||||
case SERIAL_PORT_SOFTSERIAL2:
|
case SERIAL_PORT_SOFTSERIAL2:
|
||||||
serialPort = openSoftSerial(SOFTSERIAL2, callback, baudRate, options);
|
serialPort = openSoftSerial(SOFTSERIAL2, rxCallback, baudRate, options);
|
||||||
serialSetMode(serialPort, mode);
|
serialSetMode(serialPort, mode);
|
||||||
break;
|
break;
|
||||||
#endif
|
#endif
|
||||||
|
@ -348,7 +348,8 @@ serialPort_t *openSerialPort(
|
||||||
return serialPort;
|
return serialPort;
|
||||||
}
|
}
|
||||||
|
|
||||||
void closeSerialPort(serialPort_t *serialPort) {
|
void closeSerialPort(serialPort_t *serialPort)
|
||||||
|
{
|
||||||
serialPortUsage_t *serialPortUsage = findSerialPortUsageByPort(serialPort);
|
serialPortUsage_t *serialPortUsage = findSerialPortUsageByPort(serialPort);
|
||||||
if (!serialPortUsage) {
|
if (!serialPortUsage) {
|
||||||
// already closed
|
// already closed
|
||||||
|
@ -357,7 +358,7 @@ void closeSerialPort(serialPort_t *serialPort) {
|
||||||
|
|
||||||
// TODO wait until data has been transmitted.
|
// TODO wait until data has been transmitted.
|
||||||
|
|
||||||
serialPort->callback = NULL;
|
serialPort->rxCallback = NULL;
|
||||||
|
|
||||||
serialPortUsage->function = FUNCTION_NONE;
|
serialPortUsage->function = FUNCTION_NONE;
|
||||||
serialPortUsage->serialPort = NULL;
|
serialPortUsage->serialPort = NULL;
|
||||||
|
|
|
@ -126,7 +126,7 @@ serialPortUsage_t *findSerialPortUsageByIdentifier(serialPortIdentifier_e identi
|
||||||
serialPort_t *openSerialPort(
|
serialPort_t *openSerialPort(
|
||||||
serialPortIdentifier_e identifier,
|
serialPortIdentifier_e identifier,
|
||||||
serialPortFunction_e function,
|
serialPortFunction_e function,
|
||||||
serialReceiveCallbackPtr callback,
|
serialReceiveCallbackPtr rxCallback,
|
||||||
uint32_t baudrate,
|
uint32_t baudrate,
|
||||||
portMode_t mode,
|
portMode_t mode,
|
||||||
portOptions_t options
|
portOptions_t options
|
||||||
|
|
Loading…
Add table
Add a link
Reference in a new issue