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)
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/>.
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
35 #include "build/build_config.h"
37 #include "common/utils.h"
39 #include "drivers/dma.h"
40 #include "drivers/dma_reqmap.h"
41 #include "drivers/rcc.h"
42 #include "drivers/serial.h"
43 #include "drivers/serial_uart.h"
44 #include "drivers/serial_uart_impl.h"
46 #include "pg/serial_uart.h"
49 #define UART_TX_BUFFER_ATTRIBUTE DMA_RAM // D2 SRAM
50 #define UART_RX_BUFFER_ATTRIBUTE DMA_RAM // D2 SRAM
51 #elif defined(STM32G4)
52 #define UART_TX_BUFFER_ATTRIBUTE DMA_RAM_W // SRAM MPU NOT_BUFFERABLE
53 #define UART_RX_BUFFER_ATTRIBUTE DMA_RAM_R // SRAM MPU NOT CACHABLE
54 #elif defined(STM32F7)
55 #define UART_TX_BUFFER_ATTRIBUTE FAST_DATA_ZERO_INIT // DTCM RAM
56 #define UART_RX_BUFFER_ATTRIBUTE FAST_DATA_ZERO_INIT // DTCM RAM
57 #elif defined(STM32F4) || defined(STM32F3) || defined(STM32F1)
58 #define UART_TX_BUFFER_ATTRIBUTE // NONE
59 #define UART_RX_BUFFER_ATTRIBUTE // NONE
61 #error Undefined UART_{TX,RX}_BUFFER_ATTRIBUTE for this MCU
64 #define UART_BUFFERS(n) \
65 UART_BUFFER(UART_TX_BUFFER_ATTRIBUTE, n, T); \
66 UART_BUFFER(UART_RX_BUFFER_ATTRIBUTE, n, R); struct dummy_s
68 #define LPUART_BUFFERS(n) \
69 LPUART_BUFFER(UART_TX_BUFFER_ATTRIBUTE, n, T); \
70 LPUART_BUFFER(UART_RX_BUFFER_ATTRIBUTE, n, R); struct dummy_s
118 serialPort_t
*uartOpen(UARTDevice_e device
, serialReceiveCallbackPtr rxCallback
, void *rxCallbackData
, uint32_t baudRate
, portMode_e mode
, portOptions_e options
)
120 uartPort_t
*uartPort
= serialUART(device
, baudRate
, mode
, options
);
123 return (serialPort_t
*)uartPort
;
126 uartPort
->txDMAEmpty
= true;
129 // common serial initialisation code should move to serialPort::init()
130 uartPort
->port
.rxBufferHead
= uartPort
->port
.rxBufferTail
= 0;
131 uartPort
->port
.txBufferHead
= uartPort
->port
.txBufferTail
= 0;
132 // callback works for IRQ-based RX ONLY
133 uartPort
->port
.rxCallback
= rxCallback
;
134 uartPort
->port
.rxCallbackData
= rxCallbackData
;
135 uartPort
->port
.mode
= mode
;
136 uartPort
->port
.baudRate
= baudRate
;
137 uartPort
->port
.options
= options
;
139 uartReconfigure(uartPort
);
141 return (serialPort_t
*)uartPort
;
144 static void uartSetBaudRate(serialPort_t
*instance
, uint32_t baudRate
)
146 uartPort_t
*uartPort
= (uartPort_t
*)instance
;
147 uartPort
->port
.baudRate
= baudRate
;
148 uartReconfigure(uartPort
);
151 static void uartSetMode(serialPort_t
*instance
, portMode_e mode
)
153 uartPort_t
*uartPort
= (uartPort_t
*)instance
;
154 uartPort
->port
.mode
= mode
;
155 uartReconfigure(uartPort
);
158 static uint32_t uartTotalRxBytesWaiting(const serialPort_t
*instance
)
160 const uartPort_t
*uartPort
= (const uartPort_t
*)instance
;
163 if (uartPort
->rxDMAResource
) {
164 // XXX Could be consolidated
165 #ifdef USE_HAL_DRIVER
166 uint32_t rxDMAHead
= __HAL_DMA_GET_COUNTER(uartPort
->Handle
.hdmarx
);
168 uint32_t rxDMAHead
= xDMA_GetCurrDataCounter(uartPort
->rxDMAResource
);
171 // uartPort->rxDMAPos and rxDMAHead represent distances from the end
172 // of the buffer. They count DOWN as they advance.
173 if (uartPort
->rxDMAPos
>= rxDMAHead
) {
174 return uartPort
->rxDMAPos
- rxDMAHead
;
176 return uartPort
->port
.rxBufferSize
+ uartPort
->rxDMAPos
- rxDMAHead
;
181 if (uartPort
->port
.rxBufferHead
>= uartPort
->port
.rxBufferTail
) {
182 return uartPort
->port
.rxBufferHead
- uartPort
->port
.rxBufferTail
;
184 return uartPort
->port
.rxBufferSize
+ uartPort
->port
.rxBufferHead
- uartPort
->port
.rxBufferTail
;
188 static uint32_t uartTotalTxBytesFree(const serialPort_t
*instance
)
190 const uartPort_t
*uartPort
= (const uartPort_t
*)instance
;
194 if (uartPort
->port
.txBufferHead
>= uartPort
->port
.txBufferTail
) {
195 bytesUsed
= uartPort
->port
.txBufferHead
- uartPort
->port
.txBufferTail
;
197 bytesUsed
= uartPort
->port
.txBufferSize
+ uartPort
->port
.txBufferHead
- uartPort
->port
.txBufferTail
;
201 if (uartPort
->txDMAResource
) {
203 * When we queue up a DMA request, we advance the Tx buffer tail before the transfer finishes, so we must add
204 * the remaining size of that in-progress transfer here instead:
206 #ifdef USE_HAL_DRIVER
207 bytesUsed
+= __HAL_DMA_GET_COUNTER(uartPort
->Handle
.hdmatx
);
209 bytesUsed
+= xDMA_GetCurrDataCounter(uartPort
->txDMAResource
);
213 * If the Tx buffer is being written to very quickly, we might have advanced the head into the buffer
214 * space occupied by the current DMA transfer. In that case the "bytesUsed" total will actually end up larger
215 * than the total Tx buffer size, because we'll end up transmitting the same buffer region twice. (So we'll be
216 * transmitting a garbage mixture of old and new bytes).
218 * Be kind to callers and pretend like our buffer can only ever be 100% full.
220 if (bytesUsed
>= uartPort
->port
.txBufferSize
- 1) {
226 return (uartPort
->port
.txBufferSize
- 1) - bytesUsed
;
229 static bool isUartTransmitBufferEmpty(const serialPort_t
*instance
)
231 const uartPort_t
*uartPort
= (const uartPort_t
*)instance
;
233 if (uartPort
->txDMAResource
) {
234 return uartPort
->txDMAEmpty
;
238 return uartPort
->port
.txBufferTail
== uartPort
->port
.txBufferHead
;
242 static uint8_t uartRead(serialPort_t
*instance
)
245 uartPort_t
*uartPort
= (uartPort_t
*)instance
;
248 if (uartPort
->rxDMAResource
) {
249 ch
= uartPort
->port
.rxBuffer
[uartPort
->port
.rxBufferSize
- uartPort
->rxDMAPos
];
250 if (--uartPort
->rxDMAPos
== 0)
251 uartPort
->rxDMAPos
= uartPort
->port
.rxBufferSize
;
255 ch
= uartPort
->port
.rxBuffer
[uartPort
->port
.rxBufferTail
];
256 if (uartPort
->port
.rxBufferTail
+ 1 >= uartPort
->port
.rxBufferSize
) {
257 uartPort
->port
.rxBufferTail
= 0;
259 uartPort
->port
.rxBufferTail
++;
266 static void uartWrite(serialPort_t
*instance
, uint8_t ch
)
268 uartPort_t
*uartPort
= (uartPort_t
*)instance
;
270 uartPort
->port
.txBuffer
[uartPort
->port
.txBufferHead
] = ch
;
272 if (uartPort
->port
.txBufferHead
+ 1 >= uartPort
->port
.txBufferSize
) {
273 uartPort
->port
.txBufferHead
= 0;
275 uartPort
->port
.txBufferHead
++;
279 if (uartPort
->txDMAResource
) {
280 uartTryStartTxDMA(uartPort
);
284 #ifdef USE_HAL_DRIVER
285 __HAL_UART_ENABLE_IT(&uartPort
->Handle
, UART_IT_TXE
);
287 USART_ITConfig(uartPort
->USARTx
, USART_IT_TXE
, ENABLE
);
292 const struct serialPortVTable uartVTable
[] = {
294 .serialWrite
= uartWrite
,
295 .serialTotalRxWaiting
= uartTotalRxBytesWaiting
,
296 .serialTotalTxFree
= uartTotalTxBytesFree
,
297 .serialRead
= uartRead
,
298 .serialSetBaudRate
= uartSetBaudRate
,
299 .isSerialTransmitBufferEmpty
= isUartTransmitBufferEmpty
,
300 .setMode
= uartSetMode
,
301 .setCtrlLineStateCb
= NULL
,
302 .setBaudRateCb
= NULL
,
310 void uartConfigureDma(uartDevice_t
*uartdev
)
312 uartPort_t
*uartPort
= &(uartdev
->port
);
313 const uartHardware_t
*hardware
= uartdev
->hardware
;
316 UARTDevice_e device
= hardware
->device
;
317 const dmaChannelSpec_t
*dmaChannelSpec
;
319 if (serialUartConfig(device
)->txDmaopt
!= DMA_OPT_UNUSED
) {
320 dmaChannelSpec
= dmaGetChannelSpecByPeripheral(DMA_PERIPH_UART_TX
, device
, serialUartConfig(device
)->txDmaopt
);
321 if (dmaChannelSpec
) {
322 uartPort
->txDMAResource
= dmaChannelSpec
->ref
;
323 uartPort
->txDMAChannel
= dmaChannelSpec
->channel
;
327 if (serialUartConfig(device
)->rxDmaopt
!= DMA_OPT_UNUSED
) {
328 dmaChannelSpec
= dmaGetChannelSpecByPeripheral(DMA_PERIPH_UART_RX
, device
, serialUartConfig(device
)->txDmaopt
);
329 if (dmaChannelSpec
) {
330 uartPort
->rxDMAResource
= dmaChannelSpec
->ref
;
331 uartPort
->rxDMAChannel
= dmaChannelSpec
->channel
;
335 // Non USE_DMA_SPEC does not support configurable ON/OFF of UART DMA
337 if (hardware
->rxDMAResource
) {
338 uartPort
->rxDMAResource
= hardware
->rxDMAResource
;
339 uartPort
->rxDMAChannel
= hardware
->rxDMAChannel
;
342 if (hardware
->txDMAResource
) {
343 uartPort
->txDMAResource
= hardware
->txDMAResource
;
344 uartPort
->txDMAChannel
= hardware
->txDMAChannel
;
348 if (uartPort
->txDMAResource
) {
349 dmaIdentifier_e identifier
= dmaGetIdentifier(uartPort
->txDMAResource
);
350 if (dmaAllocate(identifier
, OWNER_SERIAL_TX
, RESOURCE_INDEX(hardware
->device
))) {
351 dmaEnable(identifier
);
352 dmaSetHandler(identifier
, uartDmaIrqHandler
, hardware
->txPriority
, (uint32_t)uartdev
);
353 uartPort
->txDMAPeripheralBaseAddr
= (uint32_t)&UART_REG_TXD(hardware
->reg
);
357 if (uartPort
->rxDMAResource
) {
358 dmaIdentifier_e identifier
= dmaGetIdentifier(uartPort
->rxDMAResource
);
359 if (dmaAllocate(identifier
, OWNER_SERIAL_RX
, RESOURCE_INDEX(hardware
->device
))) {
360 dmaEnable(identifier
);
361 uartPort
->rxDMAPeripheralBaseAddr
= (uint32_t)&UART_REG_RXD(hardware
->reg
);
367 #define UART_IRQHandler(type, number, dev) \
368 FAST_IRQ_HANDLER void type ## number ## _IRQHandler(void) \
370 uartPort_t *uartPort = &(uartDevmap[UARTDEV_ ## dev]->port); \
371 uartIrqHandler(uartPort); \
375 UART_IRQHandler(USART
, 1, 1) // USART1 Rx/Tx IRQ Handler
379 UART_IRQHandler(USART
, 2, 2) // USART2 Rx/Tx IRQ Handler
383 UART_IRQHandler(USART
, 3, 3) // USART3 Rx/Tx IRQ Handler
387 UART_IRQHandler(UART
, 4, 4) // UART4 Rx/Tx IRQ Handler
391 UART_IRQHandler(UART
, 5, 5) // UART5 Rx/Tx IRQ Handler
395 UART_IRQHandler(USART
, 6, 6) // USART6 Rx/Tx IRQ Handler
399 UART_IRQHandler(UART
, 7, 7) // UART7 Rx/Tx IRQ Handler
403 UART_IRQHandler(UART
, 8, 8) // UART8 Rx/Tx IRQ Handler
407 UART_IRQHandler(LPUART
, 1, 9) // UART9 (implemented with LPUART1) Rx/Tx IRQ Handler