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)
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/>.
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
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
;
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 // XXX uartReconfigure does not handle resource management properly.
69 void uartReconfigure(uartPort_t
*uartPort
)
71 HAL_UART_DeInit(&uartPort
->Handle
);
72 uartPort
->Handle
.Init
.BaudRate
= uartPort
->port
.baudRate
;
73 // according to the stm32 documentation wordlen has to be 9 for parity bits
74 // this does not seem to matter for rx but will give bad data on tx!
75 uartPort
->Handle
.Init
.WordLength
= (uartPort
->port
.options
& SERIAL_PARITY_EVEN
) ? UART_WORDLENGTH_9B
: UART_WORDLENGTH_8B
;
76 uartPort
->Handle
.Init
.StopBits
= (uartPort
->port
.options
& SERIAL_STOPBITS_2
) ? USART_STOPBITS_2
: USART_STOPBITS_1
;
77 uartPort
->Handle
.Init
.Parity
= (uartPort
->port
.options
& SERIAL_PARITY_EVEN
) ? USART_PARITY_EVEN
: USART_PARITY_NONE
;
78 uartPort
->Handle
.Init
.HwFlowCtl
= UART_HWCONTROL_NONE
;
79 uartPort
->Handle
.Init
.OneBitSampling
= UART_ONE_BIT_SAMPLE_DISABLE
;
80 uartPort
->Handle
.Init
.Mode
= 0;
82 if (uartPort
->port
.mode
& MODE_RX
)
83 uartPort
->Handle
.Init
.Mode
|= UART_MODE_RX
;
84 if (uartPort
->port
.mode
& MODE_TX
)
85 uartPort
->Handle
.Init
.Mode
|= UART_MODE_TX
;
88 usartConfigurePinInversion(uartPort
);
90 #ifdef TARGET_USART_CONFIG
91 void usartTargetConfigure(uartPort_t
*);
92 usartTargetConfigure(uartPort
);
95 if (uartPort
->port
.options
& SERIAL_BIDIR
)
97 HAL_HalfDuplex_Init(&uartPort
->Handle
);
101 HAL_UART_Init(&uartPort
->Handle
);
104 // Receive DMA or IRQ
105 if (uartPort
->port
.mode
& MODE_RX
)
108 if (uartPort
->rxDMAResource
)
110 uartPort
->rxDMAHandle
.Instance
= (DMA_ARCH_TYPE
*)uartPort
->rxDMAResource
;
111 #if !defined(STM32H7)
112 uartPort
->rxDMAHandle
.Init
.Channel
= uartPort
->rxDMAChannel
;
114 uartPort
->txDMAHandle
.Init
.Request
= uartPort
->rxDMARequest
;
116 uartPort
->rxDMAHandle
.Init
.Direction
= DMA_PERIPH_TO_MEMORY
;
117 uartPort
->rxDMAHandle
.Init
.PeriphInc
= DMA_PINC_DISABLE
;
118 uartPort
->rxDMAHandle
.Init
.MemInc
= DMA_MINC_ENABLE
;
119 uartPort
->rxDMAHandle
.Init
.PeriphDataAlignment
= DMA_PDATAALIGN_BYTE
;
120 uartPort
->rxDMAHandle
.Init
.MemDataAlignment
= DMA_MDATAALIGN_BYTE
;
121 uartPort
->rxDMAHandle
.Init
.Mode
= DMA_CIRCULAR
;
122 uartPort
->rxDMAHandle
.Init
.FIFOMode
= DMA_FIFOMODE_DISABLE
;
123 uartPort
->rxDMAHandle
.Init
.FIFOThreshold
= DMA_FIFO_THRESHOLD_1QUARTERFULL
;
124 uartPort
->rxDMAHandle
.Init
.PeriphBurst
= DMA_PBURST_SINGLE
;
125 uartPort
->rxDMAHandle
.Init
.MemBurst
= DMA_MBURST_SINGLE
;
126 uartPort
->rxDMAHandle
.Init
.Priority
= DMA_PRIORITY_MEDIUM
;
129 HAL_DMA_DeInit(&uartPort
->rxDMAHandle
);
130 HAL_DMA_Init(&uartPort
->rxDMAHandle
);
131 /* Associate the initialized DMA handle to the UART handle */
132 __HAL_LINKDMA(&uartPort
->Handle
, hdmarx
, uartPort
->rxDMAHandle
);
134 HAL_UART_Receive_DMA(&uartPort
->Handle
, (uint8_t*)uartPort
->port
.rxBuffer
, uartPort
->port
.rxBufferSize
);
136 uartPort
->rxDMAPos
= __HAL_DMA_GET_COUNTER(&uartPort
->rxDMAHandle
);
140 /* Enable the UART Parity Error Interrupt */
141 SET_BIT(uartPort
->USARTx
->CR1
, USART_CR1_PEIE
);
143 /* Enable the UART Error Interrupt: (Frame error, noise error, overrun error) */
144 SET_BIT(uartPort
->USARTx
->CR3
, USART_CR3_EIE
);
146 /* Enable the UART Data Register not empty Interrupt */
147 SET_BIT(uartPort
->USARTx
->CR1
, USART_CR1_RXNEIE
);
149 /* Enable Idle Line detection */
150 SET_BIT(uartPort
->USARTx
->CR1
, USART_CR1_IDLEIE
);
154 // Transmit DMA or IRQ
155 if (uartPort
->port
.mode
& MODE_TX
) {
157 if (uartPort
->txDMAResource
) {
158 uartPort
->txDMAHandle
.Instance
= (DMA_ARCH_TYPE
*)uartPort
->txDMAResource
;
159 #if !defined(STM32H7)
160 uartPort
->txDMAHandle
.Init
.Channel
= uartPort
->txDMAChannel
;
162 uartPort
->txDMAHandle
.Init
.Request
= uartPort
->txDMARequest
;
164 uartPort
->txDMAHandle
.Init
.Direction
= DMA_MEMORY_TO_PERIPH
;
165 uartPort
->txDMAHandle
.Init
.PeriphInc
= DMA_PINC_DISABLE
;
166 uartPort
->txDMAHandle
.Init
.MemInc
= DMA_MINC_ENABLE
;
167 uartPort
->txDMAHandle
.Init
.PeriphDataAlignment
= DMA_PDATAALIGN_BYTE
;
168 uartPort
->txDMAHandle
.Init
.MemDataAlignment
= DMA_MDATAALIGN_BYTE
;
169 uartPort
->txDMAHandle
.Init
.Mode
= DMA_NORMAL
;
170 uartPort
->txDMAHandle
.Init
.FIFOMode
= DMA_FIFOMODE_DISABLE
;
171 uartPort
->txDMAHandle
.Init
.FIFOThreshold
= DMA_FIFO_THRESHOLD_1QUARTERFULL
;
172 uartPort
->txDMAHandle
.Init
.PeriphBurst
= DMA_PBURST_SINGLE
;
173 uartPort
->txDMAHandle
.Init
.MemBurst
= DMA_MBURST_SINGLE
;
174 uartPort
->txDMAHandle
.Init
.Priority
= DMA_PRIORITY_MEDIUM
;
177 HAL_DMA_DeInit(&uartPort
->txDMAHandle
);
178 HAL_StatusTypeDef status
= HAL_DMA_Init(&uartPort
->txDMAHandle
);
179 if (status
!= HAL_OK
)
183 /* Associate the initialized DMA handle to the UART handle */
184 __HAL_LINKDMA(&uartPort
->Handle
, hdmatx
, uartPort
->txDMAHandle
);
186 __HAL_DMA_SET_COUNTER(&uartPort
->txDMAHandle
, 0);
191 /* Enable the UART Transmit Data Register Empty Interrupt */
192 SET_BIT(uartPort
->USARTx
->CR1
, USART_CR1_TXEIE
);
199 void uartTryStartTxDMA(uartPort_t
*s
)
201 ATOMIC_BLOCK(NVIC_PRIO_SERIALUART_TXDMA
) {
202 if (IS_DMA_ENABLED(s
->txDMAResource
)) {
203 // DMA is already in progress
207 HAL_UART_StateTypeDef state
= HAL_UART_GetState(&s
->Handle
);
208 if ((state
& HAL_UART_STATE_BUSY_TX
) == HAL_UART_STATE_BUSY_TX
) {
212 if (s
->port
.txBufferHead
== s
->port
.txBufferTail
) {
213 // No more data to transmit
214 s
->txDMAEmpty
= true;
219 uint32_t fromwhere
= s
->port
.txBufferTail
;
221 if (s
->port
.txBufferHead
> s
->port
.txBufferTail
) {
222 size
= s
->port
.txBufferHead
- s
->port
.txBufferTail
;
223 s
->port
.txBufferTail
= s
->port
.txBufferHead
;
225 size
= s
->port
.txBufferSize
- s
->port
.txBufferTail
;
226 s
->port
.txBufferTail
= 0;
228 s
->txDMAEmpty
= false;
230 HAL_UART_Transmit_DMA(&s
->Handle
, (uint8_t *)&s
->port
.txBuffer
[fromwhere
], size
);