static void usartConfigurePinInversion(uartPort_t *uartPort) { #if !defined(INVERTER) && !defined(STM32F303xC) UNUSED(uartPort); #else bool inverted = uartPort->port.options & SERIAL_INVERTED; #ifdef INVERTER if (inverted && uartPort->USARTx == INVERTER_USART) { // Enable hardware inverter if available. INVERTER_ON; } #endif #ifdef STM32F303xC uint32_t inversionPins = 0; if (uartPort->port.mode & MODE_TX) { inversionPins |= USART_InvPin_Tx; } if (uartPort->port.mode & MODE_RX) { inversionPins |= USART_InvPin_Rx; } USART_InvPinCmd(uartPort->USARTx, inversionPins, inverted ? ENABLE : DISABLE); #endif #endif }
static void usartConfigurePinInversion(uartPort_t *uartPort) { #if !defined(INVERTER) && !defined(STM32F303xC) UNUSED(uartPort); #endif #ifdef INVERTER if (uartPort->port.inversion == SERIAL_INVERTED && uartPort->USARTx == INVERTER_USART) { // Enable hardware inverter if available. INVERTER_ON; } #endif #ifdef STM32F303xC uint32_t inversionPins = 0; if (uartPort->port.mode & MODE_TX) { inversionPins |= USART_InvPin_Tx; } if (uartPort->port.mode & MODE_RX) { inversionPins |= USART_InvPin_Rx; } // Note: inversion when using MODE_BIDIR not supported yet. USART_InvPinCmd(uartPort->USARTx, inversionPins, uartPort->port.inversion == SERIAL_INVERTED ? ENABLE : DISABLE); #endif }
/** * Initialise a single USART device */ int32_t PIOS_USART_Init(uintptr_t * usart_id, const struct pios_usart_cfg * cfg) { PIOS_DEBUG_Assert(usart_id); PIOS_DEBUG_Assert(cfg); struct pios_usart_dev * usart_dev; usart_dev = (struct pios_usart_dev *) PIOS_USART_alloc(); if (!usart_dev) goto out_fail; /* Bind the configuration to the device instance */ usart_dev->cfg = cfg; /* Map pins to USART function */ if (usart_dev->cfg->remap) { if (usart_dev->cfg->rx.gpio != 0) GPIO_PinAFConfig(usart_dev->cfg->rx.gpio, usart_dev->cfg->rx.pin_source, usart_dev->cfg->remap); if (usart_dev->cfg->tx.gpio != 0) GPIO_PinAFConfig(usart_dev->cfg->tx.gpio, usart_dev->cfg->tx.pin_source, usart_dev->cfg->remap); } /* Initialize the USART Rx and Tx pins */ if (usart_dev->cfg->rx.gpio != 0) GPIO_Init(usart_dev->cfg->rx.gpio, (GPIO_InitTypeDef *)&usart_dev->cfg->rx.init); if (usart_dev->cfg->tx.gpio != 0) GPIO_Init(usart_dev->cfg->tx.gpio, (GPIO_InitTypeDef *)&usart_dev->cfg->tx.init); /* Apply inversion and swap settings */ if (usart_dev->cfg->rx_invert == true) USART_InvPinCmd(usart_dev->cfg->regs, USART_InvPin_Rx, ENABLE); else USART_InvPinCmd(usart_dev->cfg->regs, USART_InvPin_Rx, DISABLE); if (usart_dev->cfg->tx_invert == true) USART_InvPinCmd(usart_dev->cfg->regs, USART_InvPin_Tx, ENABLE); else USART_InvPinCmd(usart_dev->cfg->regs, USART_InvPin_Tx, DISABLE); if (usart_dev->cfg->rxtx_swap == true) USART_SWAPPinCmd(usart_dev->cfg->regs, ENABLE); else USART_SWAPPinCmd(usart_dev->cfg->regs, DISABLE); if (usart_dev->cfg->single_wire == true) USART_HalfDuplexCmd(usart_dev->cfg->regs, ENABLE); else USART_HalfDuplexCmd(usart_dev->cfg->regs, DISABLE); /* Configure the USART */ USART_Init(usart_dev->cfg->regs, (USART_InitTypeDef *)&usart_dev->cfg->init); *usart_id = (uintptr_t)usart_dev; /* Configure USART Interrupts */ switch ((uint32_t)usart_dev->cfg->regs) { case (uint32_t)USART1: PIOS_USART_1_id = (uintptr_t)usart_dev; break; case (uint32_t)USART2: PIOS_USART_2_id = (uintptr_t)usart_dev; break; case (uint32_t)USART3: PIOS_USART_3_id = (uintptr_t)usart_dev; break; case (uint32_t)UART4: PIOS_UART_4_id = (uintptr_t)usart_dev; break; case (uint32_t)UART5: PIOS_UART_5_id = (uintptr_t)usart_dev; break; } NVIC_Init((NVIC_InitTypeDef *)&(usart_dev->cfg->irq.init)); USART_ITConfig(usart_dev->cfg->regs, USART_IT_RXNE, ENABLE); USART_ITConfig(usart_dev->cfg->regs, USART_IT_TXE, ENABLE); // FIXME XXX Clear / reset uart here - sends NUL char else /* Enable USART */ USART_Cmd(usart_dev->cfg->regs, ENABLE); return(0); out_fail: return(-1); }