duplicate emptyline removal (#14027)
[betaflight.git] / src / platform / APM32 / serial_uart_apm32.c
blob43344e23172d6875139362fa50470b56c8b97914
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
28 #include <stdbool.h>
29 #include <stdint.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/inverter.h"
40 #include "drivers/nvic.h"
41 #include "drivers/rcc.h"
43 #include "drivers/serial.h"
44 #include "drivers/serial_uart.h"
45 #include "drivers/serial_uart_impl.h"
47 // XXX uartReconfigure does not handle resource management properly.
49 void uartReconfigure(uartPort_t *uartPort)
51 DAL_UART_DeInit(&uartPort->Handle);
52 uartPort->Handle.Init.BaudRate = uartPort->port.baudRate;
53 // according to the stm32 documentation wordlen has to be 9 for parity bits
54 // this does not seem to matter for rx but will give bad data on tx!
55 uartPort->Handle.Init.WordLength = (uartPort->port.options & SERIAL_PARITY_EVEN) ? UART_WORDLENGTH_9B : UART_WORDLENGTH_8B;
56 uartPort->Handle.Init.StopBits = (uartPort->port.options & SERIAL_STOPBITS_2) ? USART_STOPBITS_2 : USART_STOPBITS_1;
57 uartPort->Handle.Init.Parity = (uartPort->port.options & SERIAL_PARITY_EVEN) ? USART_PARITY_EVEN : USART_PARITY_NONE;
58 uartPort->Handle.Init.HwFlowCtl = UART_HWCONTROL_NONE;
59 uartPort->Handle.Init.OverSampling = UART_OVERSAMPLING_16;
60 uartPort->Handle.Init.Mode = 0;
62 if (uartPort->port.mode & MODE_RX)
63 uartPort->Handle.Init.Mode |= UART_MODE_RX;
64 if (uartPort->port.mode & MODE_TX)
65 uartPort->Handle.Init.Mode |= UART_MODE_TX;
67 // config external pin inverter (no internal pin inversion available)
68 uartConfigureExternalPinInversion(uartPort);
70 #ifdef TARGET_USART_CONFIG
71 // TODO: move declaration into header file
72 void usartTargetConfigure(uartPort_t *);
73 usartTargetConfigure(uartPort);
74 #endif
76 if (uartPort->port.options & SERIAL_BIDIR) {
77 DAL_HalfDuplex_Init(&uartPort->Handle);
78 } else {
79 DAL_UART_Init(&uartPort->Handle);
82 // Receive DMA or IRQ
83 if (uartPort->port.mode & MODE_RX) {
84 #ifdef USE_DMA
85 if (uartPort->rxDMAResource) {
86 uartPort->rxDMAHandle.Instance = (DMA_ARCH_TYPE *)uartPort->rxDMAResource;
87 uartPort->txDMAHandle.Init.Channel = uartPort->rxDMAChannel;
88 uartPort->rxDMAHandle.Init.Direction = DMA_PERIPH_TO_MEMORY;
89 uartPort->rxDMAHandle.Init.PeriphInc = DMA_PINC_DISABLE;
90 uartPort->rxDMAHandle.Init.MemInc = DMA_MINC_ENABLE;
91 uartPort->rxDMAHandle.Init.PeriphDataAlignment = DMA_PDATAALIGN_BYTE;
92 uartPort->rxDMAHandle.Init.MemDataAlignment = DMA_MDATAALIGN_BYTE;
93 uartPort->rxDMAHandle.Init.Mode = DMA_CIRCULAR;
94 #if defined(APM32F4)
95 uartPort->rxDMAHandle.Init.FIFOMode = DMA_FIFOMODE_DISABLE;
96 uartPort->rxDMAHandle.Init.FIFOThreshold = DMA_FIFO_THRESHOLD_1QUARTERFULL;
97 uartPort->rxDMAHandle.Init.PeriphBurst = DMA_PBURST_SINGLE;
98 uartPort->rxDMAHandle.Init.MemBurst = DMA_MBURST_SINGLE;
99 #endif
100 uartPort->rxDMAHandle.Init.Priority = DMA_PRIORITY_MEDIUM;
102 DAL_DMA_DeInit(&uartPort->rxDMAHandle);
103 DAL_DMA_Init(&uartPort->rxDMAHandle);
104 /* Associate the initialized DMA handle to the UART handle */
105 __DAL_LINKDMA(&uartPort->Handle, hdmarx, uartPort->rxDMAHandle);
107 DAL_UART_Receive_DMA(&uartPort->Handle, (uint8_t*)uartPort->port.rxBuffer, uartPort->port.rxBufferSize);
109 uartPort->rxDMAPos = __DAL_DMA_GET_COUNTER(&uartPort->rxDMAHandle);
110 } else
111 #endif
113 /* Enable the UART Parity Error Interrupt */
114 SET_BIT(uartPort->USARTx->CTRL1, USART_CTRL1_PEIEN);
116 /* Enable the UART Error Interrupt: (Frame error, noise error, overrun error) */
117 SET_BIT(uartPort->USARTx->CTRL3, USART_CTRL3_ERRIEN);
119 /* Enable the UART Data Register not empty Interrupt */
120 SET_BIT(uartPort->USARTx->CTRL1, USART_CTRL1_RXBNEIEN);
122 /* Enable Idle Line detection */
123 SET_BIT(uartPort->USARTx->CTRL1, USART_CTRL1_IDLEIEN);
127 // Transmit DMA or IRQ
128 if (uartPort->port.mode & MODE_TX) {
129 #ifdef USE_DMA
130 if (uartPort->txDMAResource) {
131 uartPort->txDMAHandle.Instance = (DMA_ARCH_TYPE *)uartPort->txDMAResource;
132 uartPort->txDMAHandle.Init.Channel = uartPort->txDMAChannel;
133 uartPort->txDMAHandle.Init.Direction = DMA_MEMORY_TO_PERIPH;
134 uartPort->txDMAHandle.Init.PeriphInc = DMA_PINC_DISABLE;
135 uartPort->txDMAHandle.Init.MemInc = DMA_MINC_ENABLE;
136 uartPort->txDMAHandle.Init.PeriphDataAlignment = DMA_PDATAALIGN_BYTE;
137 uartPort->txDMAHandle.Init.MemDataAlignment = DMA_MDATAALIGN_BYTE;
138 uartPort->txDMAHandle.Init.Mode = DMA_NORMAL;
139 uartPort->txDMAHandle.Init.FIFOMode = DMA_FIFOMODE_DISABLE;
140 uartPort->txDMAHandle.Init.FIFOThreshold = DMA_FIFO_THRESHOLD_1QUARTERFULL;
141 uartPort->txDMAHandle.Init.PeriphBurst = DMA_PBURST_SINGLE;
142 uartPort->txDMAHandle.Init.MemBurst = DMA_MBURST_SINGLE;
143 uartPort->txDMAHandle.Init.Priority = DMA_PRIORITY_MEDIUM;
145 DAL_DMA_DeInit(&uartPort->txDMAHandle);
146 DAL_StatusTypeDef status = DAL_DMA_Init(&uartPort->txDMAHandle);
147 if (status != DAL_OK) {
148 while (1);
150 /* Associate the initialized DMA handle to the UART handle */
151 __DAL_LINKDMA(&uartPort->Handle, hdmatx, uartPort->txDMAHandle);
153 __DAL_DMA_SET_COUNTER(&uartPort->txDMAHandle, 0);
154 } else
155 #endif
158 /* Enable the UART Transmit Data Register Empty Interrupt */
159 SET_BIT(uartPort->USARTx->CTRL1, USART_CTRL1_TXBEIEN);
160 SET_BIT(uartPort->USARTx->CTRL1, USART_CTRL1_TXCIEN);
165 #ifdef USE_DMA
166 void uartTryStartTxDMA(uartPort_t *s)
168 // uartTryStartTxDMA must be protected, since it is called from
169 // uartWrite and handleUsartTxDma (an ISR).
171 ATOMIC_BLOCK(NVIC_PRIO_SERIALUART_TXDMA) {
172 if (IS_DMA_ENABLED(s->txDMAResource)) {
173 // DMA is already in progress
174 return;
177 DAL_UART_StateTypeDef state = DAL_UART_GetState(&s->Handle);
178 if ((state & DAL_UART_STATE_BUSY_TX) == DAL_UART_STATE_BUSY_TX) {
179 // UART is still transmitting
180 return;
183 if (s->port.txBufferHead == s->port.txBufferTail) {
184 // No more data to transmit
185 s->txDMAEmpty = true;
186 return;
189 unsigned chunk;
190 uint32_t fromwhere = s->port.txBufferTail;
192 if (s->port.txBufferHead > s->port.txBufferTail) {
193 chunk = s->port.txBufferHead - s->port.txBufferTail;
194 s->port.txBufferTail = s->port.txBufferHead;
195 } else {
196 chunk = s->port.txBufferSize - s->port.txBufferTail;
197 s->port.txBufferTail = 0;
199 s->txDMAEmpty = false;
200 DAL_UART_Transmit_DMA(&s->Handle, (uint8_t*)s->port.txBuffer + fromwhere, chunk);
203 #endif
204 #endif // USE_UART