Adding support for UART0 (#14094)
[betaflight.git] / src / main / drivers / serial_uart.c
blobd4c530d8894136b907edff1c2028893d11e62e9a
1 /*
2 * This file is part of Cleanflight and Betaflight.
4 * Cleanflight and Betaflight are free software. You can redistribute
5 * this software and/or modify this software under the terms of the
6 * GNU General Public License as published by the Free Software
7 * Foundation, either version 3 of the License, or (at your option)
8 * any later version.
10 * Cleanflight and Betaflight are distributed in the hope that they
11 * will be useful, but WITHOUT ANY WARRANTY; without even the implied
12 * warranty of MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.
13 * See the GNU General Public License for more details.
15 * You should have received a copy of the GNU General Public License
16 * along with this software.
18 * If not, see <http://www.gnu.org/licenses/>.
22 * Authors:
23 * jflyper - Refactoring, cleanup and made pin-configurable
24 * Dominic Clifton - Serial port abstraction, Separation of common STM32 code for cleanflight, various cleanups.
25 * Hamasaki/Timecop - Initial baseflight code
28 #include <stdbool.h>
29 #include <stdint.h>
30 #include <string.h>
32 #include "platform.h"
34 #ifdef USE_UART
36 #include "build/build_config.h"
38 #include <common/maths.h>
39 #include "common/utils.h"
41 #include "io/serial.h"
43 #include "drivers/dma.h"
44 #include "drivers/dma_reqmap.h"
45 #include "drivers/rcc.h"
46 #include "drivers/serial.h"
47 #include "drivers/serial_impl.h"
48 #include "drivers/serial_uart.h"
49 #include "drivers/serial_uart_impl.h"
51 #include "pg/serial_uart.h"
53 #if defined(STM32H7)
54 #define UART_TX_BUFFER_ATTRIBUTE DMA_RAM // D2 SRAM
55 #define UART_RX_BUFFER_ATTRIBUTE DMA_RAM // D2 SRAM
56 #elif defined(STM32G4)
57 #define UART_TX_BUFFER_ATTRIBUTE DMA_RAM_W // SRAM MPU NOT_BUFFERABLE
58 #define UART_RX_BUFFER_ATTRIBUTE DMA_RAM_R // SRAM MPU NOT CACHABLE
59 #elif defined(STM32F7)
60 #define UART_TX_BUFFER_ATTRIBUTE FAST_DATA_ZERO_INIT // DTCM RAM
61 #define UART_RX_BUFFER_ATTRIBUTE FAST_DATA_ZERO_INIT // DTCM RAM
62 #elif defined(STM32F4) || defined(AT32F4) || defined(APM32F4)
63 #define UART_TX_BUFFER_ATTRIBUTE // NONE
64 #define UART_RX_BUFFER_ATTRIBUTE // NONE
65 #else
66 #error Undefined UART_{TX,RX}_BUFFER_ATTRIBUTE for this MCU
67 #endif
69 #define UART_BUFFERS(n) \
70 UART_BUFFER(UART_TX_BUFFER_ATTRIBUTE, n, T); \
71 UART_BUFFER(UART_RX_BUFFER_ATTRIBUTE, n, R); struct dummy_s \
72 /**/
74 #ifdef USE_UART0
75 UART_BUFFERS(0);
76 #endif
78 #ifdef USE_UART1
79 UART_BUFFERS(1);
80 #endif
82 #ifdef USE_UART2
83 UART_BUFFERS(2);
84 #endif
86 #ifdef USE_UART3
87 UART_BUFFERS(3);
88 #endif
90 #ifdef USE_UART4
91 UART_BUFFERS(4);
92 #endif
94 #ifdef USE_UART5
95 UART_BUFFERS(5);
96 #endif
98 #ifdef USE_UART6
99 UART_BUFFERS(6);
100 #endif
102 #ifdef USE_UART7
103 UART_BUFFERS(7);
104 #endif
106 #ifdef USE_UART8
107 UART_BUFFERS(8);
108 #endif
110 #ifdef USE_UART9
111 UART_BUFFERS(9);
112 #endif
114 #ifdef USE_UART10
115 UART_BUFFERS(10);
116 #endif
118 #ifdef USE_LPUART1
119 UART_BUFFERS(Lp1); // TODO - maybe some other naming scheme ?
120 #endif
122 #undef UART_BUFFERS
124 // store only devices configured for target (USE_UARTx)
125 // some entries may be unused, for example because of pin configuration
126 // uartDeviceIdx_e is direct index into this table
127 FAST_DATA_ZERO_INIT uartDevice_t uartDevice[UARTDEV_COUNT];
129 // map serialPortIdentifier_e to uartDeviceIdx_e
130 uartDeviceIdx_e uartDeviceIdxFromIdentifier(serialPortIdentifier_e identifier)
132 #ifdef USE_LPUART1
133 if (identifier == SERIAL_PORT_LPUART1) {
134 return UARTDEV_LP1;
136 #endif
138 #if 1 // TODO ...
139 // store +1 in table - unset values default to 0
140 // table is for UART only to save space (LPUART is handled separately)
141 #define _R(id, dev) [id] = (dev) + 1
142 static const uartDeviceIdx_e uartMap[] = {
143 #ifdef USE_UART0
144 _R(SERIAL_PORT_UART0, UARTDEV_0),
145 #endif
146 #ifdef USE_UART1
147 _R(SERIAL_PORT_USART1, UARTDEV_1),
148 #endif
149 #ifdef USE_UART2
150 _R(SERIAL_PORT_USART2, UARTDEV_2),
151 #endif
152 #ifdef USE_UART3
153 _R(SERIAL_PORT_USART3, UARTDEV_3),
154 #endif
155 #ifdef USE_UART4
156 _R(SERIAL_PORT_UART4, UARTDEV_4),
157 #endif
158 #ifdef USE_UART5
159 _R(SERIAL_PORT_UART5, UARTDEV_5),
160 #endif
161 #ifdef USE_UART6
162 _R(SERIAL_PORT_USART6, UARTDEV_6),
163 #endif
164 #ifdef USE_UART7
165 _R(SERIAL_PORT_USART7, UARTDEV_7),
166 #endif
167 #ifdef USE_UART8
168 _R(SERIAL_PORT_USART8, UARTDEV_8),
169 #endif
170 #ifdef USE_UART9
171 _R(SERIAL_PORT_UART9, UARTDEV_9),
172 #endif
173 #ifdef USE_UART10
174 _R(SERIAL_PORT_USART10, UARTDEV_10),
175 #endif
177 #undef _R
178 if (identifier >= 0 && identifier < (int)ARRAYLEN(uartMap)) {
179 // UART case, but given USE_UARTx may not be defined
180 return uartMap[identifier] ? uartMap[identifier] - 1 : UARTDEV_INVALID;
182 #else
184 const int idx = identifier - SERIAL_PORT_UART_FIRST;
185 if (idx >= 0 && idx < SERIAL_UART_MAX) {
186 if (BIT(idx) & SERIAL_UART_MASK) {
187 // return number of enabled UART ports smaller than idx
188 return popcount((BIT(idx) - 1) & SERIAL_UART_MASK);
189 } else {
190 return UARTDEV_INVALID;
194 #endif
195 // neither LPUART nor UART
196 return UARTDEV_INVALID;
199 uartDevice_t *uartDeviceFromIdentifier(serialPortIdentifier_e identifier)
201 const uartDeviceIdx_e deviceIdx = uartDeviceIdxFromIdentifier(identifier);
202 return deviceIdx != UARTDEV_INVALID ? &uartDevice[deviceIdx] : NULL;
205 serialPort_t *uartOpen(serialPortIdentifier_e identifier, serialReceiveCallbackPtr rxCallback, void *rxCallbackData, uint32_t baudRate, portMode_e mode, portOptions_e options)
207 uartDevice_t *uartDevice = uartDeviceFromIdentifier(identifier);
208 if (!uartDevice) {
209 return NULL;
211 // fill identifier early, so initialization code can use it
212 uartDevice->port.port.identifier = identifier;
214 uartPort_t *uartPort = serialUART(uartDevice, baudRate, mode, options);
215 if (!uartPort) {
216 return NULL;
219 // common serial initialisation code should move to serialPort::init()
220 uartPort->port.rxBufferHead = uartPort->port.rxBufferTail = 0;
221 uartPort->port.txBufferHead = uartPort->port.txBufferTail = 0;
222 // callback works for IRQ-based RX ONLY
223 uartPort->port.rxCallback = rxCallback;
224 uartPort->port.rxCallbackData = rxCallbackData;
225 uartPort->port.mode = mode;
226 uartPort->port.baudRate = baudRate;
227 uartPort->port.options = options;
229 uartReconfigure(uartPort);
231 return (serialPort_t *)uartPort;
234 static void uartSetBaudRate(serialPort_t *instance, uint32_t baudRate)
236 uartPort_t *uartPort = (uartPort_t *)instance;
237 uartPort->port.baudRate = baudRate;
238 uartReconfigure(uartPort);
241 static void uartSetMode(serialPort_t *instance, portMode_e mode)
243 uartPort_t *uartPort = (uartPort_t *)instance;
244 uartPort->port.mode = mode;
245 uartReconfigure(uartPort);
248 static uint32_t uartTotalRxBytesWaiting(const serialPort_t *instance)
250 const uartPort_t *uartPort = (const uartPort_t*)instance;
252 #ifdef USE_DMA
253 if (uartPort->rxDMAResource) {
254 // XXX Could be consolidated
255 #ifdef USE_HAL_DRIVER
256 uint32_t rxDMAHead = __HAL_DMA_GET_COUNTER(uartPort->Handle.hdmarx);
257 #else
258 uint32_t rxDMAHead = xDMA_GetCurrDataCounter(uartPort->rxDMAResource);
259 #endif
261 // uartPort->rxDMAPos and rxDMAHead represent distances from the end
262 // of the buffer. They count DOWN as they advance.
263 if (uartPort->rxDMAPos >= rxDMAHead) {
264 return uartPort->rxDMAPos - rxDMAHead;
265 } else {
266 return uartPort->port.rxBufferSize + uartPort->rxDMAPos - rxDMAHead;
269 #endif
271 if (uartPort->port.rxBufferHead >= uartPort->port.rxBufferTail) {
272 return uartPort->port.rxBufferHead - uartPort->port.rxBufferTail;
273 } else {
274 return uartPort->port.rxBufferSize + uartPort->port.rxBufferHead - uartPort->port.rxBufferTail;
278 static uint32_t uartTotalTxBytesFree(const serialPort_t *instance)
280 const uartPort_t *uartPort = (const uartPort_t*)instance;
282 uint32_t bytesUsed;
284 if (uartPort->port.txBufferHead >= uartPort->port.txBufferTail) {
285 bytesUsed = uartPort->port.txBufferHead - uartPort->port.txBufferTail;
286 } else {
287 bytesUsed = uartPort->port.txBufferSize + uartPort->port.txBufferHead - uartPort->port.txBufferTail;
290 #ifdef USE_DMA
291 if (uartPort->txDMAResource) {
293 * When we queue up a DMA request, we advance the Tx buffer tail before the transfer finishes, so we must add
294 * the remaining size of that in-progress transfer here instead:
296 #ifdef USE_HAL_DRIVER
297 bytesUsed += __HAL_DMA_GET_COUNTER(uartPort->Handle.hdmatx);
298 #else
299 bytesUsed += xDMA_GetCurrDataCounter(uartPort->txDMAResource);
300 #endif
303 * If the Tx buffer is being written to very quickly, we might have advanced the head into the buffer
304 * space occupied by the current DMA transfer. In that case the "bytesUsed" total will actually end up larger
305 * than the total Tx buffer size, because we'll end up transmitting the same buffer region twice. (So we'll be
306 * transmitting a garbage mixture of old and new bytes).
308 * Be kind to callers and pretend like our buffer can only ever be 100% full.
310 if (bytesUsed >= uartPort->port.txBufferSize - 1) {
311 return 0;
314 #endif
316 return (uartPort->port.txBufferSize - 1) - bytesUsed;
319 static bool isUartTransmitBufferEmpty(const serialPort_t *instance)
321 const uartPort_t *uartPort = (const uartPort_t *)instance;
322 #ifdef USE_DMA
323 if (uartPort->txDMAResource) {
324 return uartPort->txDMAEmpty;
325 } else
326 #endif
328 return uartPort->port.txBufferTail == uartPort->port.txBufferHead;
332 static uint8_t uartRead(serialPort_t *instance)
334 uint8_t ch;
335 uartPort_t *uartPort = (uartPort_t *)instance;
337 #ifdef USE_DMA
338 if (uartPort->rxDMAResource) {
339 ch = uartPort->port.rxBuffer[uartPort->port.rxBufferSize - uartPort->rxDMAPos];
340 if (--uartPort->rxDMAPos == 0)
341 uartPort->rxDMAPos = uartPort->port.rxBufferSize;
342 } else
343 #endif
345 ch = uartPort->port.rxBuffer[uartPort->port.rxBufferTail];
346 if (uartPort->port.rxBufferTail + 1 >= uartPort->port.rxBufferSize) {
347 uartPort->port.rxBufferTail = 0;
348 } else {
349 uartPort->port.rxBufferTail++;
353 return ch;
356 static void uartWrite(serialPort_t *instance, uint8_t ch)
358 uartPort_t *uartPort = (uartPort_t *)instance;
360 // Check if the TX line is being pulled low by an unpowered peripheral
361 if (uartPort->checkUsartTxOutput && !uartPort->checkUsartTxOutput(uartPort)) {
362 // TX line is being pulled low, so don't transmit
363 return;
366 uartPort->port.txBuffer[uartPort->port.txBufferHead] = ch;
368 if (uartPort->port.txBufferHead + 1 >= uartPort->port.txBufferSize) {
369 uartPort->port.txBufferHead = 0;
370 } else {
371 uartPort->port.txBufferHead++;
374 #ifdef USE_DMA
375 if (uartPort->txDMAResource) {
376 uartTryStartTxDMA(uartPort);
377 } else
378 #endif
380 #if defined(USE_HAL_DRIVER)
381 __HAL_UART_ENABLE_IT(&uartPort->Handle, UART_IT_TXE);
382 #elif defined(USE_ATBSP_DRIVER)
383 usart_interrupt_enable(uartPort->USARTx, USART_TDBE_INT, TRUE);
384 #else
385 USART_ITConfig(uartPort->USARTx, USART_IT_TXE, ENABLE);
386 #endif
390 static void uartBeginWrite(serialPort_t *instance)
392 uartPort_t *uartPort = (uartPort_t *)instance;
394 // Check if the TX line is being pulled low by an unpowered peripheral
395 if (uartPort->checkUsartTxOutput) {
396 uartPort->checkUsartTxOutput(uartPort);
400 static void uartWriteBuf(serialPort_t *instance, const void *data, int count)
402 uartPort_t *uartPort = (uartPort_t *)instance;
403 uartDevice_t *uart = container_of(uartPort, uartDevice_t, port);
404 const uint8_t *bytePtr = (const uint8_t*)data;
406 // Test if checkUsartTxOutput() detected TX line being pulled low by an unpowered peripheral
407 if (uart->txPinState == TX_PIN_MONITOR) {
408 // TX line is being pulled low, so don't transmit
409 return;
412 while (count > 0) {
413 // Calculate the available space to the end of the buffer
414 const int spaceToEnd = uartPort->port.txBufferSize - uartPort->port.txBufferHead;
415 // Determine the amount to copy in this iteration
416 const int chunkSize = MIN(spaceToEnd, count);
417 // Copy the chunk
418 memcpy((void *)&uartPort->port.txBuffer[uartPort->port.txBufferHead], bytePtr, chunkSize);
419 // Advance source pointer
420 bytePtr += chunkSize;
421 // Advance head, wrapping if necessary
422 uartPort->port.txBufferHead = (uartPort->port.txBufferHead + chunkSize) % uartPort->port.txBufferSize;
423 // Decrease remaining count
424 count -= chunkSize;
428 static void uartEndWrite(serialPort_t *instance)
430 uartPort_t *uartPort = (uartPort_t *)instance;
431 uartDevice_t *uart = container_of(uartPort, uartDevice_t, port);
433 // Check if the TX line is being pulled low by an unpowered peripheral
434 if (uart->txPinState == TX_PIN_MONITOR) {
435 // TX line is being pulled low, so don't transmit
436 return;
439 #ifdef USE_DMA
440 if (uartPort->txDMAResource) {
441 uartTryStartTxDMA(uartPort);
442 } else
443 #endif
445 #if defined(USE_HAL_DRIVER)
446 __HAL_UART_ENABLE_IT(&uartPort->Handle, UART_IT_TXE);
447 #elif defined(USE_ATBSP_DRIVER)
448 usart_interrupt_enable(uartPort->USARTx, USART_TDBE_INT, TRUE);
449 #else
450 USART_ITConfig(uartPort->USARTx, USART_IT_TXE, ENABLE);
451 #endif
455 const struct serialPortVTable uartVTable[] = {
457 .serialWrite = uartWrite,
458 .serialTotalRxWaiting = uartTotalRxBytesWaiting,
459 .serialTotalTxFree = uartTotalTxBytesFree,
460 .serialRead = uartRead,
461 .serialSetBaudRate = uartSetBaudRate,
462 .isSerialTransmitBufferEmpty = isUartTransmitBufferEmpty,
463 .setMode = uartSetMode,
464 .setCtrlLineStateCb = NULL,
465 .setBaudRateCb = NULL,
466 .writeBuf = uartWriteBuf,
467 .beginWrite = uartBeginWrite,
468 .endWrite = uartEndWrite,
472 // TODO - move to serial_uart_hw.c
473 #ifdef USE_DMA
474 void uartConfigureDma(uartDevice_t *uartdev)
476 uartPort_t *uartPort = &(uartdev->port);
477 const uartHardware_t *hardware = uartdev->hardware;
479 #ifdef USE_DMA_SPEC
480 const serialPortIdentifier_e uartPortIdentifier = hardware->identifier;
481 const uartDeviceIdx_e uartDeviceIdx = uartDeviceIdxFromIdentifier(uartPortIdentifier);
482 if (uartDeviceIdx == UARTDEV_INVALID) {
483 return;
485 const int resourceIdx = serialResourceIndex(uartPortIdentifier);
486 const int ownerIndex = serialOwnerIndex(uartPortIdentifier);
487 const resourceOwner_e ownerTxRx = serialOwnerTxRx(uartPortIdentifier); // rx is always +1
489 const dmaChannelSpec_t *dmaChannelSpec;
490 const serialUartConfig_t *cfg = serialUartConfig(resourceIdx);
491 if (!cfg) {
492 return;
494 if (cfg->txDmaopt != DMA_OPT_UNUSED) {
495 dmaChannelSpec = dmaGetChannelSpecByPeripheral(DMA_PERIPH_UART_TX, uartDeviceIdx, cfg->txDmaopt);
496 if (dmaChannelSpec) {
497 uartPort->txDMAResource = dmaChannelSpec->ref;
498 #if defined(STM32F4) || defined(STM32F7) || defined(STM32H7) || defined(STM32G4) || defined(APM32F4)
499 uartPort->txDMAChannel = dmaChannelSpec->channel;
500 #elif defined(AT32F4)
501 uartPort->txDMAMuxId = dmaChannelSpec->dmaMuxId;
502 #endif
506 if (cfg->rxDmaopt != DMA_OPT_UNUSED) {
507 dmaChannelSpec = dmaGetChannelSpecByPeripheral(DMA_PERIPH_UART_RX, uartDeviceIdx, cfg->txDmaopt);
508 if (dmaChannelSpec) {
509 uartPort->rxDMAResource = dmaChannelSpec->ref;
510 #if defined(STM32F4) || defined(STM32F7) || defined(STM32H7) || defined(STM32G4) || defined(APM32F4)
511 uartPort->rxDMAChannel = dmaChannelSpec->channel;
512 #elif defined(AT32F4)
513 uartPort->rxDMAMuxId = dmaChannelSpec->dmaMuxId;
514 #endif
517 #else /* USE_DMA_SPEC */
518 // Non USE_DMA_SPEC does not support configurable ON/OFF of UART DMA
520 if (hardware->rxDMAResource) {
521 uartPort->rxDMAResource = hardware->rxDMAResource;
522 #if defined(STM32F4) || defined(STM32F7) || defined(STM32H7) || defined(STM32G4) || defined(APM32F4)
523 uartPort->rxDMAChannel = hardware->rxDMAChannel;
524 #elif defined(AT32F4)
525 uartPort->rxDMAMuxId = hardware->rxDMAMuxId;
526 #endif
529 if (hardware->txDMAResource) {
530 uartPort->txDMAResource = hardware->txDMAResource;
531 #if defined(STM32F4) || defined(STM32F7) || defined(STM32H7) || defined(STM32G4) || defined(APM32F4)
532 uartPort->txDMAChannel = hardware->txDMAChannel;
533 #elif defined(AT32F4)
534 uartPort->txDMAMuxId = hardware->txDMAMuxId;
535 #endif
537 #endif /* USE_DMA_SPEC */
539 if (uartPort->txDMAResource) {
540 const dmaIdentifier_e identifier = dmaGetIdentifier(uartPort->txDMAResource);
541 if (dmaAllocate(identifier, ownerTxRx, ownerIndex)) {
542 dmaEnable(identifier);
543 #if defined(AT32F4)
544 dmaMuxEnable(identifier, uartPort->txDMAMuxId);
545 #endif
546 dmaSetHandler(identifier, uartDmaIrqHandler, hardware->txPriority, (uint32_t)uartdev);
547 uartPort->txDMAPeripheralBaseAddr = (uint32_t)&UART_REG_TXD(hardware->reg);
551 if (uartPort->rxDMAResource) {
552 const dmaIdentifier_e identifier = dmaGetIdentifier(uartPort->rxDMAResource);
553 if (dmaAllocate(identifier, ownerTxRx + 1, ownerIndex)) {
554 dmaEnable(identifier);
555 #if defined(AT32F4)
556 dmaMuxEnable(identifier, uartPort->rxDMAMuxId);
557 #endif
558 uartPort->rxDMAPeripheralBaseAddr = (uint32_t)&UART_REG_RXD(hardware->reg);
562 #endif
564 #define UART_IRQHandler(type, number, dev) \
565 FAST_IRQ_HANDLER void type ## number ## _IRQHandler(void) \
567 uartPort_t *uartPort = &(uartDevice[(dev)].port); \
568 uartIrqHandler(uartPort); \
570 /**/
572 #ifdef USE_UART1
573 UART_IRQHandler(USART, 1, UARTDEV_1) // USART1 Rx/Tx IRQ Handler
574 #endif
576 #ifdef USE_UART2
577 UART_IRQHandler(USART, 2, UARTDEV_2) // USART2 Rx/Tx IRQ Handler
578 #endif
580 #ifdef USE_UART3
581 UART_IRQHandler(USART, 3, UARTDEV_3) // USART3 Rx/Tx IRQ Handler
582 #endif
584 #ifdef USE_UART4
585 UART_IRQHandler(UART, 4, UARTDEV_4) // UART4 Rx/Tx IRQ Handler
586 #endif
588 #ifdef USE_UART5
589 UART_IRQHandler(UART, 5, UARTDEV_5) // UART5 Rx/Tx IRQ Handler
590 #endif
592 #ifdef USE_UART6
593 UART_IRQHandler(USART, 6, UARTDEV_6) // USART6 Rx/Tx IRQ Handler
594 #endif
596 #ifdef USE_UART7
597 UART_IRQHandler(UART, 7, UARTDEV_7) // UART7 Rx/Tx IRQ Handler
598 #endif
600 #ifdef USE_UART8
601 UART_IRQHandler(UART, 8, UARTDEV_8) // UART8 Rx/Tx IRQ Handler
602 #endif
604 #ifdef USE_UART9
605 UART_IRQHandler(UART, 9, UARTDEV_9) // UART9 Rx/Tx IRQ Handler
606 #endif
608 #ifdef USE_UART10
609 UART_IRQHandler(UART, 10, UARTDEV_10) // UART10 Rx/Tx IRQ Handler
610 #endif
612 #ifdef USE_LPUART1
613 UART_IRQHandler(LPUART, 1, UARTDEV_LP1) // LPUART1 Rx/Tx IRQ Handler
614 #endif
616 #endif // USE_UART