Update FrSky SPI RX.md
[betaflight.git] / src / main / drivers / serial_uart_stm32f30x.c
blob65aedd3c44c301dcb9c558cfcae77fba9da51673
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 - Port baseflight STM32F10x to STM32F30x for cleanflight
25 * J. Ihlein - Code from FocusFlight32
26 * Bill Nesbitt - Code from AutoQuad
27 * Hamasaki/Timecop - Initial baseflight code
30 #include <stdbool.h>
31 #include <stdint.h>
33 #include "platform.h"
35 #ifdef USE_UART
37 #include "drivers/system.h"
38 #include "drivers/io.h"
39 #include "drivers/nvic.h"
40 #include "drivers/dma.h"
41 #include "drivers/rcc.h"
43 #include "drivers/serial.h"
44 #include "drivers/serial_uart.h"
45 #include "drivers/serial_uart_impl.h"
47 // XXX Will DMA eventually be configurable?
48 // XXX Do these belong here?
50 #ifdef USE_UART1_RX_DMA
51 # define UART1_RX_DMA DMA1_Channel5
52 #else
53 # define UART1_RX_DMA 0
54 #endif
56 #ifdef USE_UART1_TX_DMA
57 # define UART1_TX_DMA DMA1_Channel4
58 #else
59 # define UART1_TX_DMA 0
60 #endif
62 #ifdef USE_UART2_RX_DMA
63 # define UART2_RX_DMA DMA1_Channel6
64 #else
65 # define UART2_RX_DMA 0
66 #endif
68 #ifdef USE_UART2_TX_DMA
69 # define UART2_TX_DMA DMA1_Channel7
70 #else
71 # define UART2_TX_DMA 0
72 #endif
74 #ifdef USE_UART3_RX_DMA
75 # define UART3_RX_DMA DMA1_Channel3
76 #else
77 # define UART3_RX_DMA 0
78 #endif
80 #ifdef USE_UART3_TX_DMA
81 # define UART3_TX_DMA DMA1_Channel2
82 #else
83 # define UART3_TX_DMA 0
84 #endif
86 const uartHardware_t uartHardware[UARTDEV_COUNT] = {
87 #ifdef USE_UART1
89 .device = UARTDEV_1,
90 .reg = USART1,
91 .rxDMAChannel = UART1_RX_DMA,
92 .txDMAChannel = UART1_TX_DMA,
93 .rxPins = { { DEFIO_TAG_E(PA10) }, { DEFIO_TAG_E(PB7) }, { DEFIO_TAG_E(PC5) }, { DEFIO_TAG_E(PE1) } },
94 .txPins = { { DEFIO_TAG_E(PA9) }, { DEFIO_TAG_E(PB6) }, { DEFIO_TAG_E(PC4) }, { DEFIO_TAG_E(PE0) } },
95 .rcc = RCC_APB2(USART1),
96 .af = GPIO_AF_7,
97 .irqn = USART1_IRQn,
98 .txPriority = NVIC_PRIO_SERIALUART1_TXDMA,
99 .rxPriority = NVIC_PRIO_SERIALUART1_RXDMA,
101 #endif
103 #ifdef USE_UART2
105 .device = UARTDEV_2,
106 .reg = USART2,
107 .rxDMAChannel = UART2_RX_DMA,
108 .txDMAChannel = UART2_TX_DMA,
109 .rxPins = { { DEFIO_TAG_E(PA15) }, { DEFIO_TAG_E(PA3) }, { DEFIO_TAG_E(PB4) }, { DEFIO_TAG_E(PD6) } },
110 .txPins = { { DEFIO_TAG_E(PA14) }, { DEFIO_TAG_E(PA2) }, { DEFIO_TAG_E(PB3) }, { DEFIO_TAG_E(PD5) } },
111 .rcc = RCC_APB1(USART2),
112 .af = GPIO_AF_7,
113 .irqn = USART2_IRQn,
114 .txPriority = NVIC_PRIO_SERIALUART2_TXDMA,
115 .rxPriority = NVIC_PRIO_SERIALUART2_RXDMA,
117 #endif
119 #ifdef USE_UART3
121 .device = UARTDEV_3,
122 .reg = USART3,
123 .rxDMAChannel = UART3_RX_DMA,
124 .txDMAChannel = UART3_TX_DMA,
125 .rxPins = { { DEFIO_TAG_E(PB11) }, { DEFIO_TAG_E(PC11) }, { DEFIO_TAG_E(PD9) } },
126 .txPins = { { DEFIO_TAG_E(PB10) }, { DEFIO_TAG_E(PC10) }, { DEFIO_TAG_E(PD8) } },
127 .rcc = RCC_APB1(USART3),
128 .af = GPIO_AF_7,
129 .irqn = USART3_IRQn,
130 .txPriority = NVIC_PRIO_SERIALUART3_TXDMA,
131 .rxPriority = NVIC_PRIO_SERIALUART3_RXDMA,
133 #endif
135 #ifdef USE_UART4
136 // UART4 XXX Not tested (yet!?) Need 303RC, e.g. LUX for testing
138 .device = UARTDEV_4,
139 .reg = UART4,
140 .rxDMAChannel = 0, // XXX UART4_RX_DMA !?
141 .txDMAChannel = 0, // XXX UART4_TX_DMA !?
142 .rxPins = { { DEFIO_TAG_E(PC11) } },
143 .txPins = { { DEFIO_TAG_E(PC10) } },
144 .rcc = RCC_APB1(UART4),
145 .af = GPIO_AF_5,
146 .irqn = UART4_IRQn,
147 .txPriority = NVIC_PRIO_SERIALUART4_TXDMA,
148 .rxPriority = NVIC_PRIO_SERIALUART4_RXDMA,
150 #endif
152 #ifdef USE_UART5
153 // UART5 XXX Not tested (yet!?) Need 303RC; e.g. LUX for testing
155 .device = UARTDEV_5,
156 .reg = UART5,
157 .rxDMAChannel = 0,
158 .txDMAChannel = 0,
159 .rxPins = { { DEFIO_TAG_E(PD2) } },
160 .txPins = { { DEFIO_TAG_E(PC12) } },
161 .rcc = RCC_APB1(UART5),
162 .af = GPIO_AF_5,
163 .irqn = UART5_IRQn,
164 .txPriority = NVIC_PRIO_SERIALUART5,
165 .rxPriority = NVIC_PRIO_SERIALUART5,
167 #endif
170 static void handleUsartTxDma(dmaChannelDescriptor_t* descriptor)
172 uartPort_t *s = (uartPort_t*)(descriptor->userParam);
173 DMA_CLEAR_FLAG(descriptor, DMA_IT_TCIF);
174 DMA_Cmd(descriptor->ref, DISABLE);
176 uartTryStartTxDMA(s);
179 void serialUARTInitIO(IO_t txIO, IO_t rxIO, portMode_e mode, portOptions_e options, uint8_t af, uint8_t index)
181 if ((options & SERIAL_BIDIR) && txIO) {
182 ioConfig_t ioCfg = IO_CONFIG(GPIO_Mode_AF, GPIO_Speed_50MHz,
183 ((options & SERIAL_INVERTED) || (options & SERIAL_BIDIR_PP)) ? GPIO_OType_PP : GPIO_OType_OD,
184 ((options & SERIAL_INVERTED) || (options & SERIAL_BIDIR_PP)) ? GPIO_PuPd_DOWN : GPIO_PuPd_UP
187 IOInit(txIO, OWNER_SERIAL_TX, RESOURCE_INDEX(index));
188 IOConfigGPIOAF(txIO, ioCfg, af);
190 if (!(options & SERIAL_INVERTED))
191 IOLo(txIO); // OpenDrain output should be inactive
192 } else {
193 ioConfig_t ioCfg = IO_CONFIG(GPIO_Mode_AF, GPIO_Speed_50MHz, GPIO_OType_PP, (options & SERIAL_INVERTED) ? GPIO_PuPd_DOWN : GPIO_PuPd_UP);
194 if ((mode & MODE_TX) && txIO) {
195 IOInit(txIO, OWNER_SERIAL_TX, RESOURCE_INDEX(index));
196 IOConfigGPIOAF(txIO, ioCfg, af);
199 if ((mode & MODE_RX) && rxIO) {
200 IOInit(rxIO, OWNER_SERIAL_RX, RESOURCE_INDEX(index));
201 IOConfigGPIOAF(rxIO, ioCfg, af);
206 // XXX Should serialUART be consolidated?
208 uartPort_t *serialUART(UARTDevice_e device, uint32_t baudRate, portMode_e mode, portOptions_e options)
210 uartDevice_t *uartDev = uartDevmap[device];
211 if (!uartDev) {
212 return NULL;
215 uartPort_t *s = &(uartDev->port);
216 s->port.vTable = uartVTable;
218 s->port.baudRate = baudRate;
220 s->port.rxBuffer = uartDev->rxBuffer;
221 s->port.txBuffer = uartDev->txBuffer;
222 s->port.rxBufferSize = sizeof(uartDev->rxBuffer);
223 s->port.txBufferSize = sizeof(uartDev->txBuffer);
225 const uartHardware_t *hardware = uartDev->hardware;
227 s->USARTx = hardware->reg;
229 RCC_ClockCmd(hardware->rcc, ENABLE);
231 if (hardware->rxDMAChannel) {
232 dmaInit(dmaGetIdentifier(hardware->rxDMAChannel), OWNER_SERIAL_RX, RESOURCE_INDEX(device));
233 s->rxDMAChannel = hardware->rxDMAChannel;
234 s->rxDMAPeripheralBaseAddr = (uint32_t)&s->USARTx->RDR;
237 if (hardware->txDMAChannel) {
238 const dmaIdentifier_e identifier = dmaGetIdentifier(hardware->txDMAChannel);
239 dmaInit(identifier, OWNER_SERIAL_TX, RESOURCE_INDEX(device));
240 dmaSetHandler(identifier, handleUsartTxDma, hardware->txPriority, (uint32_t)s);
241 s->txDMAChannel = hardware->txDMAChannel;
242 s->txDMAPeripheralBaseAddr = (uint32_t)&s->USARTx->TDR;
245 serialUARTInitIO(IOGetByTag(uartDev->tx.pin), IOGetByTag(uartDev->rx.pin), mode, options, hardware->af, device);
247 if (!s->rxDMAChannel || !s->txDMAChannel) {
248 NVIC_InitTypeDef NVIC_InitStructure;
250 NVIC_InitStructure.NVIC_IRQChannel = hardware->irqn;
251 NVIC_InitStructure.NVIC_IRQChannelPreemptionPriority = NVIC_PRIORITY_BASE(hardware->rxPriority);
252 NVIC_InitStructure.NVIC_IRQChannelSubPriority = NVIC_PRIORITY_SUB(hardware->rxPriority);
253 NVIC_InitStructure.NVIC_IRQChannelCmd = ENABLE;
254 NVIC_Init(&NVIC_InitStructure);
257 return s;
260 void uartIrqHandler(uartPort_t *s)
262 uint32_t ISR = s->USARTx->ISR;
264 if (!s->rxDMAChannel && (ISR & USART_FLAG_RXNE)) {
265 if (s->port.rxCallback) {
266 s->port.rxCallback(s->USARTx->RDR, s->port.rxCallbackData);
267 } else {
268 s->port.rxBuffer[s->port.rxBufferHead++] = s->USARTx->RDR;
269 if (s->port.rxBufferHead >= s->port.rxBufferSize) {
270 s->port.rxBufferHead = 0;
275 if (!s->txDMAChannel && (ISR & USART_FLAG_TXE)) {
276 if (s->port.txBufferTail != s->port.txBufferHead) {
277 USART_SendData(s->USARTx, s->port.txBuffer[s->port.txBufferTail++]);
278 if (s->port.txBufferTail >= s->port.txBufferSize) {
279 s->port.txBufferTail = 0;
281 } else {
282 USART_ITConfig(s->USARTx, USART_IT_TXE, DISABLE);
286 if (ISR & USART_FLAG_ORE)
288 USART_ClearITPendingBit (s->USARTx, USART_IT_ORE);
291 #endif // USE_UART