void uartSetMode(serialPort_t *instance, portMode_t mode) { uartPort_t *uartPort = (uartPort_t *)instance; uartPort->port.mode = mode; #ifndef STM32F303xC // FIXME this doesnt seem to work, for now re-open the port from scratch, perhaps clearing some uart flags may help? uartReconfigure(uartPort); #else uartOpen(uartPort->USARTx, uartPort->port.callback, uartPort->port.baudRate, uartPort->port.mode, uartPort->port.inversion); #endif }
serialPort_t *uartOpen(UARTDevice_e device, serialReceiveCallbackPtr callback, void *callbackData, uint32_t baudRate, portMode_e mode, portOptions_e options) { uartPort_t *s = serialUART(device, baudRate, mode, options); if (!s) { return (serialPort_t *)s; } s->txDMAEmpty = true; // common serial initialisation code should move to serialPort::init() s->port.rxBufferHead = s->port.rxBufferTail = 0; s->port.txBufferHead = s->port.txBufferTail = 0; // callback works for IRQ-based RX ONLY s->port.rxCallback = callback; s->port.rxCallbackData = callbackData; s->port.mode = mode; s->port.baudRate = baudRate; s->port.options = options; uartReconfigure(s); return (serialPort_t *)s; }
void uartSetMode(serialPort_t *instance, portMode_t mode) { uartPort_t *uartPort = (uartPort_t *)instance; uartPort->port.mode = mode; uartReconfigure(uartPort); }
void uartSetBaudRate(serialPort_t *instance, uint32_t baudRate) { uartPort_t *uartPort = (uartPort_t *)instance; uartPort->port.baudRate = baudRate; uartReconfigure(uartPort); }
serialPort_t *uartOpen(USART_TypeDef *USARTx, serialReceiveCallbackPtr callback, uint32_t baudRate, portMode_t mode, serialInversion_e inversion) { uartPort_t *s = NULL; if (USARTx == USART1) { s = serialUSART1(baudRate, mode); #ifdef USE_USART2 } else if (USARTx == USART2) { s = serialUSART2(baudRate, mode); #endif #ifdef USE_USART3 } else if (USARTx == USART3) { s = serialUSART3(baudRate, mode); #endif } else { return (serialPort_t *)s; } s->txDMAEmpty = true; // common serial initialisation code should move to serialPort::init() s->port.rxBufferHead = s->port.rxBufferTail = 0; s->port.txBufferHead = s->port.txBufferTail = 0; // callback works for IRQ-based RX ONLY s->port.callback = callback; s->port.mode = mode; s->port.baudRate = baudRate; s->port.inversion = inversion; uartReconfigure(s); // Receive DMA or IRQ DMA_InitTypeDef DMA_InitStructure; if ((mode & MODE_RX) || (mode & MODE_BIDIR)) { if (s->rxDMAChannel) { DMA_StructInit(&DMA_InitStructure); DMA_InitStructure.DMA_PeripheralBaseAddr = s->rxDMAPeripheralBaseAddr; DMA_InitStructure.DMA_Priority = DMA_Priority_Medium; DMA_InitStructure.DMA_M2M = DMA_M2M_Disable; DMA_InitStructure.DMA_PeripheralInc = DMA_PeripheralInc_Disable; DMA_InitStructure.DMA_PeripheralDataSize = DMA_PeripheralDataSize_Byte; DMA_InitStructure.DMA_MemoryInc = DMA_MemoryInc_Enable; DMA_InitStructure.DMA_MemoryDataSize = DMA_MemoryDataSize_Byte; DMA_InitStructure.DMA_BufferSize = s->port.rxBufferSize; DMA_InitStructure.DMA_DIR = DMA_DIR_PeripheralSRC; DMA_InitStructure.DMA_Mode = DMA_Mode_Circular; DMA_InitStructure.DMA_MemoryBaseAddr = (uint32_t)s->port.rxBuffer; DMA_DeInit(s->rxDMAChannel); DMA_Init(s->rxDMAChannel, &DMA_InitStructure); DMA_Cmd(s->rxDMAChannel, ENABLE); USART_DMACmd(s->USARTx, USART_DMAReq_Rx, ENABLE); s->rxDMAPos = DMA_GetCurrDataCounter(s->rxDMAChannel); } else { USART_ClearITPendingBit(s->USARTx, USART_IT_RXNE); USART_ITConfig(s->USARTx, USART_IT_RXNE, ENABLE); } } // Transmit DMA or IRQ if ((mode & MODE_TX) || (mode & MODE_BIDIR)) { if (s->txDMAChannel) { DMA_StructInit(&DMA_InitStructure); DMA_InitStructure.DMA_PeripheralBaseAddr = s->txDMAPeripheralBaseAddr; DMA_InitStructure.DMA_Priority = DMA_Priority_Medium; DMA_InitStructure.DMA_M2M = DMA_M2M_Disable; DMA_InitStructure.DMA_PeripheralInc = DMA_PeripheralInc_Disable; DMA_InitStructure.DMA_PeripheralDataSize = DMA_PeripheralDataSize_Byte; DMA_InitStructure.DMA_MemoryInc = DMA_MemoryInc_Enable; DMA_InitStructure.DMA_MemoryDataSize = DMA_MemoryDataSize_Byte; DMA_InitStructure.DMA_BufferSize = s->port.txBufferSize; DMA_InitStructure.DMA_DIR = DMA_DIR_PeripheralDST; DMA_InitStructure.DMA_Mode = DMA_Mode_Normal; DMA_DeInit(s->txDMAChannel); DMA_Init(s->txDMAChannel, &DMA_InitStructure); DMA_ITConfig(s->txDMAChannel, DMA_IT_TC, ENABLE); DMA_SetCurrDataCounter(s->txDMAChannel, 0); s->txDMAChannel->CNDTR = 0; USART_DMACmd(s->USARTx, USART_DMAReq_Tx, ENABLE); } else { USART_ITConfig(s->USARTx, USART_IT_TXE, ENABLE); } } USART_Cmd(s->USARTx, ENABLE); if (mode & MODE_BIDIR) USART_HalfDuplexCmd(s->USARTx, ENABLE); else USART_HalfDuplexCmd(s->USARTx, DISABLE); return (serialPort_t *)s; }
serialPort_t *uartOpen(USART_TypeDef *USARTx, serialReceiveCallbackPtr callback, uint32_t baudRate, portMode_t mode, portOptions_t options) { uartPort_t *s = NULL; if (USARTx == USART1) { s = serialUSART1(baudRate, mode, options); #ifdef USE_USART2 } else if (USARTx == USART2) { s = serialUSART2(baudRate, mode, options); #endif #ifdef USE_USART3 } else if (USARTx == USART3) { s = serialUSART3(baudRate, mode, options); #endif #ifdef USE_USART4 } else if (USARTx == UART4) { s = serialUSART4(baudRate, mode, options); #endif #ifdef USE_USART5 } else if (USARTx == UART5) { s = serialUSART5(baudRate, mode, options); #endif #ifdef USE_USART6 } else if (USARTx == USART6) { s = serialUSART6(baudRate, mode, options); #endif } else { return (serialPort_t *)s; } s->txDMAEmpty = true; // common serial initialisation code should move to serialPort::init() s->port.rxBufferHead = s->port.rxBufferTail = 0; s->port.txBufferHead = s->port.txBufferTail = 0; // callback works for IRQ-based RX ONLY s->port.callback = callback; s->port.mode = mode; s->port.baudRate = baudRate; s->port.options = options; uartReconfigure(s); // Receive DMA or IRQ DMA_InitTypeDef DMA_InitStructure; if (mode & MODE_RX) { #ifdef STM32F40_41xxx if (s->rxDMAStream) { DMA_StructInit(&DMA_InitStructure); DMA_InitStructure.DMA_PeripheralBaseAddr = s->rxDMAPeripheralBaseAddr; DMA_InitStructure.DMA_Priority = DMA_Priority_Medium; DMA_InitStructure.DMA_PeripheralInc = DMA_PeripheralInc_Disable; DMA_InitStructure.DMA_PeripheralDataSize = DMA_PeripheralDataSize_Byte; DMA_InitStructure.DMA_MemoryInc = DMA_MemoryInc_Enable; DMA_InitStructure.DMA_MemoryDataSize = DMA_MemoryDataSize_Byte; DMA_InitStructure.DMA_FIFOMode = DMA_FIFOMode_Disable ; DMA_InitStructure.DMA_FIFOThreshold = DMA_FIFOThreshold_1QuarterFull ; DMA_InitStructure.DMA_MemoryBurst = DMA_MemoryBurst_Single ; DMA_InitStructure.DMA_PeripheralBurst = DMA_PeripheralBurst_Single; #else if (s->rxDMAChannel) { DMA_StructInit(&DMA_InitStructure); DMA_InitStructure.DMA_PeripheralBaseAddr = s->rxDMAPeripheralBaseAddr; DMA_InitStructure.DMA_Priority = DMA_Priority_Medium; DMA_InitStructure.DMA_M2M = DMA_M2M_Disable; DMA_InitStructure.DMA_PeripheralInc = DMA_PeripheralInc_Disable; DMA_InitStructure.DMA_PeripheralDataSize = DMA_PeripheralDataSize_Byte; DMA_InitStructure.DMA_MemoryInc = DMA_MemoryInc_Enable; DMA_InitStructure.DMA_MemoryDataSize = DMA_MemoryDataSize_Byte; #endif DMA_InitStructure.DMA_BufferSize = s->port.rxBufferSize; #ifdef STM32F40_41xxx DMA_InitStructure.DMA_Channel = s->rxDMAChannel; DMA_InitStructure.DMA_DIR = DMA_DIR_PeripheralToMemory; DMA_InitStructure.DMA_Mode = DMA_Mode_Circular; DMA_InitStructure.DMA_Memory0BaseAddr = (uint32_t)s->port.rxBuffer; DMA_DeInit(s->rxDMAStream); DMA_Init(s->rxDMAStream, &DMA_InitStructure); DMA_Cmd(s->rxDMAStream, ENABLE); USART_DMACmd(s->USARTx, USART_DMAReq_Rx, ENABLE); s->rxDMAPos = DMA_GetCurrDataCounter(s->rxDMAStream); #else DMA_InitStructure.DMA_DIR = DMA_DIR_PeripheralSRC; DMA_InitStructure.DMA_Mode = DMA_Mode_Circular; DMA_InitStructure.DMA_MemoryBaseAddr = (uint32_t)s->port.rxBuffer; DMA_DeInit(s->rxDMAChannel); DMA_Init(s->rxDMAChannel, &DMA_InitStructure); DMA_Cmd(s->rxDMAChannel, ENABLE); USART_DMACmd(s->USARTx, USART_DMAReq_Rx, ENABLE); s->rxDMAPos = DMA_GetCurrDataCounter(s->rxDMAChannel); #endif } else { USART_ClearITPendingBit(s->USARTx, USART_IT_RXNE); USART_ITConfig(s->USARTx, USART_IT_RXNE, ENABLE); } } // Transmit DMA or IRQ if (mode & MODE_TX) { #ifdef STM32F40_41xxx if (s->txDMAStream) { DMA_StructInit(&DMA_InitStructure); DMA_InitStructure.DMA_PeripheralBaseAddr = s->txDMAPeripheralBaseAddr; DMA_InitStructure.DMA_Priority = DMA_Priority_Medium; DMA_InitStructure.DMA_PeripheralInc = DMA_PeripheralInc_Disable; DMA_InitStructure.DMA_PeripheralDataSize = DMA_PeripheralDataSize_Byte; DMA_InitStructure.DMA_MemoryInc = DMA_MemoryInc_Enable; DMA_InitStructure.DMA_MemoryDataSize = DMA_MemoryDataSize_Byte; DMA_InitStructure.DMA_FIFOMode = DMA_FIFOMode_Disable ; DMA_InitStructure.DMA_FIFOThreshold = DMA_FIFOThreshold_1QuarterFull ; DMA_InitStructure.DMA_MemoryBurst = DMA_MemoryBurst_Single ; DMA_InitStructure.DMA_PeripheralBurst = DMA_PeripheralBurst_Single; #else if (s->txDMAChannel) { DMA_StructInit(&DMA_InitStructure); DMA_InitStructure.DMA_PeripheralBaseAddr = s->txDMAPeripheralBaseAddr; DMA_InitStructure.DMA_Priority = DMA_Priority_Medium; DMA_InitStructure.DMA_M2M = DMA_M2M_Disable; DMA_InitStructure.DMA_PeripheralInc = DMA_PeripheralInc_Disable; DMA_InitStructure.DMA_PeripheralDataSize = DMA_PeripheralDataSize_Byte; DMA_InitStructure.DMA_MemoryInc = DMA_MemoryInc_Enable; DMA_InitStructure.DMA_MemoryDataSize = DMA_MemoryDataSize_Byte; #endif DMA_InitStructure.DMA_BufferSize = s->port.txBufferSize; #ifdef STM32F40_41xxx DMA_InitStructure.DMA_Channel = s->txDMAChannel; DMA_InitStructure.DMA_DIR = DMA_DIR_MemoryToPeripheral; DMA_InitStructure.DMA_Mode = DMA_Mode_Normal; DMA_DeInit(s->txDMAStream); DMA_Init(s->txDMAStream, &DMA_InitStructure); DMA_ITConfig(s->txDMAStream, DMA_IT_TC|DMA_IT_FE|DMA_IT_TE|DMA_IT_DME, ENABLE); DMA_SetCurrDataCounter(s->txDMAStream, 0); #else DMA_InitStructure.DMA_DIR = DMA_DIR_PeripheralDST; DMA_InitStructure.DMA_Mode = DMA_Mode_Normal; DMA_DeInit(s->txDMAChannel); DMA_Init(s->txDMAChannel, &DMA_InitStructure); DMA_ITConfig(s->txDMAChannel, DMA_IT_TC, ENABLE); DMA_SetCurrDataCounter(s->txDMAChannel, 0); s->txDMAChannel->CNDTR = 0; #endif USART_DMACmd(s->USARTx, USART_DMAReq_Tx, ENABLE); } else { USART_ITConfig(s->USARTx, USART_IT_TXE, ENABLE); } } USART_Cmd(s->USARTx, ENABLE); return (serialPort_t *)s; } void uartSetBaudRate(serialPort_t *instance, uint32_t baudRate) { uartPort_t *uartPort = (uartPort_t *)instance; uartPort->port.baudRate = baudRate; uartReconfigure(uartPort); } void uartSetMode(serialPort_t *instance, portMode_t mode) { uartPort_t *uartPort = (uartPort_t *)instance; uartPort->port.mode = mode; uartReconfigure(uartPort); }