Merge pull request #11198 from SteveCEvans/sce_rc2
[betaflight.git] / src / main / drivers / serial_uart_stm32f10x.c
blobcc5746b60292272c6dfe3742d64032e21d2dd859
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 * Authors:
23 * jflyper - Refactoring, cleanup and made pin-configurable
24 * Dominic Clifton/Hydra - Various cleanups for Cleanflight
25 * Bill Nesbitt - Code from AutoQuad
26 * Hamasaki/Timecop - Initial baseflight code
29 #include <stdbool.h>
30 #include <stdint.h>
32 #include "platform.h"
34 #ifdef USE_UART
36 #include "drivers/system.h"
37 #include "drivers/io.h"
38 #include "drivers/nvic.h"
39 #include "drivers/dma.h"
40 #include "drivers/rcc.h"
42 #include "drivers/serial.h"
43 #include "drivers/serial_uart.h"
44 #include "drivers/serial_uart_impl.h"
46 #ifdef USE_UART1_RX_DMA
47 # define UART1_RX_DMA_CHANNEL DMA1_Channel5
48 #else
49 # define UART1_RX_DMA_CHANNEL 0
50 #endif
52 #ifdef USE_UART1_TX_DMA
53 # define UART1_TX_DMA_CHANNEL DMA1_Channel4
54 #else
55 # define UART1_TX_DMA_CHANNEL 0
56 #endif
58 #define UART2_RX_DMA_CHANNEL 0
59 #define UART2_TX_DMA_CHANNEL 0
60 #define UART3_RX_DMA_CHANNEL 0
61 #define UART3_TX_DMA_CHANNEL 0
63 const uartHardware_t uartHardware[UARTDEV_COUNT] = {
64 #ifdef USE_UART1
66 .device = UARTDEV_1,
67 .reg = USART1,
68 .rxDMAResource = (dmaResource_t *)UART1_RX_DMA_CHANNEL,
69 .txDMAResource = (dmaResource_t *)UART1_TX_DMA_CHANNEL,
70 .rxPins = { { DEFIO_TAG_E(PA10) }, { DEFIO_TAG_E(PB7) } },
71 .txPins = { { DEFIO_TAG_E(PA9) }, { DEFIO_TAG_E(PB6) } },
72 //.af = GPIO_AF_USART1,
73 .rcc = RCC_APB2(USART1),
74 .irqn = USART1_IRQn,
75 .txPriority = NVIC_PRIO_SERIALUART1_TXDMA,
76 .rxPriority = NVIC_PRIO_SERIALUART1,
77 .txBuffer = uart1TxBuffer,
78 .rxBuffer = uart1RxBuffer,
79 .txBufferSize = sizeof(uart1TxBuffer),
80 .rxBufferSize = sizeof(uart1RxBuffer),
82 #endif
83 #ifdef USE_UART2
85 .device = UARTDEV_2,
86 .reg = USART2,
87 .rxDMAResource = (dmaResource_t *)UART2_RX_DMA_CHANNEL,
88 .txDMAResource = (dmaResource_t *)UART2_TX_DMA_CHANNEL,
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,
95 .rxPriority = NVIC_PRIO_SERIALUART2,
96 .txBuffer = uart2TxBuffer,
97 .rxBuffer = uart2RxBuffer,
98 .txBufferSize = sizeof(uart2TxBuffer),
99 .rxBufferSize = sizeof(uart2RxBuffer),
101 #endif
102 #ifdef USE_UART3
104 .device = UARTDEV_3,
105 .reg = USART3,
106 .rxDMAResource = (dmaResource_t *)UART3_RX_DMA_CHANNEL,
107 .txDMAResource = (dmaResource_t *)UART3_TX_DMA_CHANNEL,
108 .rxPins = { { DEFIO_TAG_E(PB11) }, { DEFIO_TAG_E(PD9) }, { DEFIO_TAG_E(PC11) } },
109 .txPins = { { DEFIO_TAG_E(PB10) }, { DEFIO_TAG_E(PD8) }, { DEFIO_TAG_E(PC10) } },
110 //.af = GPIO_AF_USART3,
111 .rcc = RCC_APB1(USART3),
112 .irqn = USART3_IRQn,
113 .txPriority = NVIC_PRIO_SERIALUART3,
114 .rxPriority = NVIC_PRIO_SERIALUART3,
115 .txBuffer = uart3TxBuffer,
116 .rxBuffer = uart3RxBuffer,
117 .txBufferSize = sizeof(uart3TxBuffer),
118 .rxBufferSize = sizeof(uart3RxBuffer),
120 #endif
123 void uartDmaIrqHandler(dmaChannelDescriptor_t* descriptor)
125 uartPort_t *s = (uartPort_t*)(descriptor->userParam);
126 DMA_CLEAR_FLAG(descriptor, DMA_IT_TCIF);
127 xDMA_Cmd(descriptor->ref, DISABLE); // XXX F1 needs this!!!
129 uartTryStartTxDMA(s);
132 // XXX Should serialUART be consolidated?
134 uartPort_t *serialUART(UARTDevice_e device, uint32_t baudRate, portMode_e mode, portOptions_e options)
136 uartDevice_t *uartdev = uartDevmap[device];
137 if (!uartdev) {
138 return NULL;
141 uartPort_t *s = &uartdev->port;
143 s->port.vTable = uartVTable;
145 s->port.baudRate = baudRate;
147 const uartHardware_t *hardware = uartdev->hardware;
149 s->USARTx = hardware->reg;
151 s->port.rxBuffer = hardware->rxBuffer;
152 s->port.txBuffer = hardware->txBuffer;
153 s->port.rxBufferSize = hardware->rxBufferSize;
154 s->port.txBufferSize = hardware->txBufferSize;
156 RCC_ClockCmd(hardware->rcc, ENABLE);
158 uartConfigureDma(uartdev);
160 IO_t rxIO = IOGetByTag(uartdev->rx.pin);
161 IO_t txIO = IOGetByTag(uartdev->tx.pin);
163 if (options & SERIAL_BIDIR) {
164 IOInit(txIO, OWNER_SERIAL_TX, RESOURCE_INDEX(device));
165 IOConfigGPIO(txIO, ((options & SERIAL_BIDIR_PP) || (options & SERIAL_BIDIR_PP_PD)) ? IOCFG_AF_PP : IOCFG_AF_OD);
166 } else {
167 if (mode & MODE_TX) {
168 IOInit(txIO, OWNER_SERIAL_TX, RESOURCE_INDEX(device));
169 IOConfigGPIO(txIO, IOCFG_AF_PP);
172 if (mode & MODE_RX) {
173 IOInit(rxIO, OWNER_SERIAL_RX, RESOURCE_INDEX(device));
174 IOConfigGPIO(rxIO, IOCFG_IPU);
178 // RX/TX Interrupt
179 if (!hardware->rxDMAResource || !hardware->txDMAResource) {
180 NVIC_InitTypeDef NVIC_InitStructure;
182 NVIC_InitStructure.NVIC_IRQChannel = hardware->irqn;
183 NVIC_InitStructure.NVIC_IRQChannelPreemptionPriority = NVIC_PRIORITY_BASE(hardware->rxPriority);
184 NVIC_InitStructure.NVIC_IRQChannelSubPriority = NVIC_PRIORITY_SUB(hardware->rxPriority);
185 NVIC_InitStructure.NVIC_IRQChannelCmd = ENABLE;
186 NVIC_Init(&NVIC_InitStructure);
189 return s;
192 void uartIrqHandler(uartPort_t *s)
194 uint16_t SR = s->USARTx->SR;
196 if (SR & USART_FLAG_RXNE && !s->rxDMAResource) {
197 // If we registered a callback, pass crap there
198 if (s->port.rxCallback) {
199 s->port.rxCallback(s->USARTx->DR, s->port.rxCallbackData);
200 } else {
201 s->port.rxBuffer[s->port.rxBufferHead++] = s->USARTx->DR;
202 if (s->port.rxBufferHead >= s->port.rxBufferSize) {
203 s->port.rxBufferHead = 0;
207 if (SR & USART_FLAG_TXE) {
208 if (s->port.txBufferTail != s->port.txBufferHead) {
209 s->USARTx->DR = s->port.txBuffer[s->port.txBufferTail++];
210 if (s->port.txBufferTail >= s->port.txBufferSize) {
211 s->port.txBufferTail = 0;
213 } else {
214 USART_ITConfig(s->USARTx, USART_IT_TXE, DISABLE);
217 if (SR & USART_FLAG_IDLE) {
218 if (s->port.idleCallback) {
219 s->port.idleCallback();
222 const uint32_t read_to_clear = s->USARTx->DR;
223 (void) read_to_clear;
226 #endif // USE_UART