static void uartReconfigure(uartPort_t *uartPort) { USART_InitTypeDef USART_InitStructure; USART_Cmd(uartPort->USARTx, DISABLE); USART_InitStructure.USART_BaudRate = uartPort->port.baudRate; USART_InitStructure.USART_WordLength = USART_WordLength_8b; USART_InitStructure.USART_StopBits = (uartPort->port.options & SERIAL_STOPBITS_2) ? USART_StopBits_2 : USART_StopBits_1; USART_InitStructure.USART_Parity = (uartPort->port.options & SERIAL_PARITY_EVEN) ? USART_Parity_Even : USART_Parity_No; USART_InitStructure.USART_HardwareFlowControl = USART_HardwareFlowControl_None; USART_InitStructure.USART_Mode = 0; if (uartPort->port.mode & MODE_RX) USART_InitStructure.USART_Mode |= USART_Mode_Rx; if (uartPort->port.mode & MODE_TX) USART_InitStructure.USART_Mode |= USART_Mode_Tx; USART_Init(uartPort->USARTx, &USART_InitStructure); usartConfigurePinInversion(uartPort); if(uartPort->port.options & SERIAL_BIDIR) USART_HalfDuplexCmd(uartPort->USARTx, ENABLE); else USART_HalfDuplexCmd(uartPort->USARTx, DISABLE); USART_Cmd(uartPort->USARTx, ENABLE); }
static void uartReconfigure(uartPort_t *uartPort) { USART_InitTypeDef USART_InitStructure; USART_Cmd(uartPort->USARTx, DISABLE); USART_InitStructure.USART_BaudRate = uartPort->port.baudRate; USART_InitStructure.USART_WordLength = USART_WordLength_8b; if (uartPort->port.mode & MODE_SBUS) { USART_InitStructure.USART_StopBits = USART_StopBits_2; USART_InitStructure.USART_Parity = USART_Parity_Even; } else { if (uartPort->port.mode & MODE_STOPBITS2) USART_InitStructure.USART_StopBits = USART_StopBits_2; else USART_InitStructure.USART_StopBits = USART_StopBits_1; USART_InitStructure.USART_Parity = USART_Parity_No; } USART_InitStructure.USART_HardwareFlowControl = USART_HardwareFlowControl_None; USART_InitStructure.USART_Mode = 0; if (uartPort->port.mode & MODE_RX) USART_InitStructure.USART_Mode |= USART_Mode_Rx; if (uartPort->port.mode & MODE_TX) USART_InitStructure.USART_Mode |= USART_Mode_Tx; if (uartPort->port.mode & MODE_BIDIR) USART_InitStructure.USART_Mode |= USART_Mode_Tx | USART_Mode_Rx; USART_Init(uartPort->USARTx, &USART_InitStructure); usartConfigurePinInversion(uartPort); USART_Cmd(uartPort->USARTx, ENABLE); }
void uartReconfigure(uartPort_t *uartPort) { /*RCC_PeriphCLKInitTypeDef RCC_PeriphClkInit; RCC_PeriphClkInit.PeriphClockSelection = RCC_PERIPHCLK_USART1|RCC_PERIPHCLK_USART2|RCC_PERIPHCLK_USART3| RCC_PERIPHCLK_UART4|RCC_PERIPHCLK_UART5|RCC_PERIPHCLK_USART6|RCC_PERIPHCLK_UART7|RCC_PERIPHCLK_UART8; RCC_PeriphClkInit.Usart1ClockSelection = RCC_USART1CLKSOURCE_SYSCLK; RCC_PeriphClkInit.Usart2ClockSelection = RCC_USART2CLKSOURCE_SYSCLK; RCC_PeriphClkInit.Usart3ClockSelection = RCC_USART3CLKSOURCE_SYSCLK; RCC_PeriphClkInit.Uart4ClockSelection = RCC_UART4CLKSOURCE_SYSCLK; RCC_PeriphClkInit.Uart5ClockSelection = RCC_UART5CLKSOURCE_SYSCLK; RCC_PeriphClkInit.Usart6ClockSelection = RCC_USART6CLKSOURCE_SYSCLK; RCC_PeriphClkInit.Uart7ClockSelection = RCC_UART7CLKSOURCE_SYSCLK; RCC_PeriphClkInit.Uart8ClockSelection = RCC_UART8CLKSOURCE_SYSCLK; HAL_RCCEx_PeriphCLKConfig(&RCC_PeriphClkInit);*/ HAL_UART_DeInit(&uartPort->Handle); uartPort->Handle.Init.BaudRate = uartPort->port.baudRate; // according to the stm32 documentation wordlen has to be 9 for parity bits // this does not seem to matter for rx but will give bad data on tx! uartPort->Handle.Init.WordLength = (uartPort->port.options & SERIAL_PARITY_EVEN) ? UART_WORDLENGTH_9B : UART_WORDLENGTH_8B; uartPort->Handle.Init.StopBits = (uartPort->port.options & SERIAL_STOPBITS_2) ? USART_STOPBITS_2 : USART_STOPBITS_1; uartPort->Handle.Init.Parity = (uartPort->port.options & SERIAL_PARITY_EVEN) ? USART_PARITY_EVEN : USART_PARITY_NONE; uartPort->Handle.Init.HwFlowCtl = UART_HWCONTROL_NONE; uartPort->Handle.Init.OneBitSampling = UART_ONE_BIT_SAMPLE_DISABLE; uartPort->Handle.Init.Mode = 0; if (uartPort->port.mode & MODE_RX) uartPort->Handle.Init.Mode |= UART_MODE_RX; if (uartPort->port.mode & MODE_TX) uartPort->Handle.Init.Mode |= UART_MODE_TX; usartConfigurePinInversion(uartPort); #ifdef TARGET_USART_CONFIG usartTargetConfigure(uartPort); #endif if (uartPort->port.options & SERIAL_BIDIR) { HAL_HalfDuplex_Init(&uartPort->Handle); } else { HAL_UART_Init(&uartPort->Handle); } // Receive DMA or IRQ if (uartPort->port.mode & MODE_RX) { if (uartPort->rxDMAStream) { uartPort->rxDMAHandle.Instance = uartPort->rxDMAStream; uartPort->rxDMAHandle.Init.Channel = uartPort->rxDMAChannel; uartPort->rxDMAHandle.Init.Direction = DMA_PERIPH_TO_MEMORY; uartPort->rxDMAHandle.Init.PeriphInc = DMA_PINC_DISABLE; uartPort->rxDMAHandle.Init.MemInc = DMA_MINC_ENABLE; uartPort->rxDMAHandle.Init.PeriphDataAlignment = DMA_PDATAALIGN_BYTE; uartPort->rxDMAHandle.Init.MemDataAlignment = DMA_MDATAALIGN_BYTE; uartPort->rxDMAHandle.Init.Mode = DMA_CIRCULAR; uartPort->rxDMAHandle.Init.FIFOMode = DMA_FIFOMODE_DISABLE; uartPort->rxDMAHandle.Init.FIFOThreshold = DMA_FIFO_THRESHOLD_1QUARTERFULL; uartPort->rxDMAHandle.Init.PeriphBurst = DMA_PBURST_SINGLE; uartPort->rxDMAHandle.Init.MemBurst = DMA_MBURST_SINGLE; uartPort->rxDMAHandle.Init.Priority = DMA_PRIORITY_MEDIUM; HAL_DMA_DeInit(&uartPort->rxDMAHandle); HAL_DMA_Init(&uartPort->rxDMAHandle); /* Associate the initialized DMA handle to the UART handle */ __HAL_LINKDMA(&uartPort->Handle, hdmarx, uartPort->rxDMAHandle); HAL_UART_Receive_DMA(&uartPort->Handle, (uint8_t*)uartPort->port.rxBuffer, uartPort->port.rxBufferSize); uartPort->rxDMAPos = __HAL_DMA_GET_COUNTER(&uartPort->rxDMAHandle); } else { /* Enable the UART Parity Error Interrupt */ SET_BIT(uartPort->USARTx->CR1, USART_CR1_PEIE); /* Enable the UART Error Interrupt: (Frame error, noise error, overrun error) */ SET_BIT(uartPort->USARTx->CR3, USART_CR3_EIE); /* Enable the UART Data Register not empty Interrupt */ SET_BIT(uartPort->USARTx->CR1, USART_CR1_RXNEIE); } } // Transmit DMA or IRQ if (uartPort->port.mode & MODE_TX) { if (uartPort->txDMAStream) { uartPort->txDMAHandle.Instance = uartPort->txDMAStream; uartPort->txDMAHandle.Init.Channel = uartPort->txDMAChannel; uartPort->txDMAHandle.Init.Direction = DMA_MEMORY_TO_PERIPH; uartPort->txDMAHandle.Init.PeriphInc = DMA_PINC_DISABLE; uartPort->txDMAHandle.Init.MemInc = DMA_MINC_ENABLE; uartPort->txDMAHandle.Init.PeriphDataAlignment = DMA_PDATAALIGN_BYTE; uartPort->txDMAHandle.Init.MemDataAlignment = DMA_MDATAALIGN_BYTE; uartPort->txDMAHandle.Init.Mode = DMA_NORMAL; uartPort->txDMAHandle.Init.FIFOMode = DMA_FIFOMODE_DISABLE; uartPort->txDMAHandle.Init.FIFOThreshold = DMA_FIFO_THRESHOLD_1QUARTERFULL; uartPort->txDMAHandle.Init.PeriphBurst = DMA_PBURST_SINGLE; uartPort->txDMAHandle.Init.MemBurst = DMA_MBURST_SINGLE; uartPort->txDMAHandle.Init.Priority = DMA_PRIORITY_MEDIUM; HAL_DMA_DeInit(&uartPort->txDMAHandle); HAL_StatusTypeDef status = HAL_DMA_Init(&uartPort->txDMAHandle); if (status != HAL_OK) { while (1); } /* Associate the initialized DMA handle to the UART handle */ __HAL_LINKDMA(&uartPort->Handle, hdmatx, uartPort->txDMAHandle); __HAL_DMA_SET_COUNTER(&uartPort->txDMAHandle, 0); } else { /* Enable the UART Transmit Data Register Empty Interrupt */ SET_BIT(uartPort->USARTx->CR1, USART_CR1_TXEIE); } } return; }