Refactor uart (#13585)
[betaflight.git] / src / platform / AT32 / serial_uart_at32bsp.c
blob0ba46faf5cba81c788ab31a7ef954ed92693bfa9
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 * Initialization part of serial_uart.c using at32 bsp driver
24 * Authors:
25 * emsr ports the code to at32f435/7
28 #include <stdbool.h>
29 #include <stdint.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/inverter.h"
42 #include "drivers/nvic.h"
43 #include "drivers/rcc.h"
45 #include "drivers/dma.h"
47 #include "drivers/serial.h"
48 #include "drivers/serial_uart.h"
49 #include "drivers/serial_uart_impl.h"
51 static void uartConfigurePinSwap(uartPort_t *uartPort)
53 uartDevice_t *uartDevice = container_of(uartPort, uartDevice_t, port);
54 if (uartDevice->pinSwap) {
55 usart_transmit_receive_pin_swap(uartDevice->port.USARTx, TRUE);
59 void uartReconfigure(uartPort_t *uartPort)
61 usart_enable(uartPort->USARTx, FALSE);
62 //init
63 usart_init(uartPort->USARTx,
64 uartPort->port.baudRate,
65 USART_DATA_8BITS,
66 (uartPort->port.options & SERIAL_STOPBITS_2) ? USART_STOP_2_BIT : USART_STOP_1_BIT);
68 //set parity
69 usart_parity_selection_config(uartPort->USARTx,
70 (uartPort->port.options & SERIAL_PARITY_EVEN) ? USART_PARITY_EVEN : USART_PARITY_NONE);
72 //set hardware control
73 usart_hardware_flow_control_set(uartPort->USARTx, USART_HARDWARE_FLOW_NONE);
75 //set mode rx or tx
76 if (uartPort->port.mode & MODE_RX) {
77 usart_receiver_enable(uartPort->USARTx, TRUE);
80 if (uartPort->port.mode & MODE_TX) {
81 usart_transmitter_enable(uartPort->USARTx, TRUE);
84 // config external pin inverter (no internal pin inversion available)
85 uartConfigureExternalPinInversion(uartPort);
87 // config pin swap
88 uartConfigurePinSwap(uartPort);
90 if (uartPort->port.options & SERIAL_BIDIR) {
91 usart_single_line_halfduplex_select(uartPort->USARTx, TRUE);
92 } else {
93 usart_single_line_halfduplex_select(uartPort->USARTx, FALSE);
95 //enable usart
96 usart_enable(uartPort->USARTx, TRUE);
98 // Receive DMA or IRQ
99 dma_init_type DMA_InitStructure;
100 if (uartPort->port.mode & MODE_RX) {
101 if (uartPort->rxDMAResource) {
103 dma_default_para_init(&DMA_InitStructure);
104 DMA_InitStructure.loop_mode_enable = TRUE;
105 DMA_InitStructure.peripheral_base_addr = uartPort->rxDMAPeripheralBaseAddr;
106 DMA_InitStructure.priority = DMA_PRIORITY_MEDIUM;
107 DMA_InitStructure.peripheral_inc_enable = FALSE;
108 DMA_InitStructure.peripheral_data_width = DMA_PERIPHERAL_DATA_WIDTH_BYTE;
109 DMA_InitStructure.memory_inc_enable = TRUE;
110 DMA_InitStructure.memory_data_width = DMA_MEMORY_DATA_WIDTH_BYTE;
111 DMA_InitStructure.memory_base_addr = (uint32_t)uartPort->port.rxBuffer;
112 DMA_InitStructure.buffer_size = uartPort->port.rxBufferSize;
113 DMA_InitStructure.direction = DMA_DIR_PERIPHERAL_TO_MEMORY;
115 xDMA_DeInit(uartPort->rxDMAResource);
116 xDMA_Init(uartPort->rxDMAResource, &DMA_InitStructure);
117 xDMA_Cmd(uartPort->rxDMAResource, TRUE);
118 usart_dma_receiver_enable(uartPort->USARTx,TRUE);
119 uartPort->rxDMAPos = xDMA_GetCurrDataCounter(uartPort->rxDMAResource);
120 } else {
121 usart_flag_clear(uartPort->USARTx, USART_RDBF_FLAG);
122 usart_interrupt_enable(uartPort->USARTx, USART_RDBF_INT, TRUE);
123 usart_interrupt_enable(uartPort->USARTx, USART_IDLE_INT, TRUE);
127 // Transmit DMA or IRQ
128 if (uartPort->port.mode & MODE_TX) {
129 if (uartPort->txDMAResource) {
130 dma_default_para_init(&DMA_InitStructure);
131 DMA_InitStructure.loop_mode_enable = FALSE;
132 DMA_InitStructure.peripheral_base_addr = uartPort->txDMAPeripheralBaseAddr;
133 DMA_InitStructure.priority = DMA_PRIORITY_MEDIUM;
134 DMA_InitStructure.peripheral_inc_enable = FALSE;
135 DMA_InitStructure.peripheral_data_width = DMA_PERIPHERAL_DATA_WIDTH_BYTE;
136 DMA_InitStructure.memory_inc_enable = TRUE;
137 DMA_InitStructure.memory_data_width = DMA_MEMORY_DATA_WIDTH_BYTE;
138 DMA_InitStructure.memory_base_addr = (uint32_t)uartPort->port.txBuffer;
139 DMA_InitStructure.buffer_size = uartPort->port.txBufferSize;
140 DMA_InitStructure.direction = DMA_DIR_MEMORY_TO_PERIPHERAL;
142 xDMA_DeInit(uartPort->txDMAResource);
143 xDMA_Init(uartPort->txDMAResource, &DMA_InitStructure);
144 xDMA_ITConfig(uartPort->txDMAResource, DMA_IT_TCIF, TRUE);
145 xDMA_SetCurrDataCounter(uartPort->txDMAResource, 0);
146 usart_dma_transmitter_enable(uartPort->USARTx, TRUE);
148 } else {
149 usart_interrupt_enable(uartPort->USARTx, USART_TDBE_INT, TRUE);
151 usart_interrupt_enable(uartPort->USARTx, USART_TDC_INT, TRUE);
153 // TODO: usart_enable is called twice
154 usart_enable(uartPort->USARTx,TRUE);
157 bool checkUsartTxOutput(uartPort_t *s)
159 uartDevice_t *uart = container_of(s, uartDevice_t, port);
160 IO_t txIO = IOGetByTag(uart->tx.pin);
162 if ((uart->txPinState == TX_PIN_MONITOR) && txIO) {
163 if (IORead(txIO)) {
164 // TX is high so we're good to transmit
166 // Enable USART TX output
167 uart->txPinState = TX_PIN_ACTIVE;
168 IOConfigGPIOAF(txIO, IOCFG_AF_PP, uart->tx.af);
170 // Enable the UART transmitter
171 usart_transmitter_enable(s->USARTx, true);
173 return true;
174 } else {
175 // TX line is pulled low so don't enable USART TX
176 return false;
180 return true;
183 void uartTxMonitor(uartPort_t *s)
185 uartDevice_t *uart = container_of(s, uartDevice_t, port);
187 if (uart->txPinState == TX_PIN_ACTIVE) {
188 IO_t txIO = IOGetByTag(uart->tx.pin);
190 // Disable the UART transmitter
191 usart_transmitter_enable(s->USARTx, false);
193 // Switch TX to an input with pullup so it's state can be monitored
194 uart->txPinState = TX_PIN_MONITOR;
195 IOConfigGPIO(txIO, IOCFG_IPU);
199 #ifdef USE_DMA
200 void uartTryStartTxDMA(uartPort_t *s)
202 // uartTryStartTxDMA must be protected, since it is called from
203 // uartWrite and handleUsartTxDma (an ISR).
205 ATOMIC_BLOCK(NVIC_PRIO_SERIALUART_TXDMA) {
206 if (IS_DMA_ENABLED(s->txDMAResource)) {
207 // DMA is already in progress
208 return;
211 // For F4, there are cases that NDTR is non-zero upon TC interrupt.
212 // We couldn't find out the root cause, so mask the case here.
213 if (xDMA_GetCurrDataCounter(s->txDMAResource)) {
214 // Possible premature TC case.
215 goto reenable;
218 if (s->port.txBufferHead == s->port.txBufferTail) {
219 // No more data to transmit.
220 s->txDMAEmpty = true;
221 return;
224 // Start a new transaction.
225 ((DMA_ARCH_TYPE*)s->txDMAResource) -> maddr =(uint32_t)&s->port.txBuffer[s->port.txBufferTail];
227 if (s->port.txBufferHead > s->port.txBufferTail) {
228 xDMA_SetCurrDataCounter(s->txDMAResource, s->port.txBufferHead - s->port.txBufferTail);
229 s->port.txBufferTail = s->port.txBufferHead;
230 } else {
231 xDMA_SetCurrDataCounter(s->txDMAResource, s->port.txBufferSize - s->port.txBufferTail);
232 s->port.txBufferTail = 0;
234 s->txDMAEmpty = false;
236 reenable:
237 xDMA_Cmd(s->txDMAResource, TRUE);
240 #endif
243 static void handleUsartTxDma(uartPort_t *s)
245 uartTryStartTxDMA(s);
247 if (s->txDMAEmpty) {
248 // Switch TX to an input with pullup so it's state can be monitored
249 uartTxMonitor(s);
253 void uartDmaIrqHandler(dmaChannelDescriptor_t* descriptor)
255 uartPort_t *s = &(((uartDevice_t*)(descriptor->userParam))->port);
256 if (DMA_GET_FLAG_STATUS(descriptor, DMA_IT_TCIF))
258 DMA_CLEAR_FLAG(descriptor, DMA_IT_TCIF);
259 DMA_CLEAR_FLAG(descriptor, DMA_IT_HTIF);
260 handleUsartTxDma(s);
263 if (DMA_GET_FLAG_STATUS(descriptor, DMA_IT_TEIF))
265 DMA_CLEAR_FLAG(descriptor, DMA_IT_TEIF);
269 void uartIrqHandler(uartPort_t *s)
271 if (!s->rxDMAResource && (usart_flag_get(s->USARTx, USART_RDBF_FLAG) == SET)) {
272 if (s->port.rxCallback) {
273 s->port.rxCallback(s->USARTx->dt, s->port.rxCallbackData);
274 } else {
275 s->port.rxBuffer[s->port.rxBufferHead] = s->USARTx->dt;
276 s->port.rxBufferHead = (s->port.rxBufferHead + 1) % s->port.rxBufferSize;
280 // UART transmission completed
281 if ((usart_flag_get(s->USARTx, USART_TDC_FLAG) != RESET)) {
282 usart_flag_clear(s->USARTx, USART_TDC_FLAG);
284 // Switch TX to an input with pull-up so it's state can be monitored
285 uartTxMonitor(s);
288 if (!s->txDMAResource && (usart_flag_get(s->USARTx, USART_TDBE_FLAG) == SET)) {
289 if (s->port.txBufferTail != s->port.txBufferHead) {
290 usart_data_transmit(s->USARTx, s->port.txBuffer[s->port.txBufferTail]);
291 s->port.txBufferTail = (s->port.txBufferTail + 1) % s->port.txBufferSize;
292 } else {
293 usart_interrupt_enable(s->USARTx, USART_TDBE_INT, FALSE);
297 if (usart_flag_get(s->USARTx, USART_ROERR_FLAG) == SET) {
298 usart_flag_clear(s->USARTx, USART_ROERR_FLAG);
301 if (usart_flag_get(s->USARTx, USART_IDLEF_FLAG) == SET) {
302 if (s->port.idleCallback) {
303 s->port.idleCallback();
306 (void) s->USARTx->sts;
307 (void) s->USARTx->dt;
310 #endif // USE_UART