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/>.
22 * Initialization part of serial_uart.c
27 * jflyper - Refactoring, cleanup and made pin-configurable
28 * Dominic Clifton - Serial port abstraction, Separation of common STM32 code for cleanflight, various cleanups.
29 * Hamasaki/Timecop - Initial baseflight code
39 #include "build/build_config.h"
40 #include "build/atomic.h"
42 #include "common/utils.h"
43 #include "drivers/inverter.h"
44 #include "drivers/nvic.h"
45 #include "drivers/rcc.h"
47 #include "drivers/serial.h"
48 #include "drivers/serial_uart.h"
49 #include "drivers/serial_uart_impl.h"
51 static void usartConfigurePinInversion(uartPort_t
*uartPort
)
53 #if !defined(USE_INVERTER)
56 bool inverted
= uartPort
->port
.options
& SERIAL_INVERTED
;
60 // Enable hardware inverter if available.
61 enableInverter(uartPort
->USARTx
, true);
67 void uartReconfigure(uartPort_t
*uartPort
)
69 USART_InitTypeDef USART_InitStructure
;
70 USART_Cmd(uartPort
->USARTx
, DISABLE
);
72 USART_InitStructure
.USART_BaudRate
= uartPort
->port
.baudRate
;
74 // according to the stm32 documentation wordlen has to be 9 for parity bits
75 // this does not seem to matter for rx but will give bad data on tx!
76 if (uartPort
->port
.options
& SERIAL_PARITY_EVEN
) {
77 USART_InitStructure
.USART_WordLength
= USART_WordLength_9b
;
79 USART_InitStructure
.USART_WordLength
= USART_WordLength_8b
;
82 USART_InitStructure
.USART_StopBits
= (uartPort
->port
.options
& SERIAL_STOPBITS_2
) ? USART_StopBits_2
: USART_StopBits_1
;
83 USART_InitStructure
.USART_Parity
= (uartPort
->port
.options
& SERIAL_PARITY_EVEN
) ? USART_Parity_Even
: USART_Parity_No
;
85 USART_InitStructure
.USART_HardwareFlowControl
= USART_HardwareFlowControl_None
;
86 USART_InitStructure
.USART_Mode
= 0;
87 if (uartPort
->port
.mode
& MODE_RX
)
88 USART_InitStructure
.USART_Mode
|= USART_Mode_Rx
;
89 if (uartPort
->port
.mode
& MODE_TX
)
90 USART_InitStructure
.USART_Mode
|= USART_Mode_Tx
;
92 USART_Init(uartPort
->USARTx
, &USART_InitStructure
);
94 usartConfigurePinInversion(uartPort
);
96 if (uartPort
->port
.options
& SERIAL_BIDIR
)
97 USART_HalfDuplexCmd(uartPort
->USARTx
, ENABLE
);
99 USART_HalfDuplexCmd(uartPort
->USARTx
, DISABLE
);
101 USART_Cmd(uartPort
->USARTx
, ENABLE
);
103 // Receive DMA or IRQ
104 DMA_InitTypeDef DMA_InitStructure
;
105 if (uartPort
->port
.mode
& MODE_RX
) {
106 if (uartPort
->rxDMAResource
) {
107 DMA_StructInit(&DMA_InitStructure
);
108 DMA_InitStructure
.DMA_Mode
= DMA_Mode_Circular
;
109 DMA_InitStructure
.DMA_PeripheralBaseAddr
= uartPort
->rxDMAPeripheralBaseAddr
;
110 DMA_InitStructure
.DMA_Priority
= DMA_Priority_Medium
;
111 DMA_InitStructure
.DMA_PeripheralInc
= DMA_PeripheralInc_Disable
;
112 DMA_InitStructure
.DMA_PeripheralDataSize
= DMA_PeripheralDataSize_Byte
;
113 DMA_InitStructure
.DMA_MemoryInc
= DMA_MemoryInc_Enable
;
114 DMA_InitStructure
.DMA_MemoryDataSize
= DMA_MemoryDataSize_Byte
;
115 DMA_InitStructure
.DMA_BufferSize
= uartPort
->port
.rxBufferSize
;
117 DMA_InitStructure
.DMA_FIFOMode
= DMA_FIFOMode_Disable
;
118 DMA_InitStructure
.DMA_FIFOThreshold
= DMA_FIFOThreshold_1QuarterFull
;
119 DMA_InitStructure
.DMA_MemoryBurst
= DMA_MemoryBurst_Single
;
120 DMA_InitStructure
.DMA_PeripheralBurst
= DMA_PeripheralBurst_Single
;
122 DMA_InitStructure
.DMA_Channel
= uartPort
->rxDMAChannel
;
123 DMA_InitStructure
.DMA_DIR
= DMA_DIR_PeripheralToMemory
;
124 DMA_InitStructure
.DMA_Memory0BaseAddr
= (uint32_t)uartPort
->port
.rxBuffer
;
126 DMA_InitStructure
.DMA_M2M
= DMA_M2M_Disable
;
127 DMA_InitStructure
.DMA_DIR
= DMA_DIR_PeripheralSRC
;
128 DMA_InitStructure
.DMA_MemoryBaseAddr
= (uint32_t)uartPort
->port
.rxBuffer
;
131 xDMA_DeInit(uartPort
->rxDMAResource
);
132 xDMA_Init(uartPort
->rxDMAResource
, &DMA_InitStructure
);
133 xDMA_Cmd(uartPort
->rxDMAResource
, ENABLE
);
134 USART_DMACmd(uartPort
->USARTx
, USART_DMAReq_Rx
, ENABLE
);
135 uartPort
->rxDMAPos
= xDMA_GetCurrDataCounter(uartPort
->rxDMAResource
);
137 USART_ClearITPendingBit(uartPort
->USARTx
, USART_IT_RXNE
);
138 USART_ITConfig(uartPort
->USARTx
, USART_IT_RXNE
, ENABLE
);
139 USART_ITConfig(uartPort
->USARTx
, USART_IT_IDLE
, ENABLE
);
143 // Transmit DMA or IRQ
144 if (uartPort
->port
.mode
& MODE_TX
) {
145 if (uartPort
->txDMAResource
) {
146 DMA_StructInit(&DMA_InitStructure
);
147 DMA_InitStructure
.DMA_Mode
= DMA_Mode_Normal
;
148 DMA_InitStructure
.DMA_PeripheralBaseAddr
= uartPort
->txDMAPeripheralBaseAddr
;
149 DMA_InitStructure
.DMA_Priority
= DMA_Priority_Medium
;
150 DMA_InitStructure
.DMA_PeripheralInc
= DMA_PeripheralInc_Disable
;
151 DMA_InitStructure
.DMA_PeripheralDataSize
= DMA_PeripheralDataSize_Byte
;
152 DMA_InitStructure
.DMA_MemoryInc
= DMA_MemoryInc_Enable
;
153 DMA_InitStructure
.DMA_MemoryDataSize
= DMA_MemoryDataSize_Byte
;
154 DMA_InitStructure
.DMA_BufferSize
= uartPort
->port
.txBufferSize
;
157 DMA_InitStructure
.DMA_FIFOMode
= DMA_FIFOMode_Disable
;
158 DMA_InitStructure
.DMA_FIFOThreshold
= DMA_FIFOThreshold_1QuarterFull
;
159 DMA_InitStructure
.DMA_MemoryBurst
= DMA_MemoryBurst_Single
;
160 DMA_InitStructure
.DMA_PeripheralBurst
= DMA_PeripheralBurst_Single
;
162 DMA_InitStructure
.DMA_Channel
= uartPort
->txDMAChannel
;
163 DMA_InitStructure
.DMA_DIR
= DMA_DIR_MemoryToPeripheral
;
165 DMA_InitStructure
.DMA_M2M
= DMA_M2M_Disable
;
166 DMA_InitStructure
.DMA_DIR
= DMA_DIR_PeripheralDST
;
169 xDMA_DeInit(uartPort
->txDMAResource
);
170 xDMA_Init(uartPort
->txDMAResource
, &DMA_InitStructure
);
173 xDMA_ITConfig(uartPort
->txDMAResource
, DMA_IT_TC
| DMA_IT_FE
| DMA_IT_TE
| DMA_IT_DME
, ENABLE
);
175 xDMA_ITConfig(uartPort
->txDMAResource
, DMA_IT_TC
, ENABLE
);
178 xDMA_SetCurrDataCounter(uartPort
->txDMAResource
, 0);
179 USART_DMACmd(uartPort
->USARTx
, USART_DMAReq_Tx
, ENABLE
);
181 USART_ITConfig(uartPort
->USARTx
, USART_IT_TXE
, ENABLE
);
183 // Enable the interrupt so completion of the transmission will be signalled
184 USART_ITConfig(uartPort
->USARTx
, USART_IT_TC
, ENABLE
);
187 USART_Cmd(uartPort
->USARTx
, ENABLE
);
191 void uartTryStartTxDMA(uartPort_t
*s
)
193 // uartTryStartTxDMA must be protected, since it is called from
194 // uartWrite and handleUsartTxDma (an ISR).
196 ATOMIC_BLOCK(NVIC_PRIO_SERIALUART_TXDMA
) {
197 if (IS_DMA_ENABLED(s
->txDMAResource
)) {
198 // DMA is already in progress
202 // For F4 (and F1), there are cases that NDTR (CNDTR for F1) is non-zero upon TC interrupt.
203 // We couldn't find out the root cause, so mask the case here.
204 // F3 is not confirmed to be vulnerable, but not excluded as a safety.
206 if (xDMA_GetCurrDataCounter(s
->txDMAResource
)) {
207 // Possible premature TC case.
211 if (s
->port
.txBufferHead
== s
->port
.txBufferTail
) {
212 // No more data to transmit.
213 s
->txDMAEmpty
= true;
217 // Start a new transaction.
220 xDMA_MemoryTargetConfig(s
->txDMAResource
, (uint32_t)&s
->port
.txBuffer
[s
->port
.txBufferTail
], DMA_Memory_0
);
222 DMAx_SetMemoryAddress(s
->txDMAResource
, (uint32_t)&s
->port
.txBuffer
[s
->port
.txBufferTail
]);
225 if (s
->port
.txBufferHead
> s
->port
.txBufferTail
) {
226 xDMA_SetCurrDataCounter(s
->txDMAResource
, s
->port
.txBufferHead
- s
->port
.txBufferTail
);
227 s
->port
.txBufferTail
= s
->port
.txBufferHead
;
229 xDMA_SetCurrDataCounter(s
->txDMAResource
, s
->port
.txBufferSize
- s
->port
.txBufferTail
);
230 s
->port
.txBufferTail
= 0;
232 s
->txDMAEmpty
= false;
235 xDMA_Cmd(s
->txDMAResource
, ENABLE
);