Merge pull request #11297 from SteveCEvans/baro_state
[betaflight.git] / src / main / drivers / serial_uart_stm32f30x.c
blobdf77a7c8415aaabc7580557b0b2e47d1fa4b0f95
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 #ifdef USE_UART4_RX_DMA
87 # define UART4_RX_DMA DMA2_Channel3
88 #else
89 # define UART4_RX_DMA 0
90 #endif
92 #ifdef USE_UART4_TX_DMA
93 # define UART4_TX_DMA DMA2_Channel5
94 #else
95 # define UART4_TX_DMA 0
96 #endif
98 const uartHardware_t uartHardware[UARTDEV_COUNT] = {
99 #ifdef USE_UART1
101 .device = UARTDEV_1,
102 .reg = USART1,
103 .rxDMAResource = (dmaResource_t *)UART1_RX_DMA,
104 .txDMAResource = (dmaResource_t *)UART1_TX_DMA,
105 .rxPins = { { DEFIO_TAG_E(PA10) }, { DEFIO_TAG_E(PB7) }, { DEFIO_TAG_E(PC5) }, { DEFIO_TAG_E(PE1) } },
106 .txPins = { { DEFIO_TAG_E(PA9) }, { DEFIO_TAG_E(PB6) }, { DEFIO_TAG_E(PC4) }, { DEFIO_TAG_E(PE0) } },
107 .rcc = RCC_APB2(USART1),
108 .af = GPIO_AF_7,
109 .irqn = USART1_IRQn,
110 .txPriority = NVIC_PRIO_SERIALUART1_TXDMA,
111 .rxPriority = NVIC_PRIO_SERIALUART1_RXDMA,
112 .txBuffer = uart1TxBuffer,
113 .rxBuffer = uart1RxBuffer,
114 .txBufferSize = sizeof(uart1TxBuffer),
115 .rxBufferSize = sizeof(uart1RxBuffer),
117 #endif
119 #ifdef USE_UART2
121 .device = UARTDEV_2,
122 .reg = USART2,
123 .rxDMAResource = (dmaResource_t *)UART2_RX_DMA,
124 .txDMAResource = (dmaResource_t *)UART2_TX_DMA,
125 .rxPins = { { DEFIO_TAG_E(PA15) }, { DEFIO_TAG_E(PA3) }, { DEFIO_TAG_E(PB4) }, { DEFIO_TAG_E(PD6) } },
126 .txPins = { { DEFIO_TAG_E(PA14) }, { DEFIO_TAG_E(PA2) }, { DEFIO_TAG_E(PB3) }, { DEFIO_TAG_E(PD5) } },
127 .rcc = RCC_APB1(USART2),
128 .af = GPIO_AF_7,
129 .irqn = USART2_IRQn,
130 .txPriority = NVIC_PRIO_SERIALUART2_TXDMA,
131 .rxPriority = NVIC_PRIO_SERIALUART2_RXDMA,
132 .txBuffer = uart2TxBuffer,
133 .rxBuffer = uart2RxBuffer,
134 .txBufferSize = sizeof(uart2TxBuffer),
135 .rxBufferSize = sizeof(uart2RxBuffer),
137 #endif
139 #ifdef USE_UART3
141 .device = UARTDEV_3,
142 .reg = USART3,
143 .rxDMAResource = (dmaResource_t *)UART3_RX_DMA,
144 .txDMAResource = (dmaResource_t *)UART3_TX_DMA,
145 .rxPins = { { DEFIO_TAG_E(PB11) }, { DEFIO_TAG_E(PC11) }, { DEFIO_TAG_E(PD9) } },
146 .txPins = { { DEFIO_TAG_E(PB10) }, { DEFIO_TAG_E(PC10) }, { DEFIO_TAG_E(PD8) } },
147 .rcc = RCC_APB1(USART3),
148 .af = GPIO_AF_7,
149 .irqn = USART3_IRQn,
150 .txPriority = NVIC_PRIO_SERIALUART3_TXDMA,
151 .rxPriority = NVIC_PRIO_SERIALUART3_RXDMA,
152 .txBuffer = uart3TxBuffer,
153 .rxBuffer = uart3RxBuffer,
154 .txBufferSize = sizeof(uart3TxBuffer),
155 .rxBufferSize = sizeof(uart3RxBuffer),
157 #endif
159 #ifdef USE_UART4
160 // UART4 XXX Not tested (yet!?) Need 303RC, e.g. LUX for testing
162 .device = UARTDEV_4,
163 .reg = UART4,
164 .rxDMAResource = (dmaResource_t *)0, // XXX UART4_RX_DMA !?
165 .txDMAResource = (dmaResource_t *)0, // XXX UART4_TX_DMA !?
166 .rxPins = { { DEFIO_TAG_E(PC11) } },
167 .txPins = { { DEFIO_TAG_E(PC10) } },
168 .rcc = RCC_APB1(UART4),
169 .af = GPIO_AF_5,
170 .irqn = UART4_IRQn,
171 .txPriority = NVIC_PRIO_SERIALUART4_TXDMA,
172 .rxPriority = NVIC_PRIO_SERIALUART4_RXDMA,
173 .txBuffer = uart4TxBuffer,
174 .rxBuffer = uart4RxBuffer,
175 .txBufferSize = sizeof(uart4TxBuffer),
176 .rxBufferSize = sizeof(uart4RxBuffer),
178 #endif
180 #ifdef USE_UART5
181 // UART5 XXX Not tested (yet!?) Need 303RC; e.g. LUX for testing
183 .device = UARTDEV_5,
184 .reg = UART5,
185 .rxDMAResource = (dmaResource_t *)0,
186 .txDMAResource = (dmaResource_t *)0,
187 .rxPins = { { DEFIO_TAG_E(PD2) } },
188 .txPins = { { DEFIO_TAG_E(PC12) } },
189 .rcc = RCC_APB1(UART5),
190 .af = GPIO_AF_5,
191 .irqn = UART5_IRQn,
192 .txPriority = NVIC_PRIO_SERIALUART5,
193 .rxPriority = NVIC_PRIO_SERIALUART5,
194 .txBuffer = uart5TxBuffer,
195 .rxBuffer = uart5RxBuffer,
196 .txBufferSize = sizeof(uart5TxBuffer),
197 .rxBufferSize = sizeof(uart5RxBuffer),
199 #endif
202 void uartDmaIrqHandler(dmaChannelDescriptor_t* descriptor)
204 uartPort_t *s = (uartPort_t*)(descriptor->userParam);
205 DMA_CLEAR_FLAG(descriptor, DMA_IT_TCIF);
206 xDMA_Cmd(descriptor->ref, DISABLE);
208 uartTryStartTxDMA(s);
211 void serialUARTInitIO(IO_t txIO, IO_t rxIO, portMode_e mode, portOptions_e options, uint8_t af, uint8_t index)
213 if ((options & SERIAL_BIDIR) && txIO) {
214 ioConfig_t ioCfg = IO_CONFIG(GPIO_Mode_AF, GPIO_Speed_50MHz,
215 ((options & SERIAL_INVERTED) || (options & SERIAL_BIDIR_PP) || (options & SERIAL_BIDIR_PP_PD)) ? GPIO_OType_PP : GPIO_OType_OD,
216 ((options & SERIAL_INVERTED) || (options & SERIAL_BIDIR_PP_PD)) ? GPIO_PuPd_DOWN : GPIO_PuPd_UP
219 IOInit(txIO, OWNER_SERIAL_TX, RESOURCE_INDEX(index));
220 IOConfigGPIOAF(txIO, ioCfg, af);
222 if (!(options & SERIAL_INVERTED))
223 IOLo(txIO); // OpenDrain output should be inactive
224 } else {
225 ioConfig_t ioCfg = IO_CONFIG(GPIO_Mode_AF, GPIO_Speed_50MHz, GPIO_OType_PP, (options & SERIAL_INVERTED) ? GPIO_PuPd_DOWN : GPIO_PuPd_UP);
226 if ((mode & MODE_TX) && txIO) {
227 IOInit(txIO, OWNER_SERIAL_TX, RESOURCE_INDEX(index));
228 IOConfigGPIOAF(txIO, ioCfg, af);
231 if ((mode & MODE_RX) && rxIO) {
232 IOInit(rxIO, OWNER_SERIAL_RX, RESOURCE_INDEX(index));
233 IOConfigGPIOAF(rxIO, ioCfg, af);
238 // XXX Should serialUART be consolidated?
240 uartPort_t *serialUART(UARTDevice_e device, uint32_t baudRate, portMode_e mode, portOptions_e options)
242 uartDevice_t *uartDev = uartDevmap[device];
243 if (!uartDev) {
244 return NULL;
247 uartPort_t *s = &(uartDev->port);
248 s->port.vTable = uartVTable;
250 s->port.baudRate = baudRate;
252 const uartHardware_t *hardware = uartDev->hardware;
254 s->USARTx = hardware->reg;
257 s->port.rxBuffer = hardware->rxBuffer;
258 s->port.txBuffer = hardware->txBuffer;
259 s->port.rxBufferSize = hardware->rxBufferSize;
260 s->port.txBufferSize = hardware->txBufferSize;
262 RCC_ClockCmd(hardware->rcc, ENABLE);
264 uartConfigureDma(uartDev);
266 serialUARTInitIO(IOGetByTag(uartDev->tx.pin), IOGetByTag(uartDev->rx.pin), mode, options, hardware->af, device);
268 if (!s->rxDMAResource || !s->txDMAResource) {
269 NVIC_InitTypeDef NVIC_InitStructure;
271 NVIC_InitStructure.NVIC_IRQChannel = hardware->irqn;
272 NVIC_InitStructure.NVIC_IRQChannelPreemptionPriority = NVIC_PRIORITY_BASE(hardware->rxPriority);
273 NVIC_InitStructure.NVIC_IRQChannelSubPriority = NVIC_PRIORITY_SUB(hardware->rxPriority);
274 NVIC_InitStructure.NVIC_IRQChannelCmd = ENABLE;
275 NVIC_Init(&NVIC_InitStructure);
278 return s;
281 void uartIrqHandler(uartPort_t *s)
283 uint32_t ISR = s->USARTx->ISR;
285 if (!s->rxDMAResource && (ISR & USART_FLAG_RXNE)) {
286 if (s->port.rxCallback) {
287 s->port.rxCallback(s->USARTx->RDR, s->port.rxCallbackData);
288 } else {
289 s->port.rxBuffer[s->port.rxBufferHead++] = s->USARTx->RDR;
290 if (s->port.rxBufferHead >= s->port.rxBufferSize) {
291 s->port.rxBufferHead = 0;
296 if (!s->txDMAResource && (ISR & USART_FLAG_TXE)) {
297 if (s->port.txBufferTail != s->port.txBufferHead) {
298 USART_SendData(s->USARTx, s->port.txBuffer[s->port.txBufferTail++]);
299 if (s->port.txBufferTail >= s->port.txBufferSize) {
300 s->port.txBufferTail = 0;
302 } else {
303 USART_ITConfig(s->USARTx, USART_IT_TXE, DISABLE);
307 if (ISR & USART_FLAG_ORE)
309 USART_ClearITPendingBit(s->USARTx, USART_IT_ORE);
312 if (ISR & USART_FLAG_IDLE) {
313 if (s->port.idleCallback) {
314 s->port.idleCallback();
317 USART_ClearITPendingBit(s->USARTx, USART_IT_IDLE);
320 #endif // USE_UART