void DMA_init(void) { dma_init(DMA1); // TIM2 Update event /* DMA1 Channel2 configuration ----------------------------------------------*/ dma_setup_transfer(DMA1, DMA_CH2, (volatile void*) &(GPIOA->regs->ODR), DMA_SIZE_32BITS, (volatile void*) &(WS2812_IO_High), DMA_SIZE_8BITS, DMA_FROM_MEM); dma_set_priority(DMA1, DMA_CH2, DMA_PRIORITY_HIGH); // TIM2 CC1 event /* DMA1 Channel5 configuration ----------------------------------------------*/ dma_setup_transfer(DMA1, DMA_CH5, (volatile void*) &(GPIOA->regs->ODR), DMA_SIZE_32BITS, (volatile void*) WS2812_buffer, DMA_SIZE_8BITS, DMA_FROM_MEM | DMA_MINC_MODE); dma_set_priority(DMA1, DMA_CH5, DMA_PRIORITY_HIGH); // TIM2 CC2 event /* DMA1 Channel7 configuration ----------------------------------------------*/ dma_setup_transfer(DMA1, DMA_CH7, (volatile void*) &(GPIOA->regs->ODR), DMA_SIZE_32BITS, (volatile void*) &(WS2812_IO_Low), DMA_SIZE_8BITS, DMA_FROM_MEM | DMA_TRNS_CMPLT); dma_set_priority(DMA1, DMA_CH7, DMA_PRIORITY_HIGH); /* configure DMA1 Channel7 interrupt */ nvic_irq_set_priority(NVIC_DMA_CH7, 1); nvic_irq_enable(NVIC_DMA_CH7); dma_attach_interrupt(DMA1, DMA_CH7, DMA1_Channel7_IRQHandler); /* enable DMA1 Channel7 transfer complete interrupt */ }
void TIM2_init() { uint32_t SystemCoreClock = 72000000; uint16_t prescalerValue = (uint16_t) (SystemCoreClock / 24000000) - 1; rcc_clk_enable(RCC_TIMER2); /* Time base configuration */ timer_pause(TIMER2); timer_set_prescaler(TIMER2, prescalerValue); timer_set_reload(TIMER2, 29); // 800kHz /* Timing Mode configuration: Channel 1 */ timer_set_mode(TIMER2, 1, TIMER_OUTPUT_COMPARE); timer_set_compare(TIMER2, 1, 8); timer_oc_set_mode(TIMER2, 1, TIMER_OC_MODE_FROZEN, ~TIMER_OC_PE); /* Timing Mode configuration: Channel 2 */ timer_set_mode(TIMER2, 2, TIMER_OUTPUT_COMPARE); timer_set_compare(TIMER2, 2, 17); timer_oc_set_mode(TIMER2, 2, TIMER_OC_MODE_PWM_1, ~TIMER_OC_PE); //timer_resume(TIMER2); timer_attach_interrupt(TIMER2, TIMER_UPDATE_INTERRUPT, TIM2_IRQHandler); /* configure TIM2 interrupt */ nvic_irq_set_priority(NVIC_TIMER2, 2); nvic_irq_enable(NVIC_TIMER2); }
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); }
/** * @brief Initialize an I2C device as bus master * @param dev Device to enable * @param flags Bitwise or of the following I2C options: * I2C_FAST_MODE: 400 khz operation, * I2C_DUTY_16_9: 16/9 Tlow/Thigh duty cycle (only applicable for * fast mode), * I2C_BUS_RESET: Reset the bus and clock out any hung slaves on * initialization, * I2C_10BIT_ADDRESSING: Enable 10-bit addressing, * I2C_REMAP: Remap I2C1 to SCL/PB8 SDA/PB9. */ void i2c_master_enable(i2c_dev *dev, uint32 flags) { #define I2C_CLK (STM32_PCLK1/1000000) uint32 ccr = 0; uint32 trise = 0; /* PE must be disabled to configure the device */ ASSERT(!(dev->regs->CR1 & I2C_CR1_PE)); if ((dev == I2C1) && (flags & I2C_REMAP)) { afio_remap(AFIO_REMAP_I2C1); I2C1->sda_pin = 9; I2C1->scl_pin = 8; } /* Reset the bus. Clock out any hung slaves. */ if (flags & I2C_BUS_RESET) { i2c_bus_reset(dev); } /* Turn on clock and set GPIO modes */ i2c_init(dev); gpio_set_mode(dev->gpio_port, dev->sda_pin, GPIO_AF_OUTPUT_OD); gpio_set_mode(dev->gpio_port, dev->scl_pin, GPIO_AF_OUTPUT_OD); /* I2C1 and I2C2 are fed from APB1, clocked at 36MHz */ i2c_set_input_clk(dev, I2C_CLK); if (flags & I2C_FAST_MODE) { ccr |= I2C_CCR_FS; if (flags & I2C_DUTY_16_9) { /* Tlow/Thigh = 16/9 */ ccr |= I2C_CCR_DUTY; ccr |= STM32_PCLK1/(400000 * 25); } else { /* Tlow/Thigh = 2 */ ccr |= STM32_PCLK1/(400000 * 3); } trise = (300 * (I2C_CLK)/1000) + 1; } else { /* Tlow/Thigh = 1 */ ccr = STM32_PCLK1/(100000 * 2); trise = I2C_CLK + 1; } /* Set minimum required value if CCR < 1*/ if ((ccr & I2C_CCR_CCR) == 0) { ccr |= 0x1; } i2c_set_clk_control(dev, ccr); i2c_set_trise(dev, trise); /* Enable event and buffer interrupts */ nvic_irq_enable(dev->ev_nvic_line); nvic_irq_enable(dev->er_nvic_line); i2c_enable_irq(dev, I2C_IRQ_EVENT | I2C_IRQ_BUFFER | I2C_IRQ_ERROR); /* * Important STM32 Errata: * * See STM32F10xx8 and STM32F10xxB Errata sheet (Doc ID 14574 Rev 8), * Section 2.11.1, 2.11.2. * * 2.11.1: * When the EV7, EV7_1, EV6_1, EV6_3, EV2, EV8, and EV3 events are not * managed before the current byte is being transferred, problems may be * encountered such as receiving an extra byte, reading the same data twice * or missing data. * * 2.11.2: * In Master Receiver mode, when closing the communication using * method 2, the content of the last read data can be corrupted. * * If the user software is not able to read the data N-1 before the STOP * condition is generated on the bus, the content of the shift register * (data N) will be corrupted. (data N is shifted 1-bit to the left). * * ---------------------------------------------------------------------- * * In order to ensure that events are not missed, the i2c interrupt must * not be preempted. We set the i2c interrupt priority to be the highest * interrupt in the system (priority level 0). All other interrupts have * been initialized to priority level 16. See nvic_init(). */ nvic_irq_set_priority(dev->ev_nvic_line, 0); nvic_irq_set_priority(dev->er_nvic_line, 0); /* Make it go! */ i2c_peripheral_enable(dev); dev->state = I2C_STATE_IDLE; }
//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); } }