void HardwareSerial::begin(uint32 baud) { ASSERT(baud <= usart_device->max_baud); if (baud > usart_device->max_baud) { return; } const stm32_pin_info *txi = &PIN_MAP[tx_pin]; const stm32_pin_info *rxi = &PIN_MAP[rx_pin]; #ifdef STM32F2 // int af = 7<<8; gpio_set_af_mode(txi->gpio_device, txi->gpio_bit, 7); gpio_set_af_mode(rxi->gpio_device, rxi->gpio_bit, 7); gpio_set_mode(txi->gpio_device, txi->gpio_bit, (gpio_pin_mode)(GPIO_AF_OUTPUT_PP | GPIO_PUPD_INPUT_PU | 0x700)); gpio_set_mode(rxi->gpio_device, rxi->gpio_bit, (gpio_pin_mode)(GPIO_MODE_AF | GPIO_PUPD_INPUT_PU | 0x700)); //gpio_set_mode(txi->gpio_device, txi->gpio_bit, (gpio_pin_mode)(GPIO_PUPD_INPUT_PU)); //gpio_set_mode(rxi->gpio_device, rxi->gpio_bit, (gpio_pin_mode)(GPIO_PUPD_INPUT_PU)); #else gpio_set_mode(txi->gpio_device, txi->gpio_bit, GPIO_AF_OUTPUT_PP); gpio_set_mode(rxi->gpio_device, rxi->gpio_bit, GPIO_INPUT_FLOATING); #endif #if 0 if (txi->timer_device != NULL) { /* Turn off any PWM if there's a conflict on this GPIO bit. */ timer_set_mode(txi->timer_device, txi->timer_channel, TIMER_DISABLED); } #endif usart_init(usart_device); usart_set_baud_rate(usart_device, baud); usart_enable(usart_device); }
int stm32_test_usart(int id) { int ret = -1; struct usart_data usart_data; uint8_t data[] = {'A', 'B', 'C', 'D', 'E', 'F' }; usart_data.data = &data[0]; usart_data.size = sizeof(data); /* set USART parameters */ usart_set_word_length(id, 8); usart_set_baud_rate(id, 57600); usart_set_stop_bit(id, 1); /* enable USART2 */ usart_enable(id); usart_start_tx(id, &usart_data); /* Disable USART2 */ usart_disable(id); ret = 0; return ret; }
int rc100Initialize(uint32 baudrate ) { /* * Opening device * baudrate: Real baudrate (ex> 115200, 57600, 38400...) * Return: 0(Failed), 1(Succeed) * * */ gpio_set_mode(GPIOA, 2, GPIO_AF_OUTPUT_PP); gpio_set_mode(GPIOA, 3, GPIO_INPUT_FLOATING); usart_init(USART2); //TxDStringC("USART clock = ");TxDHex32C(STM32_PCLK2);TxDStringC("\r\n"); usart_set_baud_rate(USART2, STM32_PCLK1, baudrate); usart_attach_interrupt(USART2,rc100Interrupt); usart_enable(USART2); gbRcvFlag = 0; gwRcvData = 0; gbRcvPacketNum = 0; /*Clear rx tx uart2 buffer */ gbPacketWritePointer =0; gbPacketReadPointer=0; return 1; }
void Dynamixel::begin(int baud){ uint32 Baudrate = 0; if(mDxlUsart == USART1) afio_remap(AFIO_REMAP_USART1); #ifdef BOARD_CM900 //Engineering version case gpio_set_mode(PORT_ENABLE_TXD, PIN_ENABLE_TXD, GPIO_OUTPUT_PP); gpio_set_mode(PORT_ENABLE_RXD, PIN_ENABLE_RXD, GPIO_OUTPUT_PP); gpio_write_bit(PORT_ENABLE_TXD, PIN_ENABLE_TXD, 0 );// TX Disable gpio_write_bit(PORT_ENABLE_RXD, PIN_ENABLE_RXD, 1 );// RX Enable #else gpio_set_mode(mDirPort, mDirPin, GPIO_OUTPUT_PP); gpio_write_bit(mDirPort, mDirPin, 0 );// RX Enable //gpio_set_mode(GPIOB, 5, GPIO_OUTPUT_PP); // gpio_write_bit(GPIOB, 5, 0 );// RX Enable #endif // initialize GPIO D20(PB6), D21(PB7) as DXL TX, RX respectively gpio_set_mode(mTxPort, mTxPin, GPIO_AF_OUTPUT_PP); gpio_set_mode(mRxPort, mRxPin, GPIO_INPUT_FLOATING); //Initialize USART 1 device usart_init(mDxlUsart); //Calculate baudrate, refer to ROBOTIS support page. Baudrate = 2000000 / (baud + 1); if(mDxlUsart == USART1) usart_set_baud_rate(mDxlUsart, STM32_PCLK2, Baudrate); else usart_set_baud_rate(mDxlUsart, STM32_PCLK1, Baudrate); nvic_irq_set_priority(mDxlUsart->irq_num, 0);//[ROBOTIS][ADD] 2013-04-10 set to priority 0 usart_attach_interrupt(mDxlUsart, mDxlDevice->handlers); usart_enable(mDxlUsart); delay(80); mDXLtxrxStatus = 0; mBusUsed = 0;// only 1 when tx/rx is operated //gbIsDynmixelUsed = 1; //[ROBOTIS]2012-12-13 to notify end of using dynamixel SDK to uart.c this->clearBuffer(); this->setLibStatusReturnLevel(2); this->setLibNumberTxRxAttempts(1); }
void HardwareSerialFlowControl::begin(uint32 baud) { ASSERT(baud <= this->usart_device->max_baud); if (baud > this->usart_device->max_baud) { return; } const stm32_pin_info *txi = &PIN_MAP[this->tx_pin]; const stm32_pin_info *rxi = &PIN_MAP[this->rx_pin]; //TODO figureout how to extract correct pin from &PIN_MAP[this->rts_pin] const stm32_pin_info *ctsi = &PIN_MAP[this->cts_pin]; const stm32_pin_info *rtsi = &PIN_MAP[this->rts_pin]; disable_timer_if_necessary(txi->timer_device, txi->timer_channel); /* Configure USART2 RTS and USART2 Tx as alternate function push-pull */ /* Configure USART2 CTS and USART2 Rx as input floating */ usart_config_gpios_async(this->usart_device, rxi->gpio_device, rxi->gpio_bit, txi->gpio_device, txi->gpio_bit, 0); // need to configure the rts and cts pins here as // gpio_set_mode(ctsi->gpio_device, ctsi->gpio_bit, GPIO_INPUT_FLOATING); // gpio_set_mode(rtsi->gpio_device, rtsi->gpio_bit, GPIO_AF_OUTPUT_PP); // note this would do the same thing but is less explicit usart_config_gpios_async(this->usart_device, ctsi->gpio_device, ctsi->gpio_bit, rtsi->gpio_device, rtsi->gpio_bit, 0); usart_init(this->usart_device); usart_enable(this->usart_device); // enable rts/cts flow control in registers // should this be in usart.c for libmaple? does this apply to USART1,2.. // The stm peripheral example uses a temporary register (tmpreg) with a clear // mask and the following defines: // from stm peripheral library examples: // #define CR3_CLEAR_Mask ((uint16)0xFCFF) /*!< USART CR3 Mask */ // #define USART_HardwareFlowControl_RTS_CTS ((uint16)0x0300) // uint16 tmpreg = 0x00; // tmpreg = this->usart_device->regs->CR3; // tmpreg &= CR3_CLEAR_Mask; // tmpreg |= USART_HardwareFlowControl_RTS_CTS; // USART_HardwareFlowControl_RTS_CTS should be equivalent to // tmpreg |= (USART_CR3_RTSE |USART_CR3_CTSE ); // this->usart_device->regs->CR3 = tmpreg; this->usart_device->regs->CR3 = (USART_CR3_RTSE |USART_CR3_CTSE ); usart_set_baud_rate(this->usart_device, USART_USE_PCLK, baud); }
void UARTClass::begin(const uint32_t baud) { const stm32_pin_info *txi = &PIN_MAP[this->_txPin]; const stm32_pin_info *rxi = &PIN_MAP[this->_rxPin]; usart_config_gpios_async(this->_dev, rxi->gpio_device, rxi->gpio_bit, txi->gpio_device, txi->gpio_bit, 0); usart_init(this->_dev, _pBuff, _buffSize); usart_set_baud_rate(this->_dev, 0, baud); usart_enable(this->_dev); }
//To consider: Implement Cold/Hot start functions? //Idea for cold start, start and wait for coords or 30 seconds, whichever comes first. //Might be better to separate wait to avoid blocking and allow startup for other components simultaneously. void gps_start(void){ usart_config_gpios_async(GPS_USART, GPS_PORT_RX, GPS_PIN_RX, GPS_PORT_TX, GPS_PIN_TX, 0); usart_init(GPS_USART); usart_set_baud_rate(GPS_USART, USART_USE_PCLK, GPS_BAUD); //Enable BJT to turn on GPS //TODO: Confirm this isn't affected by being on UART CLK Pin (Currently unused) gpio_set_mode(GPIOA, 1, GPIO_OUTPUT_PP); gpio_write_bit(GPIOA, 8, 1); //Enable GPS USART Port usart_enable(GPS_USART); }
void serial_initialise() { const stm32_pin_info *txi = &PIN_MAP[TX1]; const stm32_pin_info *rxi = &PIN_MAP[RX1]; gpio_set_mode(txi->gpio_device, txi->gpio_bit, GPIO_AF_OUTPUT_OD); gpio_set_mode(rxi->gpio_device, rxi->gpio_bit, GPIO_INPUT_FLOATING); if (txi->timer_device != NULL) { /* Turn off any PWM if there's a conflict on this GPIO bit. */ timer_set_mode(txi->timer_device, txi->timer_channel, TIMER_DISABLED); } usart_init(USART1); usart_set_baud_rate(USART1, STM32_PCLK2, 115200); usart_enable(USART1); }
static void setupUSART(usart_dev *dev, uint32 baud) { uint32 i = USART_RX_BUF_SIZE; /* FIXME: need some preprocess here, according to specific board */ if (dev == USART1) { gpio_set_mode(GPIOA, 9, GPIO_AF_OUTPUT_PP); gpio_set_mode(GPIOA, 10, GPIO_INPUT_FLOATING); } usart_init(dev); usart_set_baud_rate(dev, 72000000UL, baud); usart_disable(dev); usart_enable(dev); /* flush buffer */ while (i--) { usart_putc(dev, '\r'); } }
/** * @brief Print an error message on a UART upon a failed assertion * and throb the error LED, if there is one defined. * @param file Source file of failed assertion * @param line Source line of failed assertion * @param exp String representation of failed assertion * @sideeffect Turns of all peripheral interrupts except USB. */ void _fail(const char* file, int line, const char* exp) { /* Initialize the error USART */ gpio_set_mode(ERROR_TX_PORT, ERROR_TX_PIN, GPIO_AF_OUTPUT_PP); usart_init(ERROR_USART); usart_set_baud_rate(ERROR_USART, ERROR_USART_CLK_SPEED, ERROR_USART_BAUD); /* Print failed assert message */ usart_putstr(ERROR_USART, "ERROR: FAILED ASSERT("); usart_putstr(ERROR_USART, exp); usart_putstr(ERROR_USART, "): "); usart_putstr(ERROR_USART, file); usart_putstr(ERROR_USART, ": "); usart_putudec(ERROR_USART, line); usart_putc(ERROR_USART, '\n'); usart_putc(ERROR_USART, '\r'); /* Error fade */ __error(); }
/** * Initialize the serial port interface on the Onyx. */ void serial_initialise() { const stm32_pin_info *txi = &PIN_MAP[TX1]; const stm32_pin_info *rxi = &PIN_MAP[RX1]; gpio_set_mode(txi->gpio_device, txi->gpio_bit, GPIO_AF_OUTPUT_OD); gpio_set_mode(rxi->gpio_device, rxi->gpio_bit, GPIO_INPUT_FLOATING); if (txi->timer_device != NULL) { /* Turn off any PWM if there's a conflict on this GPIO bit. */ timer_set_mode(txi->timer_device, txi->timer_channel, TIMER_DISABLED); } register_cmds(); command_stack[0] = cmd_main_menu; command_stack_size = 1; usart_init(USART1); usart_set_baud_rate(USART1, STM32_PCLK2, ERROR_USART_BAUD); usart_enable(USART1); }
void HardwareSerial::begin(uint32 baud) { ASSERT(baud <= this->usart_device->max_baud); if (baud > this->usart_device->max_baud) { return; } const stm32_pin_info *txi = &PIN_MAP[this->tx_pin]; const stm32_pin_info *rxi = &PIN_MAP[this->rx_pin]; disable_timer_if_necessary(txi->timer_device, txi->timer_channel); usart_config_gpios_async(this->usart_device, rxi->gpio_device, rxi->gpio_bit, txi->gpio_device, txi->gpio_bit, 0); usart_init(this->usart_device); usart_set_baud_rate(this->usart_device, USART_USE_PCLK, baud); usart_enable(this->usart_device); }
void HardwareSerial::begin(uint32 baud, uint8_t config) { // ASSERT(baud <= this->usart_device->max_baud);// Roger Clark. Assert doesn't do anything useful, we may as well save the space in flash and ram etc if (baud > this->usart_device->max_baud) { return; } const stm32_pin_info *txi = &PIN_MAP[this->tx_pin]; const stm32_pin_info *rxi = &PIN_MAP[this->rx_pin]; disable_timer_if_necessary(txi->timer_device, txi->timer_channel); usart_init(this->usart_device); usart_config_gpios_async(this->usart_device, rxi->gpio_device, rxi->gpio_bit, txi->gpio_device, txi->gpio_bit, config); usart_set_baud_rate(this->usart_device, USART_USE_PCLK, baud); usart_enable(this->usart_device); }
void HardwareSerial::begin(uint32 baud) { ASSERT(baud <= usart_device->max_baud); if (baud > usart_device->max_baud) { return; } const stm32_pin_info *txi = &PIN_MAP[tx_pin]; const stm32_pin_info *rxi = &PIN_MAP[rx_pin]; gpio_set_mode(txi->gpio_device, txi->gpio_bit, GPIO_AF_OUTPUT_PP); gpio_set_mode(rxi->gpio_device, rxi->gpio_bit, GPIO_INPUT_FLOATING); if (txi->timer_device != NULL) { /* Turn off any PWM if there's a conflict on this GPIO bit. */ timer_set_mode(txi->timer_device, txi->timer_channel, TIMER_DISABLED); } usart_init(usart_device); usart_set_baud_rate(usart_device, clock_speed, baud); usart_enable(usart_device); }
void init(void) { setupFlash(); setupClocks(); setupNVIC(); systick_init(SYSTICK_RELOAD_VAL); gpio_init_all(); afio_init(); setupADC(); setupTimers(); setupUSB(); boardInit(); //for debug gpio_set_mode(GPIOA, 2, GPIO_AF_OUTPUT_PP); gpio_set_mode(GPIOA, 3, GPIO_INPUT_FLOATING); usart_init(USART2); usart_set_baud_rate(USART2, STM32_PCLK1, 57600); usart_enable(USART2); /*delay(1000); TxDString("hello pandora\r\n");*/ }
/*-----------------------------------------------------------------vSerialTask() * * Handle (usb/serial) from console and monitored device. * The idea here is to handle the incoming characters as quickly as possible. * All data coming from the console or the datalogger * is delimited by <CR><LF>. Finding an end of line "gives" a semaphore. * * eventually this should be moved down to the */ static void vSerialTask(void* pvParameters) { portTickType xLastWakeTime = xTaskGetTickCount(); const portTickType xWakePeriod = 50; usart_init(USART1); usart_set_baud_rate(USART1, USART_USE_PCLK, 9600); usart_enable(USART1); deviceComm.len=0; deviceComm.gotline=false; vSemaphoreCreateBinary( deviceComm.xGotLineSemaphore ); //if( deviceComm.xGotLineSemaphore == NULL ) //{ // FREAK OUT!!! //} consoleComm.len=0; consoleComm.gotline=false; vSemaphoreCreateBinary( consoleComm.xGotLineSemaphore ); //if( consoleComm.xGotLineSemaphore == NULL ) //{ // FREAK THE HELL OUT!!! //} // usart_init(USART2); // usart_set_baud_rate(USART2, USART_USE_PCLK, 9600); // usart_enable(USART2); while (true) { togglePin(YEL_LED); uint32_t rc=0; unsigned char ch; #if 0 if (!deviceComm.gotline) { //rc=usart_data_available(USART1); while (usart_data_available(USART1) && deviceComm.len<(MAX_COMMAND_LINE_LENGTH-1)) { ch=usart_getc(USART1); if (ch=='\r') { deviceComm.gotline=true; deviceComm.line[deviceComm.len]='\0'; //xSemaphoreGive(deviceComm.xGotLineSemaphore); break; } else if (ch!='\n') { deviceComm.line[deviceComm.len++]=ch; } } } #endif if (!consoleComm.gotline) { while(SerialUSB.isConnected() && SerialUSB.available() && consoleComm.len<(MAX_COMMAND_LINE_LENGTH-1)) { ch=SerialUSB.read(); SerialUSB.write(ch); if (ch=='\r') { consoleComm.gotline=true; consoleComm.line[consoleComm.len]='\0'; //xSemaphoreGive(consoleComm.xGotLineSemaphore); break; } else if ((ch==ASCII_DELETE) || (ch==ASCII_BACKSPACE)) { if (consoleComm.len) consoleComm.len--; } else if (ch!='\n') { consoleComm.line[consoleComm.len++]=ch; } } } vTaskDelayUntil(&xLastWakeTime, xWakePeriod); } }
//Dynamixel::~Dynamixel() { // // TODO Auto-generated destructor stub //} void Dynamixel::begin(int baud) { uint32 Baudrate = 0; mPacketType = DXL_PACKET_TYPE1; //2014-04-02 default packet type is 1.0 -> set as 1 if(mDxlUsart == USART1) afio_remap(AFIO_REMAP_USART1); #ifdef BOARD_CM900 //Engineering version case gpio_set_mode(PORT_ENABLE_TXD, PIN_ENABLE_TXD, GPIO_OUTPUT_PP); gpio_set_mode(PORT_ENABLE_RXD, PIN_ENABLE_RXD, GPIO_OUTPUT_PP); gpio_write_bit(PORT_ENABLE_TXD, PIN_ENABLE_TXD, 0 );// TX Disable gpio_write_bit(PORT_ENABLE_RXD, PIN_ENABLE_RXD, 1 );// RX Enable #else if(mDirPort != 0) { gpio_set_mode(mDirPort, mDirPin, GPIO_OUTPUT_PP); gpio_write_bit(mDirPort, mDirPin, 0 );// RX Enable } //gpio_set_mode(GPIOB, 5, GPIO_OUTPUT_PP); // gpio_write_bit(GPIOB, 5, 0 );// RX Enable #endif // initialize GPIO D20(PB6), D21(PB7) as DXL TX, RX respectively gpio_set_mode(mTxPort, mTxPin, GPIO_AF_OUTPUT_PP); gpio_set_mode(mRxPort, mRxPin, GPIO_INPUT_FLOATING); //Initialize USART 1 device usart_init(mDxlUsart); //Calculate baudrate, refer to ROBOTIS support page. //Baudrate = dxl_get_baudrate(baud); //Dxl 2.0 if(baud == 3) baud = 1; else if(baud == 2) baud = 16; else if(baud == 1) baud = 34; else if(baud == 0) baud = 207; Baudrate = 2000000 / (baud + 1); if(mDxlUsart == USART1) usart_set_baud_rate(mDxlUsart, STM32_PCLK2, Baudrate); else usart_set_baud_rate(mDxlUsart, STM32_PCLK1, Baudrate); nvic_irq_set_priority(mDxlUsart->irq_num, 0);//[ROBOTIS][ADD] 2013-04-10 set to priority 0 usart_attach_interrupt(mDxlUsart, mDxlDevice->handlers); usart_enable(mDxlUsart); delay(100); mDXLtxrxStatus = 0; mBusUsed = 0;// only 1 when tx/rx is operated //gbIsDynmixelUsed = 1; //[ROBOTIS]2012-12-13 to notify end of using dynamixel SDK to uart.c this->setLibStatusReturnLevel(2); this->setLibNumberTxRxAttempts(2); this->clearBuffer(); if(this->checkPacketType()) { // Dxl 2.0 this->setPacketType(DXL_PACKET_TYPE2); } else { // Dxl 1.0 this->setPacketType(DXL_PACKET_TYPE1); } this->setLibNumberTxRxAttempts(1); this->clearBuffer(); if(mDxlUsart == USART2) { //140508 shin SmartDelayFlag = 1; this->setPacketType(DXL_PACKET_TYPE2); } }