By default mark OSD element as rendered in case it's in the off blink state (#14188...
[betaflight.git] / src / platform / common / stm32 / serial_uart_hw.c
blob74e32147cf55c2037039bbb4c9aa372b91e3056e
1 /*
2 * This file is part of Betaflight.
4 * Betaflight is free software. You can redistribute this software
5 * and/or modify this software under the terms of the GNU General
6 * Public License as published by the Free Software Foundation,
7 * either version 3 of the License, or (at your option) any later
8 * version.
10 * Betaflight is distributed in the hope that it will be useful,
11 * but WITHOUT ANY WARRANTY; without even the implied warranty of
12 * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.
14 * See the GNU General Public License for more details.
16 * You should have received a copy of the GNU General Public
17 * License along with this software.
19 * If not, see <http://www.gnu.org/licenses/>.
23 * Common UART hardware functions
26 #include <stdbool.h>
27 #include <stdint.h>
29 #include "platform.h"
31 #if defined(USE_UART)
33 #include "build/build_config.h"
35 #include "drivers/nvic.h"
36 #include "drivers/rcc.h"
37 #include "drivers/inverter.h"
38 #include "drivers/serial.h"
39 #include "drivers/serial_impl.h"
40 #include "drivers/serial_uart.h"
41 #include "drivers/serial_uart_impl.h"
42 #include "drivers/dma.h"
43 #include "drivers/dma_reqmap.h"
45 #include "pg/serial_uart.h"
47 // TODO: split this function into mcu-specific UART files ?
48 static void enableRxIrq(const uartHardware_t *hardware)
50 #if defined(USE_HAL_DRIVER)
51 HAL_NVIC_SetPriority(hardware->irqn, NVIC_PRIORITY_BASE(hardware->rxPriority), NVIC_PRIORITY_SUB(hardware->rxPriority));
52 HAL_NVIC_EnableIRQ(hardware->irqn);
53 #elif defined(STM32F4)
54 NVIC_InitTypeDef NVIC_InitStructure;
55 NVIC_InitStructure.NVIC_IRQChannel = hardware->irqn;
56 NVIC_InitStructure.NVIC_IRQChannelPreemptionPriority = NVIC_PRIORITY_BASE(hardware->rxPriority);
57 NVIC_InitStructure.NVIC_IRQChannelSubPriority = NVIC_PRIORITY_SUB(hardware->rxPriority);
58 NVIC_InitStructure.NVIC_IRQChannelCmd = ENABLE;
59 NVIC_Init(&NVIC_InitStructure);
60 #elif defined(AT32F4)
61 nvic_irq_enable(hardware->irqn, NVIC_PRIORITY_BASE(hardware->rxPriority), NVIC_PRIORITY_SUB(hardware->rxPriority));
62 #elif defined(APM32F4)
63 DAL_NVIC_SetPriority(hardware->irqn, NVIC_PRIORITY_BASE(hardware->rxPriority), NVIC_PRIORITY_SUB(hardware->rxPriority));
64 DAL_NVIC_EnableIRQ(hardware->irqn);
65 #else
66 # error "Unhandled MCU type"
67 #endif
70 uartPort_t *serialUART(uartDevice_t *uartdev, uint32_t baudRate, portMode_e mode, portOptions_e options)
72 uartPort_t *s = &uartdev->port;
74 const uartHardware_t *hardware = uartdev->hardware;
76 s->port.vTable = uartVTable;
78 s->port.baudRate = baudRate;
80 s->port.rxBuffer = hardware->rxBuffer;
81 s->port.txBuffer = hardware->txBuffer;
82 s->port.rxBufferSize = hardware->rxBufferSize;
83 s->port.txBufferSize = hardware->txBufferSize;
85 s->USARTx = hardware->reg;
87 #ifdef USE_HAL_DRIVER
88 s->Handle.Instance = hardware->reg;
89 #endif
91 s->checkUsartTxOutput = checkUsartTxOutput;
93 if (hardware->rcc) {
94 RCC_ClockCmd(hardware->rcc, ENABLE);
97 #ifdef USE_DMA
98 uartConfigureDma(uartdev);
99 s->txDMAEmpty = true;
100 #endif
102 IO_t txIO = IOGetByTag(uartdev->tx.pin);
103 IO_t rxIO = IOGetByTag(uartdev->rx.pin);
105 uartdev->txPinState = TX_PIN_IGNORE;
107 const serialPortIdentifier_e identifier = s->port.identifier;
109 const int ownerIndex = serialOwnerIndex(identifier);
110 const resourceOwner_e ownerTxRx = serialOwnerTxRx(identifier); // rx is always +1
112 // prepare AF modes
113 #if UART_TRAIT_AF_PORT
114 uint8_t rxAf = hardware->af;
115 uint8_t txAf = hardware->af;
116 #elif UART_TRAIT_AF_PIN
117 uint8_t rxAf = uartdev->rx.af;
118 uint8_t txAf = uartdev->tx.af;
119 #endif
121 // Note: F4 did not check txIO before refactoring
122 if ((options & SERIAL_BIDIR) && txIO) {
123 // pushPull / openDrain
124 const bool pushPull = serialOptions_pushPull(options);
125 // pull direction
126 const serialPullMode_t pull = serialOptions_pull(options);
127 #if defined(STM32F7) || defined(STM32H7) || defined(STM32G4) || defined(APM32F4)
128 // Note: APM32F4 is different from STM32F4 here
129 const ioConfig_t ioCfg = IO_CONFIG(
130 pushPull ? GPIO_MODE_AF_PP : GPIO_MODE_AF_OD,
131 GPIO_SPEED_FREQ_HIGH,
132 ((const unsigned[]){GPIO_NOPULL, GPIO_PULLDOWN, GPIO_PULLUP})[pull]
134 #elif defined(AT32F4)
135 const ioConfig_t ioCfg = IO_CONFIG(
136 GPIO_MODE_MUX,
137 GPIO_DRIVE_STRENGTH_STRONGER,
138 pushPull ? GPIO_OUTPUT_PUSH_PULL : GPIO_OUTPUT_OPEN_DRAIN,
139 ((const gpio_pull_type[]){GPIO_PULL_NONE, GPIO_PULL_DOWN, GPIO_PULL_UP})[pull]
141 #elif defined(STM32F4)
142 // UART inverter is not supproted on F4, but keep it in line with other CPUs
143 // External inverter in bidir mode would be quite problematic anyway
144 const ioConfig_t ioCfg = IO_CONFIG(
145 GPIO_Mode_AF,
146 GPIO_Low_Speed, // TODO: should use stronger drive
147 pushPull ? GPIO_OType_PP : GPIO_OType_OD,
148 ((const unsigned[]){GPIO_PuPd_NOPULL, GPIO_PuPd_DOWN, GPIO_PuPd_UP})[pull]
150 #endif
151 IOInit(txIO, ownerTxRx, ownerIndex);
152 IOConfigGPIOAF(txIO, ioCfg, txAf);
153 } else {
154 if ((mode & MODE_TX) && txIO) {
155 IOInit(txIO, ownerTxRx, ownerIndex);
157 if (options & SERIAL_CHECK_TX) {
158 #if defined(STM32F7)
159 // see https://github.com/betaflight/betaflight/pull/13021
160 // Allow for F7 UART idle preamble to be sent on startup
161 uartdev->txPinState = TX_PIN_MONITOR;
162 // Switch TX to UART output whilst UART sends idle preamble
163 checkUsartTxOutput(s);
164 #else
165 uartdev->txPinState = TX_PIN_ACTIVE;
166 // Switch TX to an input with pullup so it's state can be monitored
167 uartTxMonitor(s);
168 #endif
169 } else {
170 #if defined(STM32F4) || defined(APM32F4)
171 // TODO: no need for pullup on TX only pin
172 const ioConfig_t ioCfg = IOCFG_AF_PP_UP;
173 #else
174 const ioConfig_t ioCfg = IOCFG_AF_PP;
175 #endif
176 IOConfigGPIOAF(txIO, ioCfg, txAf);
180 if ((mode & MODE_RX) && rxIO) {
181 #if defined(STM32F4) || defined(APM32F4)
182 // no inversion possible on F4, always use pullup
183 const ioConfig_t ioCfg = IOCFG_AF_PP_UP;
184 #else
185 // TODO: pullup/pulldown should be enabled for RX (based on inversion)
186 const ioConfig_t ioCfg = IOCFG_AF_PP;
187 #endif
188 IOInit(rxIO, ownerTxRx + 1, ownerIndex);
189 IOConfigGPIOAF(rxIO, ioCfg, rxAf);
193 if (true
194 #ifdef USE_DMA
195 && !s->rxDMAResource // do not enable IRW if using rxDMA
196 #endif
198 enableRxIrq(hardware);
200 return s;
203 // called from platform-specific uartReconfigure
204 void uartConfigureExternalPinInversion(uartPort_t *uartPort)
206 #if !defined(USE_INVERTER)
207 UNUSED(uartPort);
208 #else
209 const bool inverted = uartPort->port.options & SERIAL_INVERTED;
210 enableInverter(uartPort->port.identifier, inverted);
211 #endif
214 #ifdef USE_DMA
215 void uartConfigureDma(uartDevice_t *uartdev)
217 uartPort_t *uartPort = &(uartdev->port);
218 const uartHardware_t *hardware = uartdev->hardware;
220 #ifdef USE_DMA_SPEC
221 const serialPortIdentifier_e uartPortIdentifier = hardware->identifier;
222 const uartDeviceIdx_e uartDeviceIdx = uartDeviceIdxFromIdentifier(uartPortIdentifier);
223 if (uartDeviceIdx == UARTDEV_INVALID) {
224 return;
226 const int resourceIdx = serialResourceIndex(uartPortIdentifier);
227 const int ownerIndex = serialOwnerIndex(uartPortIdentifier);
228 const resourceOwner_e ownerTxRx = serialOwnerTxRx(uartPortIdentifier); // rx is always +1
230 const dmaChannelSpec_t *dmaChannelSpec;
231 const serialUartConfig_t *cfg = serialUartConfig(resourceIdx);
232 if (!cfg) {
233 return;
235 if (cfg->txDmaopt != DMA_OPT_UNUSED) {
236 dmaChannelSpec = dmaGetChannelSpecByPeripheral(DMA_PERIPH_UART_TX, uartDeviceIdx, cfg->txDmaopt);
237 if (dmaChannelSpec) {
238 uartPort->txDMAResource = dmaChannelSpec->ref;
239 #if DMA_TRAIT_CHANNEL
240 uartPort->txDMAChannel = dmaChannelSpec->channel;
241 #elif DMA_TRAIT_MUX
242 uartPort->txDMAMuxId = dmaChannelSpec->dmaMuxId;
243 #endif
247 if (cfg->rxDmaopt != DMA_OPT_UNUSED) {
248 dmaChannelSpec = dmaGetChannelSpecByPeripheral(DMA_PERIPH_UART_RX, uartDeviceIdx, cfg->txDmaopt);
249 if (dmaChannelSpec) {
250 uartPort->rxDMAResource = dmaChannelSpec->ref;
251 #if DMA_TRAIT_CHANNEL
252 uartPort->rxDMAChannel = dmaChannelSpec->channel;
253 #elif DMA_TRAIT_MUX
254 uartPort->rxDMAMuxId = dmaChannelSpec->dmaMuxId;
255 #endif
258 #else /* USE_DMA_SPEC */
259 // Non USE_DMA_SPEC does not support configurable ON/OFF of UART DMA
261 if (hardware->rxDMAResource) {
262 uartPort->rxDMAResource = hardware->rxDMAResource;
263 #if DMA_TRAIT_CHANNEL
264 uartPort->rxDMAChannel = hardware->rxDMAChannel;
265 #elif DMA_TRAIT_MUX
266 uartPort->rxDMAMuxId = hardware->rxDMAMuxId;
267 #endif
270 if (hardware->txDMAResource) {
271 uartPort->txDMAResource = hardware->txDMAResource;
272 #if DMA_TRAIT_CHANNEL
273 uartPort->txDMAChannel = hardware->txDMAChannel;
274 #elif DMA_TRAIT_MUX
275 uartPort->txDMAMuxId = hardware->txDMAMuxId;
276 #endif
278 #endif /* USE_DMA_SPEC */
280 if (uartPort->txDMAResource) {
281 const dmaIdentifier_e identifier = dmaGetIdentifier(uartPort->txDMAResource);
282 if (dmaAllocate(identifier, ownerTxRx, ownerIndex)) {
283 dmaEnable(identifier);
284 #if DMA_TRAIT_MUX
285 dmaMuxEnable(identifier, uartPort->txDMAMuxId);
286 #endif
287 dmaSetHandler(identifier, uartDmaIrqHandler, hardware->txPriority, (uint32_t)uartdev);
288 uartPort->txDMAPeripheralBaseAddr = (uint32_t)&UART_REG_TXD(hardware->reg);
292 if (uartPort->rxDMAResource) {
293 const dmaIdentifier_e identifier = dmaGetIdentifier(uartPort->rxDMAResource);
294 if (dmaAllocate(identifier, ownerTxRx + 1, ownerIndex)) {
295 dmaEnable(identifier);
296 #if DMA_TRAIT_MUX
297 dmaMuxEnable(identifier, uartPort->rxDMAMuxId);
298 #endif
299 uartPort->rxDMAPeripheralBaseAddr = (uint32_t)&UART_REG_RXD(hardware->reg);
303 #endif
305 void uartEnableTxInterrupt(uartPort_t *uartPort)
307 #if defined(USE_HAL_DRIVER)
308 __HAL_UART_ENABLE_IT(&uartPort->Handle, UART_IT_TXE);
309 #elif defined(USE_ATBSP_DRIVER)
310 usart_interrupt_enable(uartPort->USARTx, USART_TDBE_INT, TRUE);
311 #else
312 USART_ITConfig(uartPort->USARTx, USART_IT_TXE, ENABLE);
313 #endif
316 #endif /* USE_UART */