Merge pull request #11297 from SteveCEvans/baro_state
[betaflight.git] / src / main / drivers / serial_uart_hal.c
blob483f4ba25ecf1ee884bd4d54b5b0a27402e8aab7
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) {
50 bool inverted = uartPort->port.options & SERIAL_INVERTED;
52 if (inverted)
54 if (uartPort->port.mode & MODE_RX)
56 uartPort->Handle.AdvancedInit.AdvFeatureInit |= UART_ADVFEATURE_RXINVERT_INIT;
57 uartPort->Handle.AdvancedInit.RxPinLevelInvert = UART_ADVFEATURE_RXINV_ENABLE;
59 if (uartPort->port.mode & MODE_TX)
61 uartPort->Handle.AdvancedInit.AdvFeatureInit |= UART_ADVFEATURE_TXINVERT_INIT;
62 uartPort->Handle.AdvancedInit.TxPinLevelInvert = UART_ADVFEATURE_TXINV_ENABLE;
67 static uartDevice_t *uartFindDevice(uartPort_t *uartPort)
69 for (uint32_t i = 0; i < UARTDEV_COUNT_MAX; i++) {
70 uartDevice_t *candidate = uartDevmap[i];
72 if (&candidate->port == uartPort) {
73 return candidate;
76 return NULL;
79 #if !(defined(STM32F1) || defined(STM32F4))
80 static void uartConfigurePinSwap(uartPort_t *uartPort)
82 uartDevice_t *uartDevice = uartFindDevice(uartPort);
83 if (!uartDevice) {
84 return NULL;
87 if (uartDevice->pinSwap) {
88 uartDevice->port.Handle.AdvancedInit.AdvFeatureInit |= UART_ADVFEATURE_SWAP_INIT;
89 uartDevice->port.Handle.AdvancedInit.Swap = UART_ADVFEATURE_SWAP_ENABLE;
92 #endif
94 // XXX uartReconfigure does not handle resource management properly.
96 void uartReconfigure(uartPort_t *uartPort)
98 HAL_UART_DeInit(&uartPort->Handle);
99 uartPort->Handle.Init.BaudRate = uartPort->port.baudRate;
100 // according to the stm32 documentation wordlen has to be 9 for parity bits
101 // this does not seem to matter for rx but will give bad data on tx!
102 uartPort->Handle.Init.WordLength = (uartPort->port.options & SERIAL_PARITY_EVEN) ? UART_WORDLENGTH_9B : UART_WORDLENGTH_8B;
103 uartPort->Handle.Init.StopBits = (uartPort->port.options & SERIAL_STOPBITS_2) ? USART_STOPBITS_2 : USART_STOPBITS_1;
104 uartPort->Handle.Init.Parity = (uartPort->port.options & SERIAL_PARITY_EVEN) ? USART_PARITY_EVEN : USART_PARITY_NONE;
105 uartPort->Handle.Init.HwFlowCtl = UART_HWCONTROL_NONE;
106 uartPort->Handle.Init.OneBitSampling = UART_ONE_BIT_SAMPLE_DISABLE;
107 uartPort->Handle.Init.Mode = 0;
108 #if defined(STM32G4) || defined(STM32H7)
109 if (uartPort->Handle.Instance == LPUART1) {
110 uartPort->Handle.Init.ClockPrescaler = UART_PRESCALER_DIV8;
112 #endif
114 if (uartPort->port.mode & MODE_RX)
115 uartPort->Handle.Init.Mode |= UART_MODE_RX;
116 if (uartPort->port.mode & MODE_TX)
117 uartPort->Handle.Init.Mode |= UART_MODE_TX;
120 usartConfigurePinInversion(uartPort);
121 #if !(defined(STM32F1) || defined(STM32F4))
122 uartConfigurePinSwap(uartPort);
123 #endif
125 #ifdef TARGET_USART_CONFIG
126 void usartTargetConfigure(uartPort_t *);
127 usartTargetConfigure(uartPort);
128 #endif
130 if (uartPort->port.options & SERIAL_BIDIR)
132 HAL_HalfDuplex_Init(&uartPort->Handle);
134 else
136 HAL_UART_Init(&uartPort->Handle);
139 // Receive DMA or IRQ
140 if (uartPort->port.mode & MODE_RX)
142 #ifdef USE_DMA
143 if (uartPort->rxDMAResource)
145 uartPort->rxDMAHandle.Instance = (DMA_ARCH_TYPE *)uartPort->rxDMAResource;
146 #if !(defined(STM32H7) || defined(STM32G4))
147 uartPort->rxDMAHandle.Init.Channel = uartPort->rxDMAChannel;
148 #else
149 uartPort->txDMAHandle.Init.Request = uartPort->rxDMAChannel;
150 #endif
151 uartPort->rxDMAHandle.Init.Direction = DMA_PERIPH_TO_MEMORY;
152 uartPort->rxDMAHandle.Init.PeriphInc = DMA_PINC_DISABLE;
153 uartPort->rxDMAHandle.Init.MemInc = DMA_MINC_ENABLE;
154 uartPort->rxDMAHandle.Init.PeriphDataAlignment = DMA_PDATAALIGN_BYTE;
155 uartPort->rxDMAHandle.Init.MemDataAlignment = DMA_MDATAALIGN_BYTE;
156 uartPort->rxDMAHandle.Init.Mode = DMA_CIRCULAR;
157 #if defined(STM32F4) || defined(STM32F7) || defined(STM32H7)
158 uartPort->rxDMAHandle.Init.FIFOMode = DMA_FIFOMODE_DISABLE;
159 uartPort->rxDMAHandle.Init.FIFOThreshold = DMA_FIFO_THRESHOLD_1QUARTERFULL;
160 uartPort->rxDMAHandle.Init.PeriphBurst = DMA_PBURST_SINGLE;
161 uartPort->rxDMAHandle.Init.MemBurst = DMA_MBURST_SINGLE;
162 #endif
163 uartPort->rxDMAHandle.Init.Priority = DMA_PRIORITY_MEDIUM;
166 HAL_DMA_DeInit(&uartPort->rxDMAHandle);
167 HAL_DMA_Init(&uartPort->rxDMAHandle);
168 /* Associate the initialized DMA handle to the UART handle */
169 __HAL_LINKDMA(&uartPort->Handle, hdmarx, uartPort->rxDMAHandle);
171 HAL_UART_Receive_DMA(&uartPort->Handle, (uint8_t*)uartPort->port.rxBuffer, uartPort->port.rxBufferSize);
173 uartPort->rxDMAPos = __HAL_DMA_GET_COUNTER(&uartPort->rxDMAHandle);
174 } else
175 #endif
177 /* Enable the UART Parity Error Interrupt */
178 SET_BIT(uartPort->USARTx->CR1, USART_CR1_PEIE);
180 /* Enable the UART Error Interrupt: (Frame error, noise error, overrun error) */
181 SET_BIT(uartPort->USARTx->CR3, USART_CR3_EIE);
183 /* Enable the UART Data Register not empty Interrupt */
184 SET_BIT(uartPort->USARTx->CR1, USART_CR1_RXNEIE);
186 /* Enable Idle Line detection */
187 SET_BIT(uartPort->USARTx->CR1, USART_CR1_IDLEIE);
191 // Transmit DMA or IRQ
192 if (uartPort->port.mode & MODE_TX) {
193 #ifdef USE_DMA
194 if (uartPort->txDMAResource) {
195 uartPort->txDMAHandle.Instance = (DMA_ARCH_TYPE *)uartPort->txDMAResource;
196 #if !(defined(STM32H7) || defined(STM32G4))
197 uartPort->txDMAHandle.Init.Channel = uartPort->txDMAChannel;
198 #else
199 uartPort->txDMAHandle.Init.Request = uartPort->txDMAChannel;
200 #endif
201 uartPort->txDMAHandle.Init.Direction = DMA_MEMORY_TO_PERIPH;
202 uartPort->txDMAHandle.Init.PeriphInc = DMA_PINC_DISABLE;
203 uartPort->txDMAHandle.Init.MemInc = DMA_MINC_ENABLE;
204 uartPort->txDMAHandle.Init.PeriphDataAlignment = DMA_PDATAALIGN_BYTE;
205 uartPort->txDMAHandle.Init.MemDataAlignment = DMA_MDATAALIGN_BYTE;
206 uartPort->txDMAHandle.Init.Mode = DMA_NORMAL;
207 #if !defined(STM32G4)
208 // G4's DMA is channel based, and does not have FIFO
209 uartPort->txDMAHandle.Init.FIFOMode = DMA_FIFOMODE_DISABLE;
210 uartPort->txDMAHandle.Init.FIFOThreshold = DMA_FIFO_THRESHOLD_1QUARTERFULL;
211 uartPort->txDMAHandle.Init.PeriphBurst = DMA_PBURST_SINGLE;
212 uartPort->txDMAHandle.Init.MemBurst = DMA_MBURST_SINGLE;
213 #endif
214 uartPort->txDMAHandle.Init.Priority = DMA_PRIORITY_MEDIUM;
217 HAL_DMA_DeInit(&uartPort->txDMAHandle);
218 HAL_StatusTypeDef status = HAL_DMA_Init(&uartPort->txDMAHandle);
219 if (status != HAL_OK)
221 while (1);
223 /* Associate the initialized DMA handle to the UART handle */
224 __HAL_LINKDMA(&uartPort->Handle, hdmatx, uartPort->txDMAHandle);
226 __HAL_DMA_SET_COUNTER(&uartPort->txDMAHandle, 0);
227 } else
228 #endif
231 /* Enable the UART Transmit Data Register Empty Interrupt */
232 SET_BIT(uartPort->USARTx->CR1, USART_CR1_TXEIE);
235 return;
238 #ifdef USE_DMA
239 void uartTryStartTxDMA(uartPort_t *s)
241 ATOMIC_BLOCK(NVIC_PRIO_SERIALUART_TXDMA) {
242 if (IS_DMA_ENABLED(s->txDMAResource)) {
243 // DMA is already in progress
244 return;
247 HAL_UART_StateTypeDef state = HAL_UART_GetState(&s->Handle);
248 if ((state & HAL_UART_STATE_BUSY_TX) == HAL_UART_STATE_BUSY_TX) {
249 // UART is still transmitting
250 return;
253 if (s->port.txBufferHead == s->port.txBufferTail) {
254 // No more data to transmit
255 s->txDMAEmpty = true;
256 return;
259 uint16_t size;
260 uint32_t fromwhere = s->port.txBufferTail;
262 if (s->port.txBufferHead > s->port.txBufferTail) {
263 size = s->port.txBufferHead - s->port.txBufferTail;
264 s->port.txBufferTail = s->port.txBufferHead;
265 } else {
266 size = s->port.txBufferSize - s->port.txBufferTail;
267 s->port.txBufferTail = 0;
269 s->txDMAEmpty = false;
271 HAL_UART_Transmit_DMA(&s->Handle, (uint8_t *)&s->port.txBuffer[fromwhere], size);
275 static void handleUsartTxDma(uartPort_t *s)
277 uartTryStartTxDMA(s);
280 void uartDmaIrqHandler(dmaChannelDescriptor_t* descriptor)
282 uartPort_t *s = &(((uartDevice_t*)(descriptor->userParam))->port);
284 HAL_DMA_IRQHandler(&s->txDMAHandle);
286 #ifdef STM32G4
287 // G4's DMA HAL turns on half transfer interrupt.
288 // Only detect the transfer complete interrupt by checking remaining transfer count.
289 // XXX TODO Consider using HAL's XferCpltCallback facility to do this.
291 if (s->txDMAHandle.Instance->CNDTR == 0) {
293 // Unlike other stream based DMA implementations (F4, F7 and H7),
294 // G4's DMA implementation does not clear EN bit upon completion of a transfer,
295 // and it is neccesary to clear the EN bit explicitly here for IS_DMA_ENABLED macro
296 // used in uartTryStartTxDMA() to continue working with G4.
298 __HAL_DMA_DISABLE(&s->txDMAHandle);
300 #endif
302 #endif
304 FAST_IRQ_HANDLER void uartIrqHandler(uartPort_t *s)
306 UART_HandleTypeDef *huart = &s->Handle;
307 /* UART in mode Receiver ---------------------------------------------------*/
308 if ((__HAL_UART_GET_IT(huart, UART_IT_RXNE) != RESET)) {
309 uint8_t rbyte = (uint8_t)(huart->Instance->RDR & (uint8_t) 0xff);
311 if (s->port.rxCallback) {
312 s->port.rxCallback(rbyte, s->port.rxCallbackData);
313 } else {
314 s->port.rxBuffer[s->port.rxBufferHead] = rbyte;
315 s->port.rxBufferHead = (s->port.rxBufferHead + 1) % s->port.rxBufferSize;
317 CLEAR_BIT(huart->Instance->CR1, (USART_CR1_PEIE));
319 /* Disable the UART Error Interrupt: (Frame error, noise error, overrun error) */
320 CLEAR_BIT(huart->Instance->CR3, USART_CR3_EIE);
322 __HAL_UART_SEND_REQ(huart, UART_RXDATA_FLUSH_REQUEST);
325 /* UART parity error interrupt occurred -------------------------------------*/
326 if ((__HAL_UART_GET_IT(huart, UART_IT_PE) != RESET)) {
327 __HAL_UART_CLEAR_IT(huart, UART_CLEAR_PEF);
330 /* UART frame error interrupt occurred --------------------------------------*/
331 if ((__HAL_UART_GET_IT(huart, UART_IT_FE) != RESET)) {
332 __HAL_UART_CLEAR_IT(huart, UART_CLEAR_FEF);
335 /* UART noise error interrupt occurred --------------------------------------*/
336 if ((__HAL_UART_GET_IT(huart, UART_IT_NE) != RESET)) {
337 __HAL_UART_CLEAR_IT(huart, UART_CLEAR_NEF);
340 /* UART Over-Run interrupt occurred -----------------------------------------*/
341 if ((__HAL_UART_GET_IT(huart, UART_IT_ORE) != RESET)) {
342 __HAL_UART_CLEAR_IT(huart, UART_CLEAR_OREF);
345 // UART transmitter in interrupting mode, tx buffer empty
347 if (
348 #ifdef USE_DMA
349 !s->txDMAResource &&
350 #endif
351 (__HAL_UART_GET_IT(huart, UART_IT_TXE) != RESET)) {
352 /* Check that a Tx process is ongoing */
353 if (huart->gState != HAL_UART_STATE_BUSY_TX) {
354 if (s->port.txBufferTail == s->port.txBufferHead) {
355 huart->TxXferCount = 0;
356 /* Disable the UART Transmit Data Register Empty Interrupt */
357 CLEAR_BIT(huart->Instance->CR1, USART_CR1_TXEIE);
358 } else {
359 if ((huart->Init.WordLength == UART_WORDLENGTH_9B) && (huart->Init.Parity == UART_PARITY_NONE)) {
360 huart->Instance->TDR = (((uint16_t) s->port.txBuffer[s->port.txBufferTail]) & (uint16_t) 0x01FFU);
361 } else {
362 huart->Instance->TDR = (uint8_t)(s->port.txBuffer[s->port.txBufferTail]);
364 s->port.txBufferTail = (s->port.txBufferTail + 1) % s->port.txBufferSize;
369 // UART transmitter in DMA mode, transmission completed
371 if ((__HAL_UART_GET_IT(huart, UART_IT_TC) != RESET)) {
372 HAL_UART_IRQHandler(huart);
373 #ifdef USE_DMA
374 if (s->txDMAResource) {
375 handleUsartTxDma(s);
377 #endif
380 // UART reception idle detected
382 if (__HAL_UART_GET_IT(huart, UART_IT_IDLE)) {
383 if (s->port.idleCallback) {
384 s->port.idleCallback();
387 __HAL_UART_CLEAR_IDLEFLAG(huart);
391 #endif // USE_UART