Handle USART TX pulldown (#12929)
[betaflight.git] / src / main / drivers / stm32 / serial_uart_stm32f4xx.c
blob1f5dbf5b762b94dc16c1226db251571c66847348
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 * jflyper - Refactoring, cleanup and made pin-configurable
25 #include <stdbool.h>
26 #include <stdint.h>
28 #include "platform.h"
29 #include "build/debug.h"
31 #ifdef USE_UART
33 #include "build/debug.h"
35 #include "drivers/system.h"
36 #include "drivers/io.h"
37 #include "drivers/dma.h"
38 #include "drivers/nvic.h"
39 #include "drivers/rcc.h"
41 #include "drivers/serial.h"
42 #include "drivers/serial_uart.h"
43 #include "drivers/serial_uart_impl.h"
45 const uartHardware_t uartHardware[UARTDEV_COUNT] = {
46 #ifdef USE_UART1
48 .device = UARTDEV_1,
49 .reg = USART1,
50 .rxDMAChannel = DMA_Channel_4,
51 .txDMAChannel = DMA_Channel_4,
52 #ifdef USE_UART1_RX_DMA
53 .rxDMAResource = (dmaResource_t *)DMA2_Stream5,
54 #endif
55 #ifdef USE_UART1_TX_DMA
56 .txDMAResource = (dmaResource_t *)DMA2_Stream7,
57 #endif
58 .rxPins = { { DEFIO_TAG_E(PA10) }, { DEFIO_TAG_E(PB7) },
59 #if defined(STM32F411xE)
60 { DEFIO_TAG_E(PB3) },
61 #endif
63 .txPins = { { DEFIO_TAG_E(PA9) }, { DEFIO_TAG_E(PB6) },
64 #if defined(STM32F411xE)
65 { DEFIO_TAG_E(PA15) },
66 #endif
68 .af = GPIO_AF_USART1,
69 .rcc = RCC_APB2(USART1),
70 .irqn = USART1_IRQn,
71 .txPriority = NVIC_PRIO_SERIALUART1_TXDMA,
72 .rxPriority = NVIC_PRIO_SERIALUART1,
73 .txBuffer = uart1TxBuffer,
74 .rxBuffer = uart1RxBuffer,
75 .txBufferSize = sizeof(uart1TxBuffer),
76 .rxBufferSize = sizeof(uart1RxBuffer),
78 #endif
80 #ifdef USE_UART2
82 .device = UARTDEV_2,
83 .reg = USART2,
84 .rxDMAChannel = DMA_Channel_4,
85 .txDMAChannel = DMA_Channel_4,
86 #ifdef USE_UART2_RX_DMA
87 .rxDMAResource = (dmaResource_t *)DMA1_Stream5,
88 #endif
89 #ifdef USE_UART2_TX_DMA
90 .txDMAResource = (dmaResource_t *)DMA1_Stream6,
91 #endif
92 .rxPins = { { DEFIO_TAG_E(PA3) }, { DEFIO_TAG_E(PD6) } },
93 .txPins = { { DEFIO_TAG_E(PA2) }, { DEFIO_TAG_E(PD5) } },
94 .af = GPIO_AF_USART2,
95 .rcc = RCC_APB1(USART2),
96 .irqn = USART2_IRQn,
97 .txPriority = NVIC_PRIO_SERIALUART2_TXDMA,
98 .rxPriority = NVIC_PRIO_SERIALUART2,
99 .txBuffer = uart2TxBuffer,
100 .rxBuffer = uart2RxBuffer,
101 .txBufferSize = sizeof(uart2TxBuffer),
102 .rxBufferSize = sizeof(uart2RxBuffer),
104 #endif
106 #ifdef USE_UART3
108 .device = UARTDEV_3,
109 .reg = USART3,
110 .rxDMAChannel = DMA_Channel_4,
111 .txDMAChannel = DMA_Channel_4,
112 #ifdef USE_UART3_RX_DMA
113 .rxDMAResource = (dmaResource_t *)DMA1_Stream1,
114 #endif
115 #ifdef USE_UART3_TX_DMA
116 .txDMAResource = (dmaResource_t *)DMA1_Stream3,
117 #endif
118 .rxPins = { { DEFIO_TAG_E(PB11) }, { DEFIO_TAG_E(PC11) }, { DEFIO_TAG_E(PD9) } },
119 .txPins = { { DEFIO_TAG_E(PB10) }, { DEFIO_TAG_E(PC10) }, { DEFIO_TAG_E(PD8) } },
120 .af = GPIO_AF_USART3,
121 .rcc = RCC_APB1(USART3),
122 .irqn = USART3_IRQn,
123 .txPriority = NVIC_PRIO_SERIALUART3_TXDMA,
124 .rxPriority = NVIC_PRIO_SERIALUART3,
125 .txBuffer = uart3TxBuffer,
126 .rxBuffer = uart3RxBuffer,
127 .txBufferSize = sizeof(uart3TxBuffer),
128 .rxBufferSize = sizeof(uart3RxBuffer),
130 #endif
132 #ifdef USE_UART4
134 .device = UARTDEV_4,
135 .reg = UART4,
136 .rxDMAChannel = DMA_Channel_4,
137 .txDMAChannel = DMA_Channel_4,
138 #ifdef USE_UART4_RX_DMA
139 .rxDMAResource = (dmaResource_t *)DMA1_Stream2,
140 #endif
141 #ifdef USE_UART4_TX_DMA
142 .txDMAResource = (dmaResource_t *)DMA1_Stream4,
143 #endif
144 .rxPins = { { DEFIO_TAG_E(PA1) }, { DEFIO_TAG_E(PC11) } },
145 .txPins = { { DEFIO_TAG_E(PA0) }, { DEFIO_TAG_E(PC10) } },
146 .af = GPIO_AF_UART4,
147 .rcc = RCC_APB1(UART4),
148 .irqn = UART4_IRQn,
149 .txPriority = NVIC_PRIO_SERIALUART4_TXDMA,
150 .rxPriority = NVIC_PRIO_SERIALUART4,
151 .txBuffer = uart4TxBuffer,
152 .rxBuffer = uart4RxBuffer,
153 .txBufferSize = sizeof(uart4TxBuffer),
154 .rxBufferSize = sizeof(uart4RxBuffer),
156 #endif
158 #ifdef USE_UART5
160 .device = UARTDEV_5,
161 .reg = UART5,
162 .rxDMAChannel = DMA_Channel_4,
163 .txDMAChannel = DMA_Channel_4,
164 #ifdef USE_UART5_RX_DMA
165 .rxDMAResource = (dmaResource_t *)DMA1_Stream0,
166 #endif
167 #ifdef USE_UART5_TX_DMA
168 .txDMAResource = (dmaResource_t *)DMA1_Stream7,
169 #endif
170 .rxPins = { { DEFIO_TAG_E(PD2) } },
171 .txPins = { { DEFIO_TAG_E(PC12) } },
172 .af = GPIO_AF_UART5,
173 .rcc = RCC_APB1(UART5),
174 .irqn = UART5_IRQn,
175 .txPriority = NVIC_PRIO_SERIALUART5_TXDMA,
176 .rxPriority = NVIC_PRIO_SERIALUART5,
177 .txBuffer = uart5TxBuffer,
178 .rxBuffer = uart5RxBuffer,
179 .txBufferSize = sizeof(uart5TxBuffer),
180 .rxBufferSize = sizeof(uart5RxBuffer),
182 #endif
184 #ifdef USE_UART6
186 .device = UARTDEV_6,
187 .reg = USART6,
188 .rxDMAChannel = DMA_Channel_5,
189 .txDMAChannel = DMA_Channel_5,
190 #ifdef USE_UART6_RX_DMA
191 .rxDMAResource = (dmaResource_t *)DMA2_Stream1,
192 #endif
193 #ifdef USE_UART6_TX_DMA
194 .txDMAResource = (dmaResource_t *)DMA2_Stream6,
195 #endif
196 .rxPins = { { DEFIO_TAG_E(PC7) },
197 #if defined(STM32F411xE)
198 { DEFIO_TAG_E(PA12) },
199 #else
200 { DEFIO_TAG_E(PG9) },
201 #endif
203 .txPins = { { DEFIO_TAG_E(PC6) },
204 #if defined(STM32F411xE)
205 { DEFIO_TAG_E(PA11) },
206 #else
207 { DEFIO_TAG_E(PG14) },
208 #endif
210 .af = GPIO_AF_USART6,
211 .rcc = RCC_APB2(USART6),
212 .irqn = USART6_IRQn,
213 .txPriority = NVIC_PRIO_SERIALUART6_TXDMA,
214 .rxPriority = NVIC_PRIO_SERIALUART6,
215 .txBuffer = uart6TxBuffer,
216 .rxBuffer = uart6RxBuffer,
217 .txBufferSize = sizeof(uart6TxBuffer),
218 .rxBufferSize = sizeof(uart6RxBuffer),
220 #endif
223 bool checkUsartTxOutput(uartPort_t *s)
225 uartDevice_t *uart = container_of(s, uartDevice_t, port);
226 IO_t txIO = IOGetByTag(uart->tx.pin);
228 if ((uart->txPinState == TX_PIN_MONITOR) && txIO) {
229 if (IORead(txIO)) {
230 // TX is high so we're good to transmit
232 // Enable USART TX output
233 uart->txPinState = TX_PIN_ACTIVE;
234 IOConfigGPIOAF(txIO, IOCFG_AF_PP, uart->hardware->af);
235 return true;
236 } else {
237 // TX line is pulled low so don't enable USART TX
238 return false;
242 return true;
245 void uartTxMonitor(uartPort_t *s)
247 uartDevice_t *uart = container_of(s, uartDevice_t, port);
249 if (uart->txPinState == TX_PIN_ACTIVE) {
250 IO_t txIO = IOGetByTag(uart->tx.pin);
252 // Switch TX to an input with pullup so it's state can be monitored
253 uart->txPinState = TX_PIN_MONITOR;
254 IOConfigGPIO(txIO, IOCFG_IPU);
258 static void handleUsartTxDma(uartPort_t *s)
260 uartDevice_t *uart = container_of(s, uartDevice_t, port);
262 uartTryStartTxDMA(s);
264 if (s->txDMAEmpty && (uart->txPinState != TX_PIN_IGNORE)) {
265 // Switch TX to an input with pullup so it's state can be monitored
266 uartTxMonitor(s);
270 void uartDmaIrqHandler(dmaChannelDescriptor_t* descriptor)
272 uartPort_t *s = &(((uartDevice_t*)(descriptor->userParam))->port);
273 if (DMA_GET_FLAG_STATUS(descriptor, DMA_IT_TCIF))
275 DMA_CLEAR_FLAG(descriptor, DMA_IT_TCIF);
276 DMA_CLEAR_FLAG(descriptor, DMA_IT_HTIF);
277 if (DMA_GET_FLAG_STATUS(descriptor, DMA_IT_FEIF))
279 DMA_CLEAR_FLAG(descriptor, DMA_IT_FEIF);
281 handleUsartTxDma(s);
283 if (DMA_GET_FLAG_STATUS(descriptor, DMA_IT_TEIF))
285 DMA_CLEAR_FLAG(descriptor, DMA_IT_TEIF);
287 if (DMA_GET_FLAG_STATUS(descriptor, DMA_IT_DMEIF))
289 DMA_CLEAR_FLAG(descriptor, DMA_IT_DMEIF);
293 // XXX Should serialUART be consolidated?
295 uartPort_t *serialUART(UARTDevice_e device, uint32_t baudRate, portMode_e mode, portOptions_e options)
297 uartDevice_t *uart = uartDevmap[device];
298 if (!uart) return NULL;
300 const uartHardware_t *hardware = uart->hardware;
302 if (!hardware) return NULL; // XXX Can't happen !?
304 uartPort_t *s = &(uart->port);
305 s->port.vTable = uartVTable;
307 s->port.baudRate = baudRate;
309 s->port.rxBuffer = hardware->rxBuffer;
310 s->port.txBuffer = hardware->txBuffer;
311 s->port.rxBufferSize = hardware->rxBufferSize;
312 s->port.txBufferSize = hardware->txBufferSize;
314 s->USARTx = hardware->reg;
316 s->checkUsartTxOutput = checkUsartTxOutput;
318 #ifdef USE_DMA
319 uartConfigureDma(uart);
320 #endif
322 IO_t txIO = IOGetByTag(uart->tx.pin);
323 IO_t rxIO = IOGetByTag(uart->rx.pin);
325 if (hardware->rcc) {
326 RCC_ClockCmd(hardware->rcc, ENABLE);
329 uart->txPinState = TX_PIN_IGNORE;
331 if (options & SERIAL_BIDIR) {
332 IOInit(txIO, OWNER_SERIAL_TX, RESOURCE_INDEX(device));
333 IOConfigGPIOAF(txIO, ((options & SERIAL_BIDIR_PP) || (options & SERIAL_BIDIR_PP_PD)) ? IOCFG_AF_PP : IOCFG_AF_OD, hardware->af);
334 } else {
335 if ((mode & MODE_TX) && txIO) {
336 IOInit(txIO, OWNER_SERIAL_TX, RESOURCE_INDEX(device));
338 if (((options & SERIAL_INVERTED) == SERIAL_NOT_INVERTED) && !(options & SERIAL_BIDIR_PP_PD)) {
339 uart->txPinState = TX_PIN_ACTIVE;
340 // Switch TX to an input with pullup so it's state can be monitored
341 uartTxMonitor(s);
342 } else {
343 IOConfigGPIOAF(txIO, IOCFG_AF_PP_UP, hardware->af);
347 if ((mode & MODE_RX) && rxIO) {
348 IOInit(rxIO, OWNER_SERIAL_RX, RESOURCE_INDEX(device));
349 IOConfigGPIOAF(rxIO, IOCFG_AF_PP_UP, hardware->af);
353 #ifdef USE_DMA
354 if (!(s->rxDMAResource)) {
355 NVIC_InitTypeDef NVIC_InitStructure;
357 NVIC_InitStructure.NVIC_IRQChannel = hardware->irqn;
358 NVIC_InitStructure.NVIC_IRQChannelPreemptionPriority = NVIC_PRIORITY_BASE(hardware->rxPriority);
359 NVIC_InitStructure.NVIC_IRQChannelSubPriority = NVIC_PRIORITY_SUB(hardware->rxPriority);
360 NVIC_InitStructure.NVIC_IRQChannelCmd = ENABLE;
361 NVIC_Init(&NVIC_InitStructure);
363 #endif
365 return s;
368 void uartIrqHandler(uartPort_t *s)
370 if (!s->rxDMAResource && (USART_GetITStatus(s->USARTx, USART_IT_RXNE) == SET)) {
371 if (s->port.rxCallback) {
372 s->port.rxCallback(s->USARTx->DR, s->port.rxCallbackData);
373 } else {
374 s->port.rxBuffer[s->port.rxBufferHead] = s->USARTx->DR;
375 s->port.rxBufferHead = (s->port.rxBufferHead + 1) % s->port.rxBufferSize;
379 // Detect completion of transmission
380 if (USART_GetITStatus(s->USARTx, USART_IT_TC) == SET) {
381 // Switch TX to an input with pullup so it's state can be monitored
382 uartTxMonitor(s);
384 USART_ClearITPendingBit(s->USARTx, USART_IT_TC);
387 if (!s->txDMAResource && (USART_GetITStatus(s->USARTx, USART_IT_TXE) == SET)) {
388 if (s->port.txBufferTail != s->port.txBufferHead) {
389 USART_SendData(s->USARTx, s->port.txBuffer[s->port.txBufferTail]);
390 s->port.txBufferTail = (s->port.txBufferTail + 1) % s->port.txBufferSize;
391 } else {
392 USART_ITConfig(s->USARTx, USART_IT_TXE, DISABLE);
394 // Switch TX to an input with pullup so it's state can be monitored
395 uartTxMonitor(s);
399 if (USART_GetITStatus(s->USARTx, USART_IT_ORE) == SET) {
400 USART_ClearITPendingBit(s->USARTx, USART_IT_ORE);
403 if (USART_GetITStatus(s->USARTx, USART_IT_IDLE) == SET) {
404 if (s->port.idleCallback) {
405 s->port.idleCallback();
408 // clear
409 (void) s->USARTx->SR;
410 (void) s->USARTx->DR;
413 #endif