Fixed UART pin definitions for STM32F411.
[betaflight.git] / src / main / drivers / serial_uart_stm32f4xx.c
blob499f3f9f539717c4b8bf5d1a3cd22936bfc1beeb
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"
30 #ifdef USE_UART
32 #include "drivers/system.h"
33 #include "drivers/io.h"
34 #include "drivers/dma.h"
35 #include "drivers/nvic.h"
36 #include "drivers/rcc.h"
38 #include "drivers/serial.h"
39 #include "drivers/serial_uart.h"
40 #include "drivers/serial_uart_impl.h"
42 const uartHardware_t uartHardware[UARTDEV_COUNT] = {
43 #ifdef USE_UART1
45 .device = UARTDEV_1,
46 .reg = USART1,
47 .DMAChannel = DMA_Channel_4,
48 #ifdef USE_UART1_RX_DMA
49 .rxDMAResource = (dmaResource_t *)DMA2_Stream5,
50 #endif
51 #ifdef USE_UART1_TX_DMA
52 .txDMAResource = (dmaResource_t *)DMA2_Stream7,
53 #endif
54 .rxPins = { { DEFIO_TAG_E(PA10) }, { DEFIO_TAG_E(PB7) },
55 #if defined (STM32F411xE)
56 { DEFIO_TAG_E(PB3) },
57 #endif
59 .txPins = { { DEFIO_TAG_E(PA9) }, { DEFIO_TAG_E(PB6) },
60 #if defined (STM32F411xE)
61 { DEFIO_TAG_E(PA15) },
62 #endif
64 .af = GPIO_AF_USART1,
65 .rcc = RCC_APB2(USART1),
66 .irqn = USART1_IRQn,
67 .txPriority = NVIC_PRIO_SERIALUART1_TXDMA,
68 .rxPriority = NVIC_PRIO_SERIALUART1
70 #endif
72 #ifdef USE_UART2
74 .device = UARTDEV_2,
75 .reg = USART2,
76 .DMAChannel = DMA_Channel_4,
77 #ifdef USE_UART2_RX_DMA
78 .rxDMAResource = (dmaResource_t *)DMA1_Stream5,
79 #endif
80 #ifdef USE_UART2_TX_DMA
81 .txDMAResource = (dmaResource_t *)DMA1_Stream6,
82 #endif
83 .rxPins = { { DEFIO_TAG_E(PA3) }, { DEFIO_TAG_E(PD6) } },
84 .txPins = { { DEFIO_TAG_E(PA2) }, { DEFIO_TAG_E(PD5) } },
85 .af = GPIO_AF_USART2,
86 .rcc = RCC_APB1(USART2),
87 .irqn = USART2_IRQn,
88 .txPriority = NVIC_PRIO_SERIALUART2_TXDMA,
89 .rxPriority = NVIC_PRIO_SERIALUART2
91 #endif
93 #ifdef USE_UART3
95 .device = UARTDEV_3,
96 .reg = USART3,
97 .DMAChannel = DMA_Channel_4,
98 #ifdef USE_UART3_RX_DMA
99 .rxDMAResource = (dmaResource_t *)DMA1_Stream1,
100 #endif
101 #ifdef USE_UART3_TX_DMA
102 .txDMAResource = (dmaResource_t *)DMA1_Stream3,
103 #endif
104 .rxPins = { { DEFIO_TAG_E(PB11) }, { DEFIO_TAG_E(PC11) }, { DEFIO_TAG_E(PD9) } },
105 .txPins = { { DEFIO_TAG_E(PB10) }, { DEFIO_TAG_E(PC10) }, { DEFIO_TAG_E(PD8) } },
106 .af = GPIO_AF_USART3,
107 .rcc = RCC_APB1(USART3),
108 .irqn = USART3_IRQn,
109 .txPriority = NVIC_PRIO_SERIALUART3_TXDMA,
110 .rxPriority = NVIC_PRIO_SERIALUART3
112 #endif
114 #ifdef USE_UART4
116 .device = UARTDEV_4,
117 .reg = UART4,
118 .DMAChannel = DMA_Channel_4,
119 #ifdef USE_UART4_RX_DMA
120 .rxDMAResource = (dmaResource_t *)DMA1_Stream2,
121 #endif
122 #ifdef USE_UART4_TX_DMA
123 .txDMAResource = (dmaResource_t *)DMA1_Stream4,
124 #endif
125 .rxPins = { { DEFIO_TAG_E(PA1) }, { DEFIO_TAG_E(PC11) } },
126 .txPins = { { DEFIO_TAG_E(PA0) }, { DEFIO_TAG_E(PC10) } },
127 .af = GPIO_AF_UART4,
128 .rcc = RCC_APB1(UART4),
129 .irqn = UART4_IRQn,
130 .txPriority = NVIC_PRIO_SERIALUART4_TXDMA,
131 .rxPriority = NVIC_PRIO_SERIALUART4
133 #endif
135 #ifdef USE_UART5
137 .device = UARTDEV_5,
138 .reg = UART5,
139 .DMAChannel = DMA_Channel_4,
140 #ifdef USE_UART5_RX_DMA
141 .rxDMAResource = (dmaResource_t *)DMA1_Stream0,
142 #endif
143 #ifdef USE_UART5_TX_DMA
144 .txDMAResource = (dmaResource_t *)DMA1_Stream7,
145 #endif
146 .rxPins = { { DEFIO_TAG_E(PD2) } },
147 .txPins = { { DEFIO_TAG_E(PC12) } },
148 .af = GPIO_AF_UART5,
149 .rcc = RCC_APB1(UART5),
150 .irqn = UART5_IRQn,
151 .txPriority = NVIC_PRIO_SERIALUART5_TXDMA,
152 .rxPriority = NVIC_PRIO_SERIALUART5
154 #endif
156 #ifdef USE_UART6
158 .device = UARTDEV_6,
159 .reg = USART6,
160 .DMAChannel = DMA_Channel_5,
161 #ifdef USE_UART6_RX_DMA
162 .rxDMAResource = (dmaResource_t *)DMA2_Stream1,
163 #endif
164 #ifdef USE_UART6_TX_DMA
165 .txDMAResource = (dmaResource_t *)DMA2_Stream6,
166 #endif
167 .rxPins = { { DEFIO_TAG_E(PC7) },
168 #if defined (STM32F411xE)
169 { DEFIO_TAG_E(PA12) },
170 #else
171 { DEFIO_TAG_E(PG9) },
172 #endif
174 .txPins = { { DEFIO_TAG_E(PC6) },
175 #if defined (STM32F411xE)
176 { DEFIO_TAG_E(PA11) },
177 #else
178 { DEFIO_TAG_E(PG14) },
179 #endif
181 .af = GPIO_AF_USART6,
182 .rcc = RCC_APB2(USART6),
183 .irqn = USART6_IRQn,
184 .txPriority = NVIC_PRIO_SERIALUART6_TXDMA,
185 .rxPriority = NVIC_PRIO_SERIALUART6
187 #endif
190 static void handleUsartTxDma(uartPort_t *s)
192 uartTryStartTxDMA(s);
195 void dmaIRQHandler(dmaChannelDescriptor_t* descriptor)
197 uartPort_t *s = &(((uartDevice_t*)(descriptor->userParam))->port);
198 if (DMA_GET_FLAG_STATUS(descriptor, DMA_IT_TCIF))
200 DMA_CLEAR_FLAG(descriptor, DMA_IT_TCIF);
201 DMA_CLEAR_FLAG(descriptor, DMA_IT_HTIF);
202 if (DMA_GET_FLAG_STATUS(descriptor, DMA_IT_FEIF))
204 DMA_CLEAR_FLAG(descriptor, DMA_IT_FEIF);
206 handleUsartTxDma(s);
208 if (DMA_GET_FLAG_STATUS(descriptor, DMA_IT_TEIF))
210 DMA_CLEAR_FLAG(descriptor, DMA_IT_TEIF);
212 if (DMA_GET_FLAG_STATUS(descriptor, DMA_IT_DMEIF))
214 DMA_CLEAR_FLAG(descriptor, DMA_IT_DMEIF);
218 // XXX Should serialUART be consolidated?
220 uartPort_t *serialUART(UARTDevice_e device, uint32_t baudRate, portMode_e mode, portOptions_e options)
222 uartDevice_t *uart = uartDevmap[device];
223 if (!uart) return NULL;
225 const uartHardware_t *hardware = uart->hardware;
227 if (!hardware) return NULL; // XXX Can't happen !?
229 uartPort_t *s = &(uart->port);
230 s->port.vTable = uartVTable;
232 s->port.baudRate = baudRate;
234 s->port.rxBuffer = uart->rxBuffer;
235 s->port.txBuffer = uart->txBuffer;
236 s->port.rxBufferSize = sizeof(uart->rxBuffer);
237 s->port.txBufferSize = sizeof(uart->txBuffer);
239 s->USARTx = hardware->reg;
241 if (hardware->rxDMAResource) {
242 dmaInit(dmaGetIdentifier(hardware->rxDMAResource), OWNER_SERIAL_RX, RESOURCE_INDEX(device));
243 s->rxDMAChannel = hardware->DMAChannel;
244 s->rxDMAResource = hardware->rxDMAResource;
245 s->rxDMAPeripheralBaseAddr = (uint32_t)&s->USARTx->DR;
248 if (hardware->txDMAResource) {
249 const dmaIdentifier_e identifier = dmaGetIdentifier(hardware->txDMAResource);
250 dmaInit(identifier, OWNER_SERIAL_TX, RESOURCE_INDEX(device));
251 dmaSetHandler(identifier, dmaIRQHandler, hardware->txPriority, (uint32_t)uart);
252 s->txDMAChannel = hardware->DMAChannel;
253 s->txDMAResource = hardware->txDMAResource;
254 s->txDMAPeripheralBaseAddr = (uint32_t)&s->USARTx->DR;
257 IO_t txIO = IOGetByTag(uart->tx.pin);
258 IO_t rxIO = IOGetByTag(uart->rx.pin);
260 if (hardware->rcc) {
261 RCC_ClockCmd(hardware->rcc, ENABLE);
264 if (options & SERIAL_BIDIR) {
265 IOInit(txIO, OWNER_SERIAL_TX, RESOURCE_INDEX(device));
266 IOConfigGPIOAF(txIO, (options & SERIAL_BIDIR_PP) ? IOCFG_AF_PP : IOCFG_AF_OD, hardware->af);
267 } else {
268 if ((mode & MODE_TX) && txIO) {
269 IOInit(txIO, OWNER_SERIAL_TX, RESOURCE_INDEX(device));
270 IOConfigGPIOAF(txIO, IOCFG_AF_PP_UP, hardware->af);
273 if ((mode & MODE_RX) && rxIO) {
274 IOInit(rxIO, OWNER_SERIAL_RX, RESOURCE_INDEX(device));
275 IOConfigGPIOAF(rxIO, IOCFG_AF_PP_UP, hardware->af);
279 if (!(s->rxDMAChannel)) {
280 NVIC_InitTypeDef NVIC_InitStructure;
282 NVIC_InitStructure.NVIC_IRQChannel = hardware->irqn;
283 NVIC_InitStructure.NVIC_IRQChannelPreemptionPriority = NVIC_PRIORITY_BASE(hardware->rxPriority);
284 NVIC_InitStructure.NVIC_IRQChannelSubPriority = NVIC_PRIORITY_SUB(hardware->rxPriority);
285 NVIC_InitStructure.NVIC_IRQChannelCmd = ENABLE;
286 NVIC_Init(&NVIC_InitStructure);
289 return s;
292 void uartIrqHandler(uartPort_t *s)
294 if (!s->rxDMAResource && (USART_GetITStatus(s->USARTx, USART_IT_RXNE) == SET)) {
295 if (s->port.rxCallback) {
296 s->port.rxCallback(s->USARTx->DR, s->port.rxCallbackData);
297 } else {
298 s->port.rxBuffer[s->port.rxBufferHead] = s->USARTx->DR;
299 s->port.rxBufferHead = (s->port.rxBufferHead + 1) % s->port.rxBufferSize;
303 if (!s->txDMAResource && (USART_GetITStatus(s->USARTx, USART_IT_TXE) == SET)) {
304 if (s->port.txBufferTail != s->port.txBufferHead) {
305 USART_SendData(s->USARTx, s->port.txBuffer[s->port.txBufferTail]);
306 s->port.txBufferTail = (s->port.txBufferTail + 1) % s->port.txBufferSize;
307 } else {
308 USART_ITConfig(s->USARTx, USART_IT_TXE, DISABLE);
312 if (USART_GetITStatus(s->USARTx, USART_IT_ORE) == SET) {
313 USART_ClearITPendingBit(s->USARTx, USART_IT_ORE);
316 if (USART_GetITStatus(s->USARTx, USART_IT_IDLE) == SET) {
317 if (s->port.idleCallback) {
318 s->port.idleCallback();
321 // clear
322 (void) s->USARTx->SR;
323 (void) s->USARTx->DR;
326 #endif