Handle USART TX pulldown (#12929)
[betaflight.git] / src / main / drivers / stm32 / serial_uart_hal.c
blob136ececcb00b10614241063d10e1baff64d2e65d
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
27 #include <stdbool.h>
28 #include <stdint.h>
29 #include <stdlib.h>
31 #include "platform.h"
33 #include "build/debug.h"
35 #ifdef USE_UART
37 #include "build/build_config.h"
38 #include "build/atomic.h"
40 #include "common/utils.h"
41 #include "drivers/io.h"
42 #include "drivers/nvic.h"
43 #include "drivers/inverter.h"
44 #include "drivers/dma.h"
45 #include "drivers/rcc.h"
47 #include "drivers/serial.h"
48 #include "drivers/serial_uart.h"
49 #include "drivers/serial_uart_impl.h"
51 static void usartConfigurePinInversion(uartPort_t *uartPort)
53 bool inverted = uartPort->port.options & SERIAL_INVERTED;
55 if (inverted)
57 if (uartPort->port.mode & MODE_RX)
59 uartPort->Handle.AdvancedInit.AdvFeatureInit |= UART_ADVFEATURE_RXINVERT_INIT;
60 uartPort->Handle.AdvancedInit.RxPinLevelInvert = UART_ADVFEATURE_RXINV_ENABLE;
62 if (uartPort->port.mode & MODE_TX)
64 uartPort->Handle.AdvancedInit.AdvFeatureInit |= UART_ADVFEATURE_TXINVERT_INIT;
65 uartPort->Handle.AdvancedInit.TxPinLevelInvert = UART_ADVFEATURE_TXINV_ENABLE;
70 static uartDevice_t *uartFindDevice(uartPort_t *uartPort)
72 for (uint32_t i = 0; i < UARTDEV_COUNT_MAX; i++) {
73 uartDevice_t *candidate = uartDevmap[i];
75 if (&candidate->port == uartPort) {
76 return candidate;
79 return NULL;
82 #if !(defined(STM32F4))
83 static void uartConfigurePinSwap(uartPort_t *uartPort)
85 uartDevice_t *uartDevice = uartFindDevice(uartPort);
86 if (!uartDevice) {
87 return;
90 if (uartDevice->pinSwap) {
91 uartDevice->port.Handle.AdvancedInit.AdvFeatureInit |= UART_ADVFEATURE_SWAP_INIT;
92 uartDevice->port.Handle.AdvancedInit.Swap = UART_ADVFEATURE_SWAP_ENABLE;
95 #endif
97 // XXX uartReconfigure does not handle resource management properly.
99 void uartReconfigure(uartPort_t *uartPort)
101 HAL_UART_DeInit(&uartPort->Handle);
102 uartPort->Handle.Init.BaudRate = uartPort->port.baudRate;
103 // according to the stm32 documentation wordlen has to be 9 for parity bits
104 // this does not seem to matter for rx but will give bad data on tx!
105 uartPort->Handle.Init.WordLength = (uartPort->port.options & SERIAL_PARITY_EVEN) ? UART_WORDLENGTH_9B : UART_WORDLENGTH_8B;
106 uartPort->Handle.Init.StopBits = (uartPort->port.options & SERIAL_STOPBITS_2) ? USART_STOPBITS_2 : USART_STOPBITS_1;
107 uartPort->Handle.Init.Parity = (uartPort->port.options & SERIAL_PARITY_EVEN) ? USART_PARITY_EVEN : USART_PARITY_NONE;
108 uartPort->Handle.Init.HwFlowCtl = UART_HWCONTROL_NONE;
109 uartPort->Handle.Init.OneBitSampling = UART_ONE_BIT_SAMPLE_DISABLE;
110 uartPort->Handle.Init.Mode = 0;
111 #if defined(STM32G4) || defined(STM32H7)
112 if (uartPort->Handle.Instance == LPUART1) {
113 uartPort->Handle.Init.ClockPrescaler = UART_PRESCALER_DIV8;
115 #endif
117 if (uartPort->port.mode & MODE_RX)
118 uartPort->Handle.Init.Mode |= UART_MODE_RX;
119 if (uartPort->port.mode & MODE_TX)
120 uartPort->Handle.Init.Mode |= UART_MODE_TX;
123 usartConfigurePinInversion(uartPort);
124 #if !(defined(STM32F1) || defined(STM32F4))
125 uartConfigurePinSwap(uartPort);
126 #endif
128 #ifdef TARGET_USART_CONFIG
129 void usartTargetConfigure(uartPort_t *);
130 usartTargetConfigure(uartPort);
131 #endif
133 if (uartPort->port.options & SERIAL_BIDIR)
135 HAL_HalfDuplex_Init(&uartPort->Handle);
137 else
139 HAL_UART_Init(&uartPort->Handle);
142 // Receive DMA or IRQ
143 if (uartPort->port.mode & MODE_RX)
145 #ifdef USE_DMA
146 if (uartPort->rxDMAResource)
148 uartPort->rxDMAHandle.Instance = (DMA_ARCH_TYPE *)uartPort->rxDMAResource;
149 #if !(defined(STM32H7) || defined(STM32G4))
150 uartPort->rxDMAHandle.Init.Channel = uartPort->rxDMAChannel;
151 #else
152 uartPort->txDMAHandle.Init.Request = uartPort->rxDMAChannel;
153 #endif
154 uartPort->rxDMAHandle.Init.Direction = DMA_PERIPH_TO_MEMORY;
155 uartPort->rxDMAHandle.Init.PeriphInc = DMA_PINC_DISABLE;
156 uartPort->rxDMAHandle.Init.MemInc = DMA_MINC_ENABLE;
157 uartPort->rxDMAHandle.Init.PeriphDataAlignment = DMA_PDATAALIGN_BYTE;
158 uartPort->rxDMAHandle.Init.MemDataAlignment = DMA_MDATAALIGN_BYTE;
159 uartPort->rxDMAHandle.Init.Mode = DMA_CIRCULAR;
160 #if defined(STM32F4) || defined(STM32F7) || defined(STM32H7)
161 uartPort->rxDMAHandle.Init.FIFOMode = DMA_FIFOMODE_DISABLE;
162 uartPort->rxDMAHandle.Init.FIFOThreshold = DMA_FIFO_THRESHOLD_1QUARTERFULL;
163 uartPort->rxDMAHandle.Init.PeriphBurst = DMA_PBURST_SINGLE;
164 uartPort->rxDMAHandle.Init.MemBurst = DMA_MBURST_SINGLE;
165 #endif
166 uartPort->rxDMAHandle.Init.Priority = DMA_PRIORITY_MEDIUM;
169 HAL_DMA_DeInit(&uartPort->rxDMAHandle);
170 HAL_DMA_Init(&uartPort->rxDMAHandle);
171 /* Associate the initialized DMA handle to the UART handle */
172 __HAL_LINKDMA(&uartPort->Handle, hdmarx, uartPort->rxDMAHandle);
174 HAL_UART_Receive_DMA(&uartPort->Handle, (uint8_t*)uartPort->port.rxBuffer, uartPort->port.rxBufferSize);
176 uartPort->rxDMAPos = __HAL_DMA_GET_COUNTER(&uartPort->rxDMAHandle);
177 } else
178 #endif
180 /* Enable the UART Parity Error Interrupt */
181 SET_BIT(uartPort->USARTx->CR1, USART_CR1_PEIE);
183 /* Enable the UART Error Interrupt: (Frame error, noise error, overrun error) */
184 SET_BIT(uartPort->USARTx->CR3, USART_CR3_EIE);
186 /* Enable the UART Data Register not empty Interrupt */
187 SET_BIT(uartPort->USARTx->CR1, USART_CR1_RXNEIE);
189 /* Enable Idle Line detection */
190 SET_BIT(uartPort->USARTx->CR1, USART_CR1_IDLEIE);
194 // Transmit DMA or IRQ
195 if (uartPort->port.mode & MODE_TX) {
196 #ifdef USE_DMA
197 if (uartPort->txDMAResource) {
198 uartPort->txDMAHandle.Instance = (DMA_ARCH_TYPE *)uartPort->txDMAResource;
199 #if !(defined(STM32H7) || defined(STM32G4))
200 uartPort->txDMAHandle.Init.Channel = uartPort->txDMAChannel;
201 #else
202 uartPort->txDMAHandle.Init.Request = uartPort->txDMAChannel;
203 #endif
204 uartPort->txDMAHandle.Init.Direction = DMA_MEMORY_TO_PERIPH;
205 uartPort->txDMAHandle.Init.PeriphInc = DMA_PINC_DISABLE;
206 uartPort->txDMAHandle.Init.MemInc = DMA_MINC_ENABLE;
207 uartPort->txDMAHandle.Init.PeriphDataAlignment = DMA_PDATAALIGN_BYTE;
208 uartPort->txDMAHandle.Init.MemDataAlignment = DMA_MDATAALIGN_BYTE;
209 uartPort->txDMAHandle.Init.Mode = DMA_NORMAL;
210 #if !defined(STM32G4)
211 // G4's DMA is channel based, and does not have FIFO
212 uartPort->txDMAHandle.Init.FIFOMode = DMA_FIFOMODE_DISABLE;
213 uartPort->txDMAHandle.Init.FIFOThreshold = DMA_FIFO_THRESHOLD_1QUARTERFULL;
214 uartPort->txDMAHandle.Init.PeriphBurst = DMA_PBURST_SINGLE;
215 uartPort->txDMAHandle.Init.MemBurst = DMA_MBURST_SINGLE;
216 #endif
217 uartPort->txDMAHandle.Init.Priority = DMA_PRIORITY_MEDIUM;
220 HAL_DMA_DeInit(&uartPort->txDMAHandle);
221 HAL_StatusTypeDef status = HAL_DMA_Init(&uartPort->txDMAHandle);
222 if (status != HAL_OK)
224 while (1);
226 /* Associate the initialized DMA handle to the UART handle */
227 __HAL_LINKDMA(&uartPort->Handle, hdmatx, uartPort->txDMAHandle);
229 __HAL_DMA_SET_COUNTER(&uartPort->txDMAHandle, 0);
230 } else
231 #endif
234 /* Enable the UART Transmit Data Register Empty Interrupt */
235 SET_BIT(uartPort->USARTx->CR1, USART_CR1_TXEIE);
236 SET_BIT(uartPort->USARTx->CR1, USART_CR1_TCIE);
239 return;
242 bool checkUsartTxOutput(uartPort_t *s)
244 uartDevice_t *uart = container_of(s, uartDevice_t, port);
245 IO_t txIO = IOGetByTag(uart->tx.pin);
247 if ((uart->txPinState == TX_PIN_MONITOR) && txIO) {
248 if (IORead(txIO)) {
249 // TX is high so we're good to transmit
251 // Enable USART TX output
252 uart->txPinState = TX_PIN_ACTIVE;
253 IOConfigGPIOAF(txIO, IOCFG_AF_PP, uart->tx.af);
254 return true;
255 } else {
256 // TX line is pulled low so don't enable USART TX
257 return false;
261 return true;
264 void uartTxMonitor(uartPort_t *s)
266 uartDevice_t *uart = container_of(s, uartDevice_t, port);
268 if (uart->txPinState == TX_PIN_ACTIVE) {
269 IO_t txIO = IOGetByTag(uart->tx.pin);
271 // Switch TX to an input with pullup so it's state can be monitored
272 uart->txPinState = TX_PIN_MONITOR;
273 IOConfigGPIO(txIO, IOCFG_IPU);
277 #ifdef USE_DMA
278 void uartTryStartTxDMA(uartPort_t *s)
280 ATOMIC_BLOCK(NVIC_PRIO_SERIALUART_TXDMA) {
281 if (IS_DMA_ENABLED(s->txDMAResource)) {
282 // DMA is already in progress
283 return;
286 HAL_UART_StateTypeDef state = HAL_UART_GetState(&s->Handle);
287 if ((state & HAL_UART_STATE_BUSY_TX) == HAL_UART_STATE_BUSY_TX) {
288 // UART is still transmitting
289 return;
292 if (s->port.txBufferHead == s->port.txBufferTail) {
293 // No more data to transmit
294 s->txDMAEmpty = true;
295 return;
298 uint16_t size;
299 uint32_t fromwhere = s->port.txBufferTail;
301 if (s->port.txBufferHead > s->port.txBufferTail) {
302 size = s->port.txBufferHead - s->port.txBufferTail;
303 s->port.txBufferTail = s->port.txBufferHead;
304 } else {
305 size = s->port.txBufferSize - s->port.txBufferTail;
306 s->port.txBufferTail = 0;
308 s->txDMAEmpty = false;
310 HAL_UART_Transmit_DMA(&s->Handle, (uint8_t *)&s->port.txBuffer[fromwhere], size);
314 static void handleUsartTxDma(uartPort_t *s)
316 uartDevice_t *uart = container_of(s, uartDevice_t, port);
318 uartTryStartTxDMA(s);
320 if (s->txDMAEmpty && (uart->txPinState != TX_PIN_IGNORE)) {
321 // Switch TX to an input with pullup so it's state can be monitored
322 uartTxMonitor(s);
326 void uartDmaIrqHandler(dmaChannelDescriptor_t* descriptor)
328 uartPort_t *s = &(((uartDevice_t*)(descriptor->userParam))->port);
330 HAL_DMA_IRQHandler(&s->txDMAHandle);
332 #ifdef STM32G4
333 // G4's DMA HAL turns on half transfer interrupt.
334 // Only detect the transfer complete interrupt by checking remaining transfer count.
335 // XXX TODO Consider using HAL's XferCpltCallback facility to do this.
337 if (s->txDMAHandle.Instance->CNDTR == 0) {
339 // Unlike other stream based DMA implementations (F4, F7 and H7),
340 // G4's DMA implementation does not clear EN bit upon completion of a transfer,
341 // and it is neccesary to clear the EN bit explicitly here for IS_DMA_ENABLED macro
342 // used in uartTryStartTxDMA() to continue working with G4.
344 __HAL_DMA_DISABLE(&s->txDMAHandle);
346 #endif
348 #endif
350 FAST_IRQ_HANDLER void uartIrqHandler(uartPort_t *s)
352 UART_HandleTypeDef *huart = &s->Handle;
353 /* UART in mode Receiver ---------------------------------------------------*/
354 if ((__HAL_UART_GET_IT(huart, UART_IT_RXNE) != RESET)) {
355 uint8_t rbyte = (uint8_t)(huart->Instance->RDR & (uint8_t) 0xff);
357 if (s->port.rxCallback) {
358 s->port.rxCallback(rbyte, s->port.rxCallbackData);
359 } else {
360 s->port.rxBuffer[s->port.rxBufferHead] = rbyte;
361 s->port.rxBufferHead = (s->port.rxBufferHead + 1) % s->port.rxBufferSize;
363 CLEAR_BIT(huart->Instance->CR1, (USART_CR1_PEIE));
365 /* Disable the UART Error Interrupt: (Frame error, noise error, overrun error) */
366 CLEAR_BIT(huart->Instance->CR3, USART_CR3_EIE);
368 __HAL_UART_SEND_REQ(huart, UART_RXDATA_FLUSH_REQUEST);
371 /* UART parity error interrupt occurred -------------------------------------*/
372 if ((__HAL_UART_GET_IT(huart, UART_IT_PE) != RESET)) {
373 __HAL_UART_CLEAR_IT(huart, UART_CLEAR_PEF);
376 /* UART frame error interrupt occurred --------------------------------------*/
377 if ((__HAL_UART_GET_IT(huart, UART_IT_FE) != RESET)) {
378 __HAL_UART_CLEAR_IT(huart, UART_CLEAR_FEF);
381 /* UART noise error interrupt occurred --------------------------------------*/
382 if ((__HAL_UART_GET_IT(huart, UART_IT_NE) != RESET)) {
383 __HAL_UART_CLEAR_IT(huart, UART_CLEAR_NEF);
386 /* UART Over-Run interrupt occurred -----------------------------------------*/
387 if ((__HAL_UART_GET_IT(huart, UART_IT_ORE) != RESET)) {
388 __HAL_UART_CLEAR_IT(huart, UART_CLEAR_OREF);
391 // UART transmission completed
392 if ((__HAL_UART_GET_IT(huart, UART_IT_TC) != RESET)) {
393 __HAL_UART_CLEAR_IT(huart, UART_CLEAR_TCF);
395 // Switch TX to an input with pull-up so it's state can be monitored
396 uartTxMonitor(s);
398 #ifdef USE_DMA
399 if (s->txDMAResource) {
400 handleUsartTxDma(s);
402 #endif
405 if (
406 #ifdef USE_DMA
407 !s->txDMAResource &&
408 #endif
409 (__HAL_UART_GET_IT(huart, UART_IT_TXE) != RESET)) {
410 /* Check that a Tx process is ongoing */
411 if (s->port.txBufferTail == s->port.txBufferHead) {
412 /* Disable the UART Transmit Data Register Empty Interrupt */
413 CLEAR_BIT(huart->Instance->CR1, USART_CR1_TXEIE);
414 } else {
415 if ((huart->Init.WordLength == UART_WORDLENGTH_9B) && (huart->Init.Parity == UART_PARITY_NONE)) {
416 huart->Instance->TDR = (((uint16_t) s->port.txBuffer[s->port.txBufferTail]) & (uint16_t) 0x01FFU);
417 } else {
418 huart->Instance->TDR = (uint8_t)(s->port.txBuffer[s->port.txBufferTail]);
420 s->port.txBufferTail = (s->port.txBufferTail + 1) % s->port.txBufferSize;
424 // UART reception idle detected
426 if (__HAL_UART_GET_IT(huart, UART_IT_IDLE)) {
427 if (s->port.idleCallback) {
428 s->port.idleCallback();
431 __HAL_UART_CLEAR_IDLEFLAG(huart);
435 #endif // USE_UART