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
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
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 \
107 UART_BUFFERS(Lp1
); // TODO - maybe some other naming scheme ?
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
)
121 if (identifier
== SERIAL_PORT_LPUART1
) {
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
[] = {
132 _R(SERIAL_PORT_UART0
, UARTDEV_0
),
135 _R(SERIAL_PORT_USART1
, UARTDEV_1
),
138 _R(SERIAL_PORT_USART2
, UARTDEV_2
),
141 _R(SERIAL_PORT_USART3
, UARTDEV_3
),
144 _R(SERIAL_PORT_UART4
, UARTDEV_4
),
147 _R(SERIAL_PORT_UART5
, UARTDEV_5
),
150 _R(SERIAL_PORT_USART6
, UARTDEV_6
),
153 _R(SERIAL_PORT_USART7
, UARTDEV_7
),
156 _R(SERIAL_PORT_USART8
, UARTDEV_8
),
159 _R(SERIAL_PORT_UART9
, UARTDEV_9
),
162 _R(SERIAL_PORT_USART10
, UARTDEV_10
),
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
;
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
);
178 return UARTDEV_INVALID
;
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
);
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
);
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
;
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
);
246 uint32_t rxDMAHead
= xDMA_GetCurrDataCounter(uartPort
->rxDMAResource
);
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
;
254 return uartPort
->port
.rxBufferSize
+ uartPort
->rxDMAPos
- rxDMAHead
;
259 if (uartPort
->port
.rxBufferHead
>= uartPort
->port
.rxBufferTail
) {
260 return uartPort
->port
.rxBufferHead
- uartPort
->port
.rxBufferTail
;
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
;
272 if (uartPort
->port
.txBufferHead
>= uartPort
->port
.txBufferTail
) {
273 bytesUsed
= uartPort
->port
.txBufferHead
- uartPort
->port
.txBufferTail
;
275 bytesUsed
= uartPort
->port
.txBufferSize
+ uartPort
->port
.txBufferHead
- uartPort
->port
.txBufferTail
;
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
);
287 bytesUsed
+= xDMA_GetCurrDataCounter(uartPort
->txDMAResource
);
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) {
304 return (uartPort
->port
.txBufferSize
- 1) - bytesUsed
;
307 static bool isUartTransmitBufferEmpty(const serialPort_t
*instance
)
309 const uartPort_t
*uartPort
= (const uartPort_t
*)instance
;
311 if (uartPort
->txDMAResource
) {
312 return uartPort
->txDMAEmpty
;
316 return uartPort
->port
.txBufferTail
== uartPort
->port
.txBufferHead
;
320 static uint8_t uartRead(serialPort_t
*instance
)
323 uartPort_t
*uartPort
= (uartPort_t
*)instance
;
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
;
333 ch
= uartPort
->port
.rxBuffer
[uartPort
->port
.rxBufferTail
];
334 if (uartPort
->port
.rxBufferTail
+ 1 >= uartPort
->port
.rxBufferSize
) {
335 uartPort
->port
.rxBufferTail
= 0;
337 uartPort
->port
.rxBufferTail
++;
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
354 uartPort
->port
.txBuffer
[uartPort
->port
.txBufferHead
] = ch
;
356 if (uartPort
->port
.txBufferHead
+ 1 >= uartPort
->port
.txBufferSize
) {
357 uartPort
->port
.txBufferHead
= 0;
359 uartPort
->port
.txBufferHead
++;
363 if (uartPort
->txDMAResource
) {
364 uartTryStartTxDMA(uartPort
);
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
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
);
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
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
422 if (uartPort
->txDMAResource
) {
423 uartTryStartTxDMA(uartPort
);
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); \
457 UART_IRQHandler(USART
, 1, UARTDEV_1
) // USART1 Rx/Tx IRQ Handler
461 UART_IRQHandler(USART
, 2, UARTDEV_2
) // USART2 Rx/Tx IRQ Handler
465 UART_IRQHandler(USART
, 3, UARTDEV_3
) // USART3 Rx/Tx IRQ Handler
469 UART_IRQHandler(UART
, 4, UARTDEV_4
) // UART4 Rx/Tx IRQ Handler
473 UART_IRQHandler(UART
, 5, UARTDEV_5
) // UART5 Rx/Tx IRQ Handler
477 UART_IRQHandler(USART
, 6, UARTDEV_6
) // USART6 Rx/Tx IRQ Handler
481 UART_IRQHandler(UART
, 7, UARTDEV_7
) // UART7 Rx/Tx IRQ Handler
485 UART_IRQHandler(UART
, 8, UARTDEV_8
) // UART8 Rx/Tx IRQ Handler
489 UART_IRQHandler(UART
, 9, UARTDEV_9
) // UART9 Rx/Tx IRQ Handler
493 UART_IRQHandler(UART
, 10, UARTDEV_10
) // UART10 Rx/Tx IRQ Handler
497 UART_IRQHandler(LPUART
, 1, UARTDEV_LP1
) // LPUART1 Rx/Tx IRQ Handler