FIX: Invalid references when neither DSHOT nor PWM_OUTPUT is defined. (#14135)
[betaflight.git] / src / main / drivers / serial_uart.c
blob4e99137a6e91846aa7445af8bc5a1118f8a1bb5c
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(UART_TX_BUFFER_ATTRIBUTE) || !defined(UART_RX_BUFFER_ATTRIBUTE)
54 #error Undefined UART_{TX,RX}_BUFFER_ATTRIBUTE for this MCU
55 #endif
57 #define UART_BUFFERS(n) \
58 UART_BUFFER(UART_TX_BUFFER_ATTRIBUTE, n, T); \
59 UART_BUFFER(UART_RX_BUFFER_ATTRIBUTE, n, R); struct dummy_s \
60 /**/
62 #ifdef USE_UART0
63 UART_BUFFERS(0);
64 #endif
66 #ifdef USE_UART1
67 UART_BUFFERS(1);
68 #endif
70 #ifdef USE_UART2
71 UART_BUFFERS(2);
72 #endif
74 #ifdef USE_UART3
75 UART_BUFFERS(3);
76 #endif
78 #ifdef USE_UART4
79 UART_BUFFERS(4);
80 #endif
82 #ifdef USE_UART5
83 UART_BUFFERS(5);
84 #endif
86 #ifdef USE_UART6
87 UART_BUFFERS(6);
88 #endif
90 #ifdef USE_UART7
91 UART_BUFFERS(7);
92 #endif
94 #ifdef USE_UART8
95 UART_BUFFERS(8);
96 #endif
98 #ifdef USE_UART9
99 UART_BUFFERS(9);
100 #endif
102 #ifdef USE_UART10
103 UART_BUFFERS(10);
104 #endif
106 #ifdef USE_LPUART1
107 UART_BUFFERS(Lp1); // TODO - maybe some other naming scheme ?
108 #endif
110 #undef UART_BUFFERS
112 // store only devices configured for target (USE_UARTx)
113 // some entries may be unused, for example because of pin configuration
114 // uartDeviceIdx_e is direct index into this table
115 FAST_DATA_ZERO_INIT uartDevice_t uartDevice[UARTDEV_COUNT];
117 // map serialPortIdentifier_e to uartDeviceIdx_e
118 uartDeviceIdx_e uartDeviceIdxFromIdentifier(serialPortIdentifier_e identifier)
120 #ifdef USE_LPUART1
121 if (identifier == SERIAL_PORT_LPUART1) {
122 return UARTDEV_LP1;
124 #endif
126 #if 1 // TODO ...
127 // store +1 in table - unset values default to 0
128 // table is for UART only to save space (LPUART is handled separately)
129 #define _R(id, dev) [id] = (dev) + 1
130 static const uartDeviceIdx_e uartMap[] = {
131 #ifdef USE_UART0
132 _R(SERIAL_PORT_UART0, UARTDEV_0),
133 #endif
134 #ifdef USE_UART1
135 _R(SERIAL_PORT_USART1, UARTDEV_1),
136 #endif
137 #ifdef USE_UART2
138 _R(SERIAL_PORT_USART2, UARTDEV_2),
139 #endif
140 #ifdef USE_UART3
141 _R(SERIAL_PORT_USART3, UARTDEV_3),
142 #endif
143 #ifdef USE_UART4
144 _R(SERIAL_PORT_UART4, UARTDEV_4),
145 #endif
146 #ifdef USE_UART5
147 _R(SERIAL_PORT_UART5, UARTDEV_5),
148 #endif
149 #ifdef USE_UART6
150 _R(SERIAL_PORT_USART6, UARTDEV_6),
151 #endif
152 #ifdef USE_UART7
153 _R(SERIAL_PORT_USART7, UARTDEV_7),
154 #endif
155 #ifdef USE_UART8
156 _R(SERIAL_PORT_USART8, UARTDEV_8),
157 #endif
158 #ifdef USE_UART9
159 _R(SERIAL_PORT_UART9, UARTDEV_9),
160 #endif
161 #ifdef USE_UART10
162 _R(SERIAL_PORT_USART10, UARTDEV_10),
163 #endif
165 #undef _R
166 if (identifier >= 0 && identifier < (int)ARRAYLEN(uartMap)) {
167 // UART case, but given USE_UARTx may not be defined
168 return uartMap[identifier] ? uartMap[identifier] - 1 : UARTDEV_INVALID;
170 #else
172 const int idx = identifier - SERIAL_PORT_UART_FIRST;
173 if (idx >= 0 && idx < SERIAL_UART_MAX) {
174 if (BIT(idx) & SERIAL_UART_MASK) {
175 // return number of enabled UART ports smaller than idx
176 return popcount((BIT(idx) - 1) & SERIAL_UART_MASK);
177 } else {
178 return UARTDEV_INVALID;
182 #endif
183 // neither LPUART nor UART
184 return UARTDEV_INVALID;
187 uartDevice_t *uartDeviceFromIdentifier(serialPortIdentifier_e identifier)
189 const uartDeviceIdx_e deviceIdx = uartDeviceIdxFromIdentifier(identifier);
190 return deviceIdx != UARTDEV_INVALID ? &uartDevice[deviceIdx] : NULL;
193 serialPort_t *uartOpen(serialPortIdentifier_e identifier, serialReceiveCallbackPtr rxCallback, void *rxCallbackData, uint32_t baudRate, portMode_e mode, portOptions_e options)
195 uartDevice_t *uartDevice = uartDeviceFromIdentifier(identifier);
196 if (!uartDevice) {
197 return NULL;
199 // fill identifier early, so initialization code can use it
200 uartDevice->port.port.identifier = identifier;
202 uartPort_t *uartPort = serialUART(uartDevice, baudRate, mode, options);
203 if (!uartPort) {
204 return NULL;
207 // common serial initialisation code should move to serialPort::init()
208 uartPort->port.rxBufferHead = uartPort->port.rxBufferTail = 0;
209 uartPort->port.txBufferHead = uartPort->port.txBufferTail = 0;
210 // callback works for IRQ-based RX ONLY
211 uartPort->port.rxCallback = rxCallback;
212 uartPort->port.rxCallbackData = rxCallbackData;
213 uartPort->port.mode = mode;
214 uartPort->port.baudRate = baudRate;
215 uartPort->port.options = options;
217 uartReconfigure(uartPort);
219 return (serialPort_t *)uartPort;
222 static void uartSetBaudRate(serialPort_t *instance, uint32_t baudRate)
224 uartPort_t *uartPort = (uartPort_t *)instance;
225 uartPort->port.baudRate = baudRate;
226 uartReconfigure(uartPort);
229 static void uartSetMode(serialPort_t *instance, portMode_e mode)
231 uartPort_t *uartPort = (uartPort_t *)instance;
232 uartPort->port.mode = mode;
233 uartReconfigure(uartPort);
236 static uint32_t uartTotalRxBytesWaiting(const serialPort_t *instance)
238 const uartPort_t *uartPort = (const uartPort_t*)instance;
240 #ifdef USE_DMA
241 if (uartPort->rxDMAResource) {
242 // XXX Could be consolidated
243 #ifdef USE_HAL_DRIVER
244 uint32_t rxDMAHead = __HAL_DMA_GET_COUNTER(uartPort->Handle.hdmarx);
245 #else
246 uint32_t rxDMAHead = xDMA_GetCurrDataCounter(uartPort->rxDMAResource);
247 #endif
249 // uartPort->rxDMAPos and rxDMAHead represent distances from the end
250 // of the buffer. They count DOWN as they advance.
251 if (uartPort->rxDMAPos >= rxDMAHead) {
252 return uartPort->rxDMAPos - rxDMAHead;
253 } else {
254 return uartPort->port.rxBufferSize + uartPort->rxDMAPos - rxDMAHead;
257 #endif
259 if (uartPort->port.rxBufferHead >= uartPort->port.rxBufferTail) {
260 return uartPort->port.rxBufferHead - uartPort->port.rxBufferTail;
261 } else {
262 return uartPort->port.rxBufferSize + uartPort->port.rxBufferHead - uartPort->port.rxBufferTail;
266 static uint32_t uartTotalTxBytesFree(const serialPort_t *instance)
268 const uartPort_t *uartPort = (const uartPort_t*)instance;
270 uint32_t bytesUsed;
272 if (uartPort->port.txBufferHead >= uartPort->port.txBufferTail) {
273 bytesUsed = uartPort->port.txBufferHead - uartPort->port.txBufferTail;
274 } else {
275 bytesUsed = uartPort->port.txBufferSize + uartPort->port.txBufferHead - uartPort->port.txBufferTail;
278 #ifdef USE_DMA
279 if (uartPort->txDMAResource) {
281 * When we queue up a DMA request, we advance the Tx buffer tail before the transfer finishes, so we must add
282 * the remaining size of that in-progress transfer here instead:
284 #ifdef USE_HAL_DRIVER
285 bytesUsed += __HAL_DMA_GET_COUNTER(uartPort->Handle.hdmatx);
286 #else
287 bytesUsed += xDMA_GetCurrDataCounter(uartPort->txDMAResource);
288 #endif
291 * If the Tx buffer is being written to very quickly, we might have advanced the head into the buffer
292 * space occupied by the current DMA transfer. In that case the "bytesUsed" total will actually end up larger
293 * than the total Tx buffer size, because we'll end up transmitting the same buffer region twice. (So we'll be
294 * transmitting a garbage mixture of old and new bytes).
296 * Be kind to callers and pretend like our buffer can only ever be 100% full.
298 if (bytesUsed >= uartPort->port.txBufferSize - 1) {
299 return 0;
302 #endif
304 return (uartPort->port.txBufferSize - 1) - bytesUsed;
307 static bool isUartTransmitBufferEmpty(const serialPort_t *instance)
309 const uartPort_t *uartPort = (const uartPort_t *)instance;
310 #ifdef USE_DMA
311 if (uartPort->txDMAResource) {
312 return uartPort->txDMAEmpty;
313 } else
314 #endif
316 return uartPort->port.txBufferTail == uartPort->port.txBufferHead;
320 static uint8_t uartRead(serialPort_t *instance)
322 uint8_t ch;
323 uartPort_t *uartPort = (uartPort_t *)instance;
325 #ifdef USE_DMA
326 if (uartPort->rxDMAResource) {
327 ch = uartPort->port.rxBuffer[uartPort->port.rxBufferSize - uartPort->rxDMAPos];
328 if (--uartPort->rxDMAPos == 0)
329 uartPort->rxDMAPos = uartPort->port.rxBufferSize;
330 } else
331 #endif
333 ch = uartPort->port.rxBuffer[uartPort->port.rxBufferTail];
334 if (uartPort->port.rxBufferTail + 1 >= uartPort->port.rxBufferSize) {
335 uartPort->port.rxBufferTail = 0;
336 } else {
337 uartPort->port.rxBufferTail++;
341 return ch;
344 static void uartWrite(serialPort_t *instance, uint8_t ch)
346 uartPort_t *uartPort = (uartPort_t *)instance;
348 // Check if the TX line is being pulled low by an unpowered peripheral
349 if (uartPort->checkUsartTxOutput && !uartPort->checkUsartTxOutput(uartPort)) {
350 // TX line is being pulled low, so don't transmit
351 return;
354 uartPort->port.txBuffer[uartPort->port.txBufferHead] = ch;
356 if (uartPort->port.txBufferHead + 1 >= uartPort->port.txBufferSize) {
357 uartPort->port.txBufferHead = 0;
358 } else {
359 uartPort->port.txBufferHead++;
362 #ifdef USE_DMA
363 if (uartPort->txDMAResource) {
364 uartTryStartTxDMA(uartPort);
365 } else
366 #endif
368 uartEnableTxInterrupt(uartPort);
372 static void uartBeginWrite(serialPort_t *instance)
374 uartPort_t *uartPort = (uartPort_t *)instance;
376 // Check if the TX line is being pulled low by an unpowered peripheral
377 if (uartPort->checkUsartTxOutput) {
378 uartPort->checkUsartTxOutput(uartPort);
382 static void uartWriteBuf(serialPort_t *instance, const void *data, int count)
384 uartPort_t *uartPort = (uartPort_t *)instance;
385 uartDevice_t *uart = container_of(uartPort, uartDevice_t, port);
386 const uint8_t *bytePtr = (const uint8_t*)data;
388 // Test if checkUsartTxOutput() detected TX line being pulled low by an unpowered peripheral
389 if (uart->txPinState == TX_PIN_MONITOR) {
390 // TX line is being pulled low, so don't transmit
391 return;
394 while (count > 0) {
395 // Calculate the available space to the end of the buffer
396 const int spaceToEnd = uartPort->port.txBufferSize - uartPort->port.txBufferHead;
397 // Determine the amount to copy in this iteration
398 const int chunkSize = MIN(spaceToEnd, count);
399 // Copy the chunk
400 memcpy((void *)&uartPort->port.txBuffer[uartPort->port.txBufferHead], bytePtr, chunkSize);
401 // Advance source pointer
402 bytePtr += chunkSize;
403 // Advance head, wrapping if necessary
404 uartPort->port.txBufferHead = (uartPort->port.txBufferHead + chunkSize) % uartPort->port.txBufferSize;
405 // Decrease remaining count
406 count -= chunkSize;
410 static void uartEndWrite(serialPort_t *instance)
412 uartPort_t *uartPort = (uartPort_t *)instance;
413 uartDevice_t *uart = container_of(uartPort, uartDevice_t, port);
415 // Check if the TX line is being pulled low by an unpowered peripheral
416 if (uart->txPinState == TX_PIN_MONITOR) {
417 // TX line is being pulled low, so don't transmit
418 return;
421 #ifdef USE_DMA
422 if (uartPort->txDMAResource) {
423 uartTryStartTxDMA(uartPort);
424 } else
425 #endif
427 uartEnableTxInterrupt(uartPort);
431 const struct serialPortVTable uartVTable[] = {
433 .serialWrite = uartWrite,
434 .serialTotalRxWaiting = uartTotalRxBytesWaiting,
435 .serialTotalTxFree = uartTotalTxBytesFree,
436 .serialRead = uartRead,
437 .serialSetBaudRate = uartSetBaudRate,
438 .isSerialTransmitBufferEmpty = isUartTransmitBufferEmpty,
439 .setMode = uartSetMode,
440 .setCtrlLineStateCb = NULL,
441 .setBaudRateCb = NULL,
442 .writeBuf = uartWriteBuf,
443 .beginWrite = uartBeginWrite,
444 .endWrite = uartEndWrite,
448 #define UART_IRQHandler(type, number, dev) \
449 FAST_IRQ_HANDLER void type ## number ## _IRQHandler(void) \
451 uartPort_t *uartPort = &(uartDevice[(dev)].port); \
452 uartIrqHandler(uartPort); \
454 /**/
456 #ifdef USE_UART1
457 UART_IRQHandler(USART, 1, UARTDEV_1) // USART1 Rx/Tx IRQ Handler
458 #endif
460 #ifdef USE_UART2
461 UART_IRQHandler(USART, 2, UARTDEV_2) // USART2 Rx/Tx IRQ Handler
462 #endif
464 #ifdef USE_UART3
465 UART_IRQHandler(USART, 3, UARTDEV_3) // USART3 Rx/Tx IRQ Handler
466 #endif
468 #ifdef USE_UART4
469 UART_IRQHandler(UART, 4, UARTDEV_4) // UART4 Rx/Tx IRQ Handler
470 #endif
472 #ifdef USE_UART5
473 UART_IRQHandler(UART, 5, UARTDEV_5) // UART5 Rx/Tx IRQ Handler
474 #endif
476 #ifdef USE_UART6
477 UART_IRQHandler(USART, 6, UARTDEV_6) // USART6 Rx/Tx IRQ Handler
478 #endif
480 #ifdef USE_UART7
481 UART_IRQHandler(UART, 7, UARTDEV_7) // UART7 Rx/Tx IRQ Handler
482 #endif
484 #ifdef USE_UART8
485 UART_IRQHandler(UART, 8, UARTDEV_8) // UART8 Rx/Tx IRQ Handler
486 #endif
488 #ifdef USE_UART9
489 UART_IRQHandler(UART, 9, UARTDEV_9) // UART9 Rx/Tx IRQ Handler
490 #endif
492 #ifdef USE_UART10
493 UART_IRQHandler(UART, 10, UARTDEV_10) // UART10 Rx/Tx IRQ Handler
494 #endif
496 #ifdef USE_LPUART1
497 UART_IRQHandler(LPUART, 1, UARTDEV_LP1) // LPUART1 Rx/Tx IRQ Handler
498 #endif
500 #endif // USE_UART