Merge pull request #11297 from SteveCEvans/baro_state
[betaflight.git] / src / main / drivers / serial_uart_stm32f4xx.c
blob0f1dc8dbb1a601fb6c07fe637f08b44b803d062e
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 .rxDMAChannel = DMA_Channel_4,
48 .txDMAChannel = DMA_Channel_4,
49 #ifdef USE_UART1_RX_DMA
50 .rxDMAResource = (dmaResource_t *)DMA2_Stream5,
51 #endif
52 #ifdef USE_UART1_TX_DMA
53 .txDMAResource = (dmaResource_t *)DMA2_Stream7,
54 #endif
55 .rxPins = { { DEFIO_TAG_E(PA10) }, { DEFIO_TAG_E(PB7) },
56 #if defined (STM32F411xE)
57 { DEFIO_TAG_E(PB3) },
58 #endif
60 .txPins = { { DEFIO_TAG_E(PA9) }, { DEFIO_TAG_E(PB6) },
61 #if defined (STM32F411xE)
62 { DEFIO_TAG_E(PA15) },
63 #endif
65 .af = GPIO_AF_USART1,
66 .rcc = RCC_APB2(USART1),
67 .irqn = USART1_IRQn,
68 .txPriority = NVIC_PRIO_SERIALUART1_TXDMA,
69 .rxPriority = NVIC_PRIO_SERIALUART1,
70 .txBuffer = uart1TxBuffer,
71 .rxBuffer = uart1RxBuffer,
72 .txBufferSize = sizeof(uart1TxBuffer),
73 .rxBufferSize = sizeof(uart1RxBuffer),
75 #endif
77 #ifdef USE_UART2
79 .device = UARTDEV_2,
80 .reg = USART2,
81 .rxDMAChannel = DMA_Channel_4,
82 .txDMAChannel = DMA_Channel_4,
83 #ifdef USE_UART2_RX_DMA
84 .rxDMAResource = (dmaResource_t *)DMA1_Stream5,
85 #endif
86 #ifdef USE_UART2_TX_DMA
87 .txDMAResource = (dmaResource_t *)DMA1_Stream6,
88 #endif
89 .rxPins = { { DEFIO_TAG_E(PA3) }, { DEFIO_TAG_E(PD6) } },
90 .txPins = { { DEFIO_TAG_E(PA2) }, { DEFIO_TAG_E(PD5) } },
91 .af = GPIO_AF_USART2,
92 .rcc = RCC_APB1(USART2),
93 .irqn = USART2_IRQn,
94 .txPriority = NVIC_PRIO_SERIALUART2_TXDMA,
95 .rxPriority = NVIC_PRIO_SERIALUART2,
96 .txBuffer = uart2TxBuffer,
97 .rxBuffer = uart2RxBuffer,
98 .txBufferSize = sizeof(uart2TxBuffer),
99 .rxBufferSize = sizeof(uart2RxBuffer),
101 #endif
103 #ifdef USE_UART3
105 .device = UARTDEV_3,
106 .reg = USART3,
107 .rxDMAChannel = DMA_Channel_4,
108 .txDMAChannel = DMA_Channel_4,
109 #ifdef USE_UART3_RX_DMA
110 .rxDMAResource = (dmaResource_t *)DMA1_Stream1,
111 #endif
112 #ifdef USE_UART3_TX_DMA
113 .txDMAResource = (dmaResource_t *)DMA1_Stream3,
114 #endif
115 .rxPins = { { DEFIO_TAG_E(PB11) }, { DEFIO_TAG_E(PC11) }, { DEFIO_TAG_E(PD9) } },
116 .txPins = { { DEFIO_TAG_E(PB10) }, { DEFIO_TAG_E(PC10) }, { DEFIO_TAG_E(PD8) } },
117 .af = GPIO_AF_USART3,
118 .rcc = RCC_APB1(USART3),
119 .irqn = USART3_IRQn,
120 .txPriority = NVIC_PRIO_SERIALUART3_TXDMA,
121 .rxPriority = NVIC_PRIO_SERIALUART3,
122 .txBuffer = uart3TxBuffer,
123 .rxBuffer = uart3RxBuffer,
124 .txBufferSize = sizeof(uart3TxBuffer),
125 .rxBufferSize = sizeof(uart3RxBuffer),
127 #endif
129 #ifdef USE_UART4
131 .device = UARTDEV_4,
132 .reg = UART4,
133 .rxDMAChannel = DMA_Channel_4,
134 .txDMAChannel = DMA_Channel_4,
135 #ifdef USE_UART4_RX_DMA
136 .rxDMAResource = (dmaResource_t *)DMA1_Stream2,
137 #endif
138 #ifdef USE_UART4_TX_DMA
139 .txDMAResource = (dmaResource_t *)DMA1_Stream4,
140 #endif
141 .rxPins = { { DEFIO_TAG_E(PA1) }, { DEFIO_TAG_E(PC11) } },
142 .txPins = { { DEFIO_TAG_E(PA0) }, { DEFIO_TAG_E(PC10) } },
143 .af = GPIO_AF_UART4,
144 .rcc = RCC_APB1(UART4),
145 .irqn = UART4_IRQn,
146 .txPriority = NVIC_PRIO_SERIALUART4_TXDMA,
147 .rxPriority = NVIC_PRIO_SERIALUART4,
148 .txBuffer = uart4TxBuffer,
149 .rxBuffer = uart4RxBuffer,
150 .txBufferSize = sizeof(uart4TxBuffer),
151 .rxBufferSize = sizeof(uart4RxBuffer),
153 #endif
155 #ifdef USE_UART5
157 .device = UARTDEV_5,
158 .reg = UART5,
159 .rxDMAChannel = DMA_Channel_4,
160 .txDMAChannel = DMA_Channel_4,
161 #ifdef USE_UART5_RX_DMA
162 .rxDMAResource = (dmaResource_t *)DMA1_Stream0,
163 #endif
164 #ifdef USE_UART5_TX_DMA
165 .txDMAResource = (dmaResource_t *)DMA1_Stream7,
166 #endif
167 .rxPins = { { DEFIO_TAG_E(PD2) } },
168 .txPins = { { DEFIO_TAG_E(PC12) } },
169 .af = GPIO_AF_UART5,
170 .rcc = RCC_APB1(UART5),
171 .irqn = UART5_IRQn,
172 .txPriority = NVIC_PRIO_SERIALUART5_TXDMA,
173 .rxPriority = NVIC_PRIO_SERIALUART5,
174 .txBuffer = uart5TxBuffer,
175 .rxBuffer = uart5RxBuffer,
176 .txBufferSize = sizeof(uart5TxBuffer),
177 .rxBufferSize = sizeof(uart5RxBuffer),
179 #endif
181 #ifdef USE_UART6
183 .device = UARTDEV_6,
184 .reg = USART6,
185 .rxDMAChannel = DMA_Channel_5,
186 .txDMAChannel = DMA_Channel_5,
187 #ifdef USE_UART6_RX_DMA
188 .rxDMAResource = (dmaResource_t *)DMA2_Stream1,
189 #endif
190 #ifdef USE_UART6_TX_DMA
191 .txDMAResource = (dmaResource_t *)DMA2_Stream6,
192 #endif
193 .rxPins = { { DEFIO_TAG_E(PC7) },
194 #if defined (STM32F411xE)
195 { DEFIO_TAG_E(PA12) },
196 #else
197 { DEFIO_TAG_E(PG9) },
198 #endif
200 .txPins = { { DEFIO_TAG_E(PC6) },
201 #if defined (STM32F411xE)
202 { DEFIO_TAG_E(PA11) },
203 #else
204 { DEFIO_TAG_E(PG14) },
205 #endif
207 .af = GPIO_AF_USART6,
208 .rcc = RCC_APB2(USART6),
209 .irqn = USART6_IRQn,
210 .txPriority = NVIC_PRIO_SERIALUART6_TXDMA,
211 .rxPriority = NVIC_PRIO_SERIALUART6,
212 .txBuffer = uart6TxBuffer,
213 .rxBuffer = uart6RxBuffer,
214 .txBufferSize = sizeof(uart6TxBuffer),
215 .rxBufferSize = sizeof(uart6RxBuffer),
217 #endif
220 static void handleUsartTxDma(uartPort_t *s)
222 uartTryStartTxDMA(s);
225 void uartDmaIrqHandler(dmaChannelDescriptor_t* descriptor)
227 uartPort_t *s = &(((uartDevice_t*)(descriptor->userParam))->port);
228 if (DMA_GET_FLAG_STATUS(descriptor, DMA_IT_TCIF))
230 DMA_CLEAR_FLAG(descriptor, DMA_IT_TCIF);
231 DMA_CLEAR_FLAG(descriptor, DMA_IT_HTIF);
232 if (DMA_GET_FLAG_STATUS(descriptor, DMA_IT_FEIF))
234 DMA_CLEAR_FLAG(descriptor, DMA_IT_FEIF);
236 handleUsartTxDma(s);
238 if (DMA_GET_FLAG_STATUS(descriptor, DMA_IT_TEIF))
240 DMA_CLEAR_FLAG(descriptor, DMA_IT_TEIF);
242 if (DMA_GET_FLAG_STATUS(descriptor, DMA_IT_DMEIF))
244 DMA_CLEAR_FLAG(descriptor, DMA_IT_DMEIF);
248 // XXX Should serialUART be consolidated?
250 uartPort_t *serialUART(UARTDevice_e device, uint32_t baudRate, portMode_e mode, portOptions_e options)
252 uartDevice_t *uart = uartDevmap[device];
253 if (!uart) return NULL;
255 const uartHardware_t *hardware = uart->hardware;
257 if (!hardware) return NULL; // XXX Can't happen !?
259 uartPort_t *s = &(uart->port);
260 s->port.vTable = uartVTable;
262 s->port.baudRate = baudRate;
264 s->port.rxBuffer = hardware->rxBuffer;
265 s->port.txBuffer = hardware->txBuffer;
266 s->port.rxBufferSize = hardware->rxBufferSize;
267 s->port.txBufferSize = hardware->txBufferSize;
269 s->USARTx = hardware->reg;
271 #ifdef USE_DMA
272 uartConfigureDma(uart);
273 #endif
275 IO_t txIO = IOGetByTag(uart->tx.pin);
276 IO_t rxIO = IOGetByTag(uart->rx.pin);
278 if (hardware->rcc) {
279 RCC_ClockCmd(hardware->rcc, ENABLE);
282 if (options & SERIAL_BIDIR) {
283 IOInit(txIO, OWNER_SERIAL_TX, RESOURCE_INDEX(device));
284 IOConfigGPIOAF(txIO, ((options & SERIAL_BIDIR_PP) || (options & SERIAL_BIDIR_PP_PD)) ? IOCFG_AF_PP : IOCFG_AF_OD, hardware->af);
285 } else {
286 if ((mode & MODE_TX) && txIO) {
287 IOInit(txIO, OWNER_SERIAL_TX, RESOURCE_INDEX(device));
288 IOConfigGPIOAF(txIO, IOCFG_AF_PP_UP, hardware->af);
291 if ((mode & MODE_RX) && rxIO) {
292 IOInit(rxIO, OWNER_SERIAL_RX, RESOURCE_INDEX(device));
293 IOConfigGPIOAF(rxIO, IOCFG_AF_PP_UP, hardware->af);
297 #ifdef USE_DMA
298 if (!(s->rxDMAResource)) {
299 NVIC_InitTypeDef NVIC_InitStructure;
301 NVIC_InitStructure.NVIC_IRQChannel = hardware->irqn;
302 NVIC_InitStructure.NVIC_IRQChannelPreemptionPriority = NVIC_PRIORITY_BASE(hardware->rxPriority);
303 NVIC_InitStructure.NVIC_IRQChannelSubPriority = NVIC_PRIORITY_SUB(hardware->rxPriority);
304 NVIC_InitStructure.NVIC_IRQChannelCmd = ENABLE;
305 NVIC_Init(&NVIC_InitStructure);
307 #endif
309 return s;
312 void uartIrqHandler(uartPort_t *s)
314 if (!s->rxDMAResource && (USART_GetITStatus(s->USARTx, USART_IT_RXNE) == SET)) {
315 if (s->port.rxCallback) {
316 s->port.rxCallback(s->USARTx->DR, s->port.rxCallbackData);
317 } else {
318 s->port.rxBuffer[s->port.rxBufferHead] = s->USARTx->DR;
319 s->port.rxBufferHead = (s->port.rxBufferHead + 1) % s->port.rxBufferSize;
323 if (!s->txDMAResource && (USART_GetITStatus(s->USARTx, USART_IT_TXE) == SET)) {
324 if (s->port.txBufferTail != s->port.txBufferHead) {
325 USART_SendData(s->USARTx, s->port.txBuffer[s->port.txBufferTail]);
326 s->port.txBufferTail = (s->port.txBufferTail + 1) % s->port.txBufferSize;
327 } else {
328 USART_ITConfig(s->USARTx, USART_IT_TXE, DISABLE);
332 if (USART_GetITStatus(s->USARTx, USART_IT_ORE) == SET) {
333 USART_ClearITPendingBit(s->USARTx, USART_IT_ORE);
336 if (USART_GetITStatus(s->USARTx, USART_IT_IDLE) == SET) {
337 if (s->port.idleCallback) {
338 s->port.idleCallback();
341 // clear
342 (void) s->USARTx->SR;
343 (void) s->USARTx->DR;
346 #endif