Merge pull request #11198 from SteveCEvans/sce_rc2
[betaflight.git] / src / main / drivers / serial_uart_stm32g4xx.c
blob0bca53f96c7aa90232d347f42d5ddc4de77de91d
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/>.
20 * Author: jflyper
23 #include <stdbool.h>
24 #include <stdint.h>
26 #include "platform.h"
28 #ifdef USE_UART
30 #include "drivers/system.h"
31 #include "drivers/dma.h"
32 #include "drivers/io.h"
33 #include "drivers/nvic.h"
34 #include "drivers/rcc.h"
36 #include "drivers/serial.h"
37 #include "drivers/serial_uart.h"
38 #include "drivers/serial_uart_impl.h"
40 #ifndef UART1_TX_DMA_CHANNEL
41 #define UART1_TX_DMA_CHANNEL NULL
42 #endif
43 #ifndef UART1_RX_DMA_CHANNEL
44 #define UART1_RX_DMA_CHANNEL NULL
45 #endif
46 #ifndef UART2_TX_DMA_CHANNEL
47 #define UART2_TX_DMA_CHANNEL NULL
48 #endif
49 #ifndef UART2_RX_DMA_CHANNEL
50 #define UART2_RX_DMA_CHANNEL NULL
51 #endif
52 #ifndef UART3_TX_DMA_CHANNEL
53 #define UART3_TX_DMA_CHANNEL NULL
54 #endif
55 #ifndef UART3_RX_DMA_CHANNEL
56 #define UART3_RX_DMA_CHANNEL NULL
57 #endif
58 #ifndef UART4_TX_DMA_CHANNEL
59 #define UART4_TX_DMA_CHANNEL NULL
60 #endif
61 #ifndef UART4_RX_DMA_CHANNEL
62 #define UART4_RX_DMA_CHANNEL NULL
63 #endif
64 #ifndef UART5_TX_DMA_CHANNEL
65 #define UART5_TX_DMA_CHANNEL NULL
66 #endif
67 #ifndef UART5_RX_DMA_CHANNEL
68 #define UART5_RX_DMA_CHANNEL NULL
69 #endif
70 #ifndef UART9_TX_DMA_CHANNEL
71 #define UART9_TX_DMA_CHANNEL NULL
72 #endif
73 #ifndef UART9_RX_DMA_CHANNEL
74 #define UART9_RX_DMA_CHANNEL NULL
75 #endif
77 const uartHardware_t uartHardware[UARTDEV_COUNT] = {
78 #ifdef USE_UART1
80 .device = UARTDEV_1,
81 .reg = USART1,
82 #ifdef USE_DMA
83 .rxDMAChannel = DMA_REQUEST_USART1_RX,
84 .rxDMAResource = (dmaResource_t *)UART1_RX_DMA_CHANNEL,
85 .txDMAChannel = DMA_REQUEST_USART1_TX,
86 .txDMAResource = (dmaResource_t *)UART1_TX_DMA_CHANNEL,
87 #endif
88 .rxPins = {
89 { DEFIO_TAG_E(PA10), GPIO_AF7_USART1 },
90 { DEFIO_TAG_E(PB7), GPIO_AF7_USART1 },
91 { DEFIO_TAG_E(PC5), GPIO_AF7_USART1 },
93 .txPins = {
94 { DEFIO_TAG_E(PA9), GPIO_AF7_USART1 },
95 { DEFIO_TAG_E(PB6), GPIO_AF7_USART1 },
96 { DEFIO_TAG_E(PC4), GPIO_AF7_USART1 },
98 .rcc = RCC_APB2(USART1),
99 .rxIrq = USART1_IRQn,
100 .txPriority = NVIC_PRIO_SERIALUART1_TXDMA,
101 .rxPriority = NVIC_PRIO_SERIALUART1,
102 .txBuffer = uart1TxBuffer,
103 .rxBuffer = uart1RxBuffer,
104 .txBufferSize = sizeof(uart1TxBuffer),
105 .rxBufferSize = sizeof(uart1RxBuffer),
107 #endif
109 #ifdef USE_UART2
111 .device = UARTDEV_2,
112 .reg = USART2,
113 #ifdef USE_DMA
114 .rxDMAChannel = DMA_REQUEST_USART2_RX,
115 .rxDMAResource = (dmaResource_t *)UART2_RX_DMA_CHANNEL,
116 .txDMAChannel = DMA_REQUEST_USART2_TX,
117 .txDMAResource = (dmaResource_t *)UART2_TX_DMA_CHANNEL,
118 #endif
119 .rxPins = {
120 { DEFIO_TAG_E(PA3), GPIO_AF7_USART2 },
121 { DEFIO_TAG_E(PA15), GPIO_AF7_USART2 },
122 { DEFIO_TAG_E(PB4), GPIO_AF7_USART2 },
124 .txPins = {
125 { DEFIO_TAG_E(PA2), GPIO_AF7_USART2 },
126 { DEFIO_TAG_E(PA14), GPIO_AF7_USART2 },
127 { DEFIO_TAG_E(PB3), GPIO_AF7_USART2 },
129 .rcc = RCC_APB11(USART2),
130 .rxIrq = USART2_IRQn,
131 .txPriority = NVIC_PRIO_SERIALUART2_TXDMA,
132 .rxPriority = NVIC_PRIO_SERIALUART2,
133 .txBuffer = uart2TxBuffer,
134 .rxBuffer = uart2RxBuffer,
135 .txBufferSize = sizeof(uart2TxBuffer),
136 .rxBufferSize = sizeof(uart2RxBuffer),
138 #endif
140 #ifdef USE_UART3
142 .device = UARTDEV_3,
143 .reg = USART3,
144 #ifdef USE_DMA
145 .rxDMAChannel = DMA_REQUEST_USART3_RX,
146 .rxDMAResource = (dmaResource_t *)UART3_RX_DMA_CHANNEL,
147 .txDMAChannel = DMA_REQUEST_USART3_TX,
148 .txDMAResource = (dmaResource_t *)UART3_TX_DMA_CHANNEL,
149 #endif
150 .rxPins = {
151 { DEFIO_TAG_E(PB8), GPIO_AF7_USART3 },
152 { DEFIO_TAG_E(PB11), GPIO_AF7_USART3 },
153 { DEFIO_TAG_E(PC11), GPIO_AF7_USART3 },
155 .txPins = {
156 { DEFIO_TAG_E(PB9), GPIO_AF7_USART3 },
157 { DEFIO_TAG_E(PB10), GPIO_AF7_USART3 },
158 { DEFIO_TAG_E(PC10), GPIO_AF7_USART3 },
160 .rcc = RCC_APB11(USART3),
161 .rxIrq = USART3_IRQn,
162 .txPriority = NVIC_PRIO_SERIALUART3_TXDMA,
163 .rxPriority = NVIC_PRIO_SERIALUART3,
164 .txBuffer = uart3TxBuffer,
165 .rxBuffer = uart3RxBuffer,
166 .txBufferSize = sizeof(uart3TxBuffer),
167 .rxBufferSize = sizeof(uart3RxBuffer),
169 #endif
171 #ifdef USE_UART4
173 .device = UARTDEV_4,
174 .reg = UART4,
175 #ifdef USE_DMA
176 .rxDMAChannel = DMA_REQUEST_UART4_RX,
177 .rxDMAResource = (dmaResource_t *)UART4_RX_DMA_CHANNEL,
178 .txDMAChannel = DMA_REQUEST_UART4_TX,
179 .txDMAResource = (dmaResource_t *)UART4_TX_DMA_CHANNEL,
180 #endif
181 .rxPins = {
182 { DEFIO_TAG_E(PC11), GPIO_AF5_UART4 },
184 .txPins = {
185 { DEFIO_TAG_E(PC10), GPIO_AF5_UART4 },
187 .rcc = RCC_APB11(UART4),
188 .rxIrq = UART4_IRQn,
189 .txPriority = NVIC_PRIO_SERIALUART4_TXDMA,
190 .rxPriority = NVIC_PRIO_SERIALUART4,
191 .txBuffer = uart4TxBuffer,
192 .rxBuffer = uart4RxBuffer,
193 .txBufferSize = sizeof(uart4TxBuffer),
194 .rxBufferSize = sizeof(uart4RxBuffer),
196 #endif
198 #ifdef USE_UART5
200 .device = UARTDEV_5,
201 .reg = UART5,
202 #ifdef USE_DMA
203 .rxDMAChannel = DMA_REQUEST_UART5_RX,
204 .rxDMAResource = (dmaResource_t *)UART5_RX_DMA_CHANNEL,
205 .txDMAChannel = DMA_REQUEST_UART5_TX,
206 .txDMAResource = (dmaResource_t *)UART5_TX_DMA_CHANNEL,
207 #endif
208 .rxPins = {
209 { DEFIO_TAG_E(PD2), GPIO_AF5_UART5 },
211 .txPins = {
212 { DEFIO_TAG_E(PC12), GPIO_AF5_UART5 },
214 .rcc = RCC_APB11(UART5),
215 .rxIrq = UART5_IRQn,
216 .txPriority = NVIC_PRIO_SERIALUART5_TXDMA,
217 .rxPriority = NVIC_PRIO_SERIALUART5,
218 .txBuffer = uart5TxBuffer,
219 .rxBuffer = uart5RxBuffer,
220 .txBufferSize = sizeof(uart5TxBuffer),
221 .rxBufferSize = sizeof(uart5RxBuffer),
223 #endif
225 #ifdef USE_UART9
226 // On G474, UART9 is implemented as LPUART1
228 .device = UARTDEV_9,
229 .reg = LPUART1,
230 #ifdef USE_DMA
231 .rxDMAChannel = DMA_REQUEST_LPUART1_RX,
232 .rxDMAResource = (dmaResource_t *)UART9_RX_DMA_CHANNEL,
233 .txDMAChannel = DMA_REQUEST_LPUART1_TX,
234 .txDMAResource = (dmaResource_t *)UART9_TX_DMA_CHANNEL,
235 #endif
236 .rxPins = {
237 { DEFIO_TAG_E(PA3), GPIO_AF12_LPUART1 },
238 { DEFIO_TAG_E(PB10), GPIO_AF8_LPUART1 },
239 { DEFIO_TAG_E(PC0), GPIO_AF8_LPUART1 },
241 .txPins = {
242 { DEFIO_TAG_E(PA2), GPIO_AF12_LPUART1 },
243 { DEFIO_TAG_E(PB11), GPIO_AF8_LPUART1 },
244 { DEFIO_TAG_E(PC1), GPIO_AF8_LPUART1 },
246 .rcc = RCC_APB12(LPUART1),
247 .rxIrq = LPUART1_IRQn,
248 .txPriority = NVIC_PRIO_SERIALUART6_TXDMA,
249 .rxPriority = NVIC_PRIO_SERIALUART6,
250 .txBuffer = uart9TxBuffer,
251 .rxBuffer = uart9RxBuffer,
252 .txBufferSize = sizeof(uart9TxBuffer),
253 .rxBufferSize = sizeof(uart9RxBuffer),
255 #endif
259 // XXX Should serialUART be consolidated?
261 uartPort_t *serialUART(UARTDevice_e device, uint32_t baudRate, portMode_e mode, portOptions_e options)
263 uartDevice_t *uartdev = uartDevmap[device];
264 if (!uartdev) {
265 return NULL;
268 uartPort_t *s = &(uartdev->port);
270 s->port.vTable = uartVTable;
272 s->port.baudRate = baudRate;
274 const uartHardware_t *hardware = uartdev->hardware;
276 s->USARTx = hardware->reg;
278 s->port.rxBuffer = hardware->rxBuffer;
279 s->port.txBuffer = hardware->txBuffer;
280 s->port.rxBufferSize = hardware->rxBufferSize;
281 s->port.txBufferSize = hardware->txBufferSize;
283 #ifdef USE_DMA
284 uartConfigureDma(uartdev);
285 #endif
287 s->Handle.Instance = hardware->reg;
289 if (hardware->rcc) {
290 RCC_ClockCmd(hardware->rcc, ENABLE);
293 IO_t txIO = IOGetByTag(uartdev->tx.pin);
294 IO_t rxIO = IOGetByTag(uartdev->rx.pin);
296 if ((options & SERIAL_BIDIR) && txIO) {
297 ioConfig_t ioCfg = IO_CONFIG(
298 ((options & SERIAL_INVERTED) || (options & SERIAL_BIDIR_PP) || (options & SERIAL_BIDIR_PP_PD)) ? GPIO_MODE_AF_PP : GPIO_MODE_AF_OD,
299 GPIO_SPEED_FREQ_HIGH,
300 (options & SERIAL_INVERTED) ? GPIO_PULLDOWN : GPIO_PULLUP
303 IOInit(txIO, OWNER_SERIAL_TX, RESOURCE_INDEX(device));
304 IOConfigGPIOAF(txIO, ioCfg, uartdev->tx.af);
305 } else {
306 if ((mode & MODE_TX) && txIO) {
307 IOInit(txIO, OWNER_SERIAL_TX, RESOURCE_INDEX(device));
308 IOConfigGPIOAF(txIO, IOCFG_AF_PP, uartdev->tx.af);
311 if ((mode & MODE_RX) && rxIO) {
312 IOInit(rxIO, OWNER_SERIAL_RX, RESOURCE_INDEX(device));
313 IOConfigGPIOAF(rxIO, IOCFG_AF_PP, uartdev->rx.af);
317 #ifdef USE_DMA
318 if (!s->rxDMAResource)
319 #endif
321 HAL_NVIC_SetPriority(hardware->rxIrq, NVIC_PRIORITY_BASE(hardware->rxPriority), NVIC_PRIORITY_SUB(hardware->rxPriority));
322 HAL_NVIC_EnableIRQ(hardware->rxIrq);
325 return s;
327 #endif // USE_UART