Merge pull request #11939 from blckmn/flash-fix
[betaflight.git] / src / main / drivers / serial_uart_hal.c
blob53e85a5259afab67bc9d978f92b9f10c2d530431
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 #ifdef USE_UART
35 #include "build/build_config.h"
36 #include "build/atomic.h"
38 #include "common/utils.h"
39 #include "drivers/io.h"
40 #include "drivers/nvic.h"
41 #include "drivers/inverter.h"
42 #include "drivers/dma.h"
43 #include "drivers/rcc.h"
45 #include "drivers/serial.h"
46 #include "drivers/serial_uart.h"
47 #include "drivers/serial_uart_impl.h"
49 static void usartConfigurePinInversion(uartPort_t *uartPort)
51 bool inverted = uartPort->port.options & SERIAL_INVERTED;
53 if (inverted)
55 if (uartPort->port.mode & MODE_RX)
57 uartPort->Handle.AdvancedInit.AdvFeatureInit |= UART_ADVFEATURE_RXINVERT_INIT;
58 uartPort->Handle.AdvancedInit.RxPinLevelInvert = UART_ADVFEATURE_RXINV_ENABLE;
60 if (uartPort->port.mode & MODE_TX)
62 uartPort->Handle.AdvancedInit.AdvFeatureInit |= UART_ADVFEATURE_TXINVERT_INIT;
63 uartPort->Handle.AdvancedInit.TxPinLevelInvert = UART_ADVFEATURE_TXINV_ENABLE;
68 static uartDevice_t *uartFindDevice(uartPort_t *uartPort)
70 for (uint32_t i = 0; i < UARTDEV_COUNT_MAX; i++) {
71 uartDevice_t *candidate = uartDevmap[i];
73 if (&candidate->port == uartPort) {
74 return candidate;
77 return NULL;
80 #if !(defined(STM32F4))
81 static void uartConfigurePinSwap(uartPort_t *uartPort)
83 uartDevice_t *uartDevice = uartFindDevice(uartPort);
84 if (!uartDevice) {
85 return;
88 if (uartDevice->pinSwap) {
89 uartDevice->port.Handle.AdvancedInit.AdvFeatureInit |= UART_ADVFEATURE_SWAP_INIT;
90 uartDevice->port.Handle.AdvancedInit.Swap = UART_ADVFEATURE_SWAP_ENABLE;
93 #endif
95 // XXX uartReconfigure does not handle resource management properly.
97 void uartReconfigure(uartPort_t *uartPort)
99 HAL_UART_DeInit(&uartPort->Handle);
100 uartPort->Handle.Init.BaudRate = uartPort->port.baudRate;
101 // according to the stm32 documentation wordlen has to be 9 for parity bits
102 // this does not seem to matter for rx but will give bad data on tx!
103 uartPort->Handle.Init.WordLength = (uartPort->port.options & SERIAL_PARITY_EVEN) ? UART_WORDLENGTH_9B : UART_WORDLENGTH_8B;
104 uartPort->Handle.Init.StopBits = (uartPort->port.options & SERIAL_STOPBITS_2) ? USART_STOPBITS_2 : USART_STOPBITS_1;
105 uartPort->Handle.Init.Parity = (uartPort->port.options & SERIAL_PARITY_EVEN) ? USART_PARITY_EVEN : USART_PARITY_NONE;
106 uartPort->Handle.Init.HwFlowCtl = UART_HWCONTROL_NONE;
107 uartPort->Handle.Init.OneBitSampling = UART_ONE_BIT_SAMPLE_DISABLE;
108 uartPort->Handle.Init.Mode = 0;
109 #if defined(STM32G4) || defined(STM32H7)
110 if (uartPort->Handle.Instance == LPUART1) {
111 uartPort->Handle.Init.ClockPrescaler = UART_PRESCALER_DIV8;
113 #endif
115 if (uartPort->port.mode & MODE_RX)
116 uartPort->Handle.Init.Mode |= UART_MODE_RX;
117 if (uartPort->port.mode & MODE_TX)
118 uartPort->Handle.Init.Mode |= UART_MODE_TX;
121 usartConfigurePinInversion(uartPort);
122 #if !(defined(STM32F1) || defined(STM32F4))
123 uartConfigurePinSwap(uartPort);
124 #endif
126 #ifdef TARGET_USART_CONFIG
127 void usartTargetConfigure(uartPort_t *);
128 usartTargetConfigure(uartPort);
129 #endif
131 if (uartPort->port.options & SERIAL_BIDIR)
133 HAL_HalfDuplex_Init(&uartPort->Handle);
135 else
137 HAL_UART_Init(&uartPort->Handle);
140 // Receive DMA or IRQ
141 if (uartPort->port.mode & MODE_RX)
143 #ifdef USE_DMA
144 if (uartPort->rxDMAResource)
146 uartPort->rxDMAHandle.Instance = (DMA_ARCH_TYPE *)uartPort->rxDMAResource;
147 #if !(defined(STM32H7) || defined(STM32G4))
148 uartPort->rxDMAHandle.Init.Channel = uartPort->rxDMAChannel;
149 #else
150 uartPort->txDMAHandle.Init.Request = uartPort->rxDMAChannel;
151 #endif
152 uartPort->rxDMAHandle.Init.Direction = DMA_PERIPH_TO_MEMORY;
153 uartPort->rxDMAHandle.Init.PeriphInc = DMA_PINC_DISABLE;
154 uartPort->rxDMAHandle.Init.MemInc = DMA_MINC_ENABLE;
155 uartPort->rxDMAHandle.Init.PeriphDataAlignment = DMA_PDATAALIGN_BYTE;
156 uartPort->rxDMAHandle.Init.MemDataAlignment = DMA_MDATAALIGN_BYTE;
157 uartPort->rxDMAHandle.Init.Mode = DMA_CIRCULAR;
158 #if defined(STM32F4) || defined(STM32F7) || defined(STM32H7)
159 uartPort->rxDMAHandle.Init.FIFOMode = DMA_FIFOMODE_DISABLE;
160 uartPort->rxDMAHandle.Init.FIFOThreshold = DMA_FIFO_THRESHOLD_1QUARTERFULL;
161 uartPort->rxDMAHandle.Init.PeriphBurst = DMA_PBURST_SINGLE;
162 uartPort->rxDMAHandle.Init.MemBurst = DMA_MBURST_SINGLE;
163 #endif
164 uartPort->rxDMAHandle.Init.Priority = DMA_PRIORITY_MEDIUM;
167 HAL_DMA_DeInit(&uartPort->rxDMAHandle);
168 HAL_DMA_Init(&uartPort->rxDMAHandle);
169 /* Associate the initialized DMA handle to the UART handle */
170 __HAL_LINKDMA(&uartPort->Handle, hdmarx, uartPort->rxDMAHandle);
172 HAL_UART_Receive_DMA(&uartPort->Handle, (uint8_t*)uartPort->port.rxBuffer, uartPort->port.rxBufferSize);
174 uartPort->rxDMAPos = __HAL_DMA_GET_COUNTER(&uartPort->rxDMAHandle);
175 } else
176 #endif
178 /* Enable the UART Parity Error Interrupt */
179 SET_BIT(uartPort->USARTx->CR1, USART_CR1_PEIE);
181 /* Enable the UART Error Interrupt: (Frame error, noise error, overrun error) */
182 SET_BIT(uartPort->USARTx->CR3, USART_CR3_EIE);
184 /* Enable the UART Data Register not empty Interrupt */
185 SET_BIT(uartPort->USARTx->CR1, USART_CR1_RXNEIE);
187 /* Enable Idle Line detection */
188 SET_BIT(uartPort->USARTx->CR1, USART_CR1_IDLEIE);
192 // Transmit DMA or IRQ
193 if (uartPort->port.mode & MODE_TX) {
194 #ifdef USE_DMA
195 if (uartPort->txDMAResource) {
196 uartPort->txDMAHandle.Instance = (DMA_ARCH_TYPE *)uartPort->txDMAResource;
197 #if !(defined(STM32H7) || defined(STM32G4))
198 uartPort->txDMAHandle.Init.Channel = uartPort->txDMAChannel;
199 #else
200 uartPort->txDMAHandle.Init.Request = uartPort->txDMAChannel;
201 #endif
202 uartPort->txDMAHandle.Init.Direction = DMA_MEMORY_TO_PERIPH;
203 uartPort->txDMAHandle.Init.PeriphInc = DMA_PINC_DISABLE;
204 uartPort->txDMAHandle.Init.MemInc = DMA_MINC_ENABLE;
205 uartPort->txDMAHandle.Init.PeriphDataAlignment = DMA_PDATAALIGN_BYTE;
206 uartPort->txDMAHandle.Init.MemDataAlignment = DMA_MDATAALIGN_BYTE;
207 uartPort->txDMAHandle.Init.Mode = DMA_NORMAL;
208 #if !defined(STM32G4)
209 // G4's DMA is channel based, and does not have FIFO
210 uartPort->txDMAHandle.Init.FIFOMode = DMA_FIFOMODE_DISABLE;
211 uartPort->txDMAHandle.Init.FIFOThreshold = DMA_FIFO_THRESHOLD_1QUARTERFULL;
212 uartPort->txDMAHandle.Init.PeriphBurst = DMA_PBURST_SINGLE;
213 uartPort->txDMAHandle.Init.MemBurst = DMA_MBURST_SINGLE;
214 #endif
215 uartPort->txDMAHandle.Init.Priority = DMA_PRIORITY_MEDIUM;
218 HAL_DMA_DeInit(&uartPort->txDMAHandle);
219 HAL_StatusTypeDef status = HAL_DMA_Init(&uartPort->txDMAHandle);
220 if (status != HAL_OK)
222 while (1);
224 /* Associate the initialized DMA handle to the UART handle */
225 __HAL_LINKDMA(&uartPort->Handle, hdmatx, uartPort->txDMAHandle);
227 __HAL_DMA_SET_COUNTER(&uartPort->txDMAHandle, 0);
228 } else
229 #endif
232 /* Enable the UART Transmit Data Register Empty Interrupt */
233 SET_BIT(uartPort->USARTx->CR1, USART_CR1_TXEIE);
236 return;
239 #ifdef USE_DMA
240 void uartTryStartTxDMA(uartPort_t *s)
242 ATOMIC_BLOCK(NVIC_PRIO_SERIALUART_TXDMA) {
243 if (IS_DMA_ENABLED(s->txDMAResource)) {
244 // DMA is already in progress
245 return;
248 HAL_UART_StateTypeDef state = HAL_UART_GetState(&s->Handle);
249 if ((state & HAL_UART_STATE_BUSY_TX) == HAL_UART_STATE_BUSY_TX) {
250 // UART is still transmitting
251 return;
254 if (s->port.txBufferHead == s->port.txBufferTail) {
255 // No more data to transmit
256 s->txDMAEmpty = true;
257 return;
260 uint16_t size;
261 uint32_t fromwhere = s->port.txBufferTail;
263 if (s->port.txBufferHead > s->port.txBufferTail) {
264 size = s->port.txBufferHead - s->port.txBufferTail;
265 s->port.txBufferTail = s->port.txBufferHead;
266 } else {
267 size = s->port.txBufferSize - s->port.txBufferTail;
268 s->port.txBufferTail = 0;
270 s->txDMAEmpty = false;
272 HAL_UART_Transmit_DMA(&s->Handle, (uint8_t *)&s->port.txBuffer[fromwhere], size);
276 static void handleUsartTxDma(uartPort_t *s)
278 uartTryStartTxDMA(s);
281 void uartDmaIrqHandler(dmaChannelDescriptor_t* descriptor)
283 uartPort_t *s = &(((uartDevice_t*)(descriptor->userParam))->port);
285 HAL_DMA_IRQHandler(&s->txDMAHandle);
287 #ifdef STM32G4
288 // G4's DMA HAL turns on half transfer interrupt.
289 // Only detect the transfer complete interrupt by checking remaining transfer count.
290 // XXX TODO Consider using HAL's XferCpltCallback facility to do this.
292 if (s->txDMAHandle.Instance->CNDTR == 0) {
294 // Unlike other stream based DMA implementations (F4, F7 and H7),
295 // G4's DMA implementation does not clear EN bit upon completion of a transfer,
296 // and it is neccesary to clear the EN bit explicitly here for IS_DMA_ENABLED macro
297 // used in uartTryStartTxDMA() to continue working with G4.
299 __HAL_DMA_DISABLE(&s->txDMAHandle);
301 #endif
303 #endif
305 FAST_IRQ_HANDLER void uartIrqHandler(uartPort_t *s)
307 UART_HandleTypeDef *huart = &s->Handle;
308 /* UART in mode Receiver ---------------------------------------------------*/
309 if ((__HAL_UART_GET_IT(huart, UART_IT_RXNE) != RESET)) {
310 uint8_t rbyte = (uint8_t)(huart->Instance->RDR & (uint8_t) 0xff);
312 if (s->port.rxCallback) {
313 s->port.rxCallback(rbyte, s->port.rxCallbackData);
314 } else {
315 s->port.rxBuffer[s->port.rxBufferHead] = rbyte;
316 s->port.rxBufferHead = (s->port.rxBufferHead + 1) % s->port.rxBufferSize;
318 CLEAR_BIT(huart->Instance->CR1, (USART_CR1_PEIE));
320 /* Disable the UART Error Interrupt: (Frame error, noise error, overrun error) */
321 CLEAR_BIT(huart->Instance->CR3, USART_CR3_EIE);
323 __HAL_UART_SEND_REQ(huart, UART_RXDATA_FLUSH_REQUEST);
326 /* UART parity error interrupt occurred -------------------------------------*/
327 if ((__HAL_UART_GET_IT(huart, UART_IT_PE) != RESET)) {
328 __HAL_UART_CLEAR_IT(huart, UART_CLEAR_PEF);
331 /* UART frame error interrupt occurred --------------------------------------*/
332 if ((__HAL_UART_GET_IT(huart, UART_IT_FE) != RESET)) {
333 __HAL_UART_CLEAR_IT(huart, UART_CLEAR_FEF);
336 /* UART noise error interrupt occurred --------------------------------------*/
337 if ((__HAL_UART_GET_IT(huart, UART_IT_NE) != RESET)) {
338 __HAL_UART_CLEAR_IT(huart, UART_CLEAR_NEF);
341 /* UART Over-Run interrupt occurred -----------------------------------------*/
342 if ((__HAL_UART_GET_IT(huart, UART_IT_ORE) != RESET)) {
343 __HAL_UART_CLEAR_IT(huart, UART_CLEAR_OREF);
346 // UART transmitter in interrupting mode, tx buffer empty
348 if (
349 #ifdef USE_DMA
350 !s->txDMAResource &&
351 #endif
352 (__HAL_UART_GET_IT(huart, UART_IT_TXE) != RESET)) {
353 /* Check that a Tx process is ongoing */
354 if (huart->gState != HAL_UART_STATE_BUSY_TX) {
355 if (s->port.txBufferTail == s->port.txBufferHead) {
356 huart->TxXferCount = 0;
357 /* Disable the UART Transmit Data Register Empty Interrupt */
358 CLEAR_BIT(huart->Instance->CR1, USART_CR1_TXEIE);
359 } else {
360 if ((huart->Init.WordLength == UART_WORDLENGTH_9B) && (huart->Init.Parity == UART_PARITY_NONE)) {
361 huart->Instance->TDR = (((uint16_t) s->port.txBuffer[s->port.txBufferTail]) & (uint16_t) 0x01FFU);
362 } else {
363 huart->Instance->TDR = (uint8_t)(s->port.txBuffer[s->port.txBufferTail]);
365 s->port.txBufferTail = (s->port.txBufferTail + 1) % s->port.txBufferSize;
370 // UART transmitter in DMA mode, transmission completed
372 if ((__HAL_UART_GET_IT(huart, UART_IT_TC) != RESET)) {
373 HAL_UART_IRQHandler(huart);
374 #ifdef USE_DMA
375 if (s->txDMAResource) {
376 handleUsartTxDma(s);
378 #endif
381 // UART reception idle detected
383 if (__HAL_UART_GET_IT(huart, UART_IT_IDLE)) {
384 if (s->port.idleCallback) {
385 s->port.idleCallback();
388 __HAL_UART_CLEAR_IDLEFLAG(huart);
392 #endif // USE_UART