void setup_timer_int() {
    // Pause the timer while we're configuring it
    timer.pause();

    // Set up period
    timer.setPeriod(TIMER_PERIODE); // in microseconds

    // Set up an interrupt on channel 1
    timer.setChannel1Mode(TIMER_OUTPUT_COMPARE);
    timer.setCompare(TIMER_CH1, 1);  // Interrupt 1 count after each update
    timer.attachCompare1Interrupt(timer_int_handler);

    // Refresh the timer's count, prescale, and overflow
    timer.refresh();

    // Start the timer counting
    timer.resume();
}
Esempio n. 2
0
unsigned int baud_time_get() 
{
  #ifdef ___MAPLE  
    timer4.pause();
    unsigned int tmp = timer4.getCount();  //get current timer count
    timer4.setCount(0);                    // reset timer count
    timer4.refresh();
    timer4.resume();
  #endif

  #ifdef ___ARDUINO
    TCCR1B &= 0xF8;                        // Clear CS10/CS11/CS12 bits, stopping the timer
    unsigned int tmp = int(TCNT1/2);       // get current timer count, dividing by two
                                           // because Arduino timer is counting at 2Mhz instead of 1Mhz
                                           // due to limited prescaler selection
    tmp += 0x8000 * baudOverflow;          // if timer overflowed, we will add 0xFFFF/2
    TCNT1 = 0;                             // reset timer count    
    baudOverflow = false;                  // reset baudOverflow after resetting timer    
    TCCR1B |= (1 << CS11);                 // Configure for 8 prescaler, restarting timer
  #endif

  #ifdef ___TEENSY
    unsigned int tmp = int(FTM0_CNT*2.8);
    FTM0_CNT = 0x0;
  #endif
  
  return tmp;
}
Esempio n. 3
0
void dxl_serial_init(volatile struct dxl_device *device, int index)
{
    ASSERT(index >= 1 && index <= 3);

    // Initializing device
    struct serial *serial = (struct serial*)malloc(sizeof(struct serial));
    dxl_device_init(device);
    device->data = (void *)serial;
    device->tick = dxl_serial_tick;
    device->process = process;

    serial->index = index;
    serial->txComplete = true;
    serial->dmaEvent = false;

    if (index == 1) {
        serial->port = &Serial1;
        serial->direction = DIRECTION1;
        serial->channel = DMA_CH4;
    } else if (index == 2) {
        serial->port = &Serial2;
        serial->direction = DIRECTION2;
        serial->channel = DMA_CH7;
    } else {
        serial->port = &Serial3;
        serial->direction = DIRECTION3;
        serial->channel = DMA_CH2;
    }
            
    serial->syncReadCurrent = 0xff;
    serial->syncReadCount = 0;

    initSerial(serial);

    if (!serialInitialized) {
        serialInitialized = true;
    
        // Initializing DMA
        dma_init(DMA1);

        usart1_tc_handler = usart1_tc;
        usart2_tc_handler = usart2_tc;
        usart3_tc_handler = usart3_tc;

        // Reset allocation
        for (unsigned int k=0; k<sizeof(devicePorts); k++) {
            devicePorts[k] = 0;
        }

        // Initialize sync read timer
        syncReadTimer.pause();
        syncReadTimer.setPrescaleFactor(CYCLES_PER_MICROSECOND*10);
        syncReadTimer.setOverflow(0xffff);
        syncReadTimer.refresh();
        syncReadTimer.resume();
    }
}
Esempio n. 4
0
void Dynamixel::begin(int baud) {
	//TxDString("[DXL]start begin\r\n");

	afio_remap(AFIO_REMAP_USART1);//USART1 -> DXL
	afio_cfg_debug_ports(AFIO_DEBUG_FULL_SWJ_NO_NJRST);
#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(PORT_TXRX_DIRECTION, PIN_TXRX_DIRECTION, GPIO_OUTPUT_PP);
	 gpio_write_bit(PORT_TXRX_DIRECTION, PIN_TXRX_DIRECTION, 0 );// RX Enable
#endif
	/* timer_set_mode(TIMER2, TIMER_CH1, TIMER_OUTPUT_COMPARE);

	 timer_pause(TIMER2);

	 uint16 ovf = timer_get_reload(TIMER2);
	 timer_set_count(TIMER2, min(0, ovf));

	 timer_set_reload(TIMER2, 10000);//set overflow

	 ovf = timer_get_reload(TIMER2);
	 timer_set_compare(TIMER2, TIMER_CH1, min(1000, ovf));

	 timer_attach_interrupt(TIMER2, TIMER_CH1, TIM2_IRQHandler);

	 timer_generate_update(TIMER2);
	 //timer_resume(TIMER2);*/

	/*
	 * Timer Configuation for Dynamixel bus
	 * 2013-04-03 ROBOTIS Changed it as the below codes
	 * Dynamixel bus used timer 2(channel 1) to check timeout for receiving data from the bus.
	 * So, don't use time 2(channel 1) in other parts.
	 * */
	// Pause the timer while we're configuring it
	timer.pause();

	// Set up period
	timer.setPeriod(1); // in microseconds

	// Set up an interrupt on channel 1
	timer.setMode(TIMER_CH1,TIMER_OUTPUT_COMPARE);
	timer.setCompare(TIMER_CH1, 1);  // Interrupt 1 count after each update
	timer.attachInterrupt(TIMER_CH1,TIM2_IRQHandler);

	// Refresh the timer's count, prescale, and overflow
	timer.refresh();

	// Start the timer counting
	//timer.resume();
	 dxl_initialize(0, baud);
}
Esempio n. 5
0
void baud_timer_restart() 
{
  #ifdef ___MAPLE
    timer4.setCount(0); 
    timer4.refresh();  
  #endif
  
  #ifdef ___ARDUINO
    TCNT1 = 0;
    baudOverflow = false;   
  #endif   
  
  #ifdef ___TEENSY
    FTM0_CNT = 0x0;
  #endif     
}
Esempio n. 6
0
//Timer control routines
void baud_timer_init() 
{
  #ifdef ___MAPLE
    timer4.pause();                                    // Pause the timer while configuring it
    timer4.setMode(TIMER_CH1, TIMER_OUTPUT_COMPARE);   // Set up interrupt on channel 1
    timer4.setCount(0);                                // Reset count to zero
        
    timer4.setPrescaleFactor(72);                      // Timer counts at 72MHz/72 = 1MHz  1 count = 1uS
    timer4.setOverflow(0xFFFF);                        // reset occurs at 15.259Hz
    timer4.refresh();                                  // Refresh the timer's count, prescale, and overflow
    timer4.resume();                                   // Start the timer counting
  #endif

  #ifdef ___ARDUINO
    cli();                               // stop interrupts during configuration
    TCCR1A = 0;                          // Clear TCCR1A register
    TCCR1B = 0;                          // Clear TCCR1B register
    TCNT1  = 0;                          // Initialize counter value
    OCR1A  = 0xFFFF;                     // Set compare match register to maximum value
    TCCR1B |= (1 << WGM12);              // CTC mode
                                         // We want 1uS ticks, for 16MHz CPU, we use prescaler of 16
                                         // as 1MHz = 1uS period, but Arduino is lame and only has
                                         // 3 bit multiplier, we can have 8 (overflows too quickly)
                                         // or 64, which operates at 1/4 the desired resolution
    TCCR1B |= (1 << CS11);               // Configure for 8 prescaler
    TIMSK1 |= (1 << OCIE1A);             // enable compare interrupt
    sei();                               // re-enable interrupts 
  #endif    
  
  #ifdef ___TEENSY
    FTM0_MODE |= FTM_MODE_WPDIS;
    
    FTM0_CNT = 0;
    FTM0_CNTIN = 0;
    FTM0_SC |= FTM_SC_PS(7);
    FTM0_SC |= FTM_SC_CLKS(1);
    FTM0_MOD = 0xFFFF;
    FTM0_MODE |= FTM_MODE_FTMEN;
    /*
    PIT_LDVAL1 = 0x500000;
    PIT_TCTRL1 = TIE;
    PIT_TCTRL1 |= TEN;
    PIT_TFLG1 |= 1;
    */
  #endif  
}
Esempio n. 7
0
/**
 * Processing master packets (sending it to the local bus)
 */
static void process(volatile struct dxl_device *self, volatile struct dxl_packet *packet)
{
    struct serial *serial = (struct serial*)self->data;
    dxl_serial_tick(self);

    if (serial->txComplete && !syncReadMode) {
        if (packet->instruction == DXL_SYNC_READ && packet->parameter_nb > 2) {
            ui8 i;
            syncReadMode = true;
            syncReadAddr = packet->parameters[0];
            syncReadLength = packet->parameters[1];
            syncReadDevices = 0;
            ui8 total = 0;

            for (i=0; (i+2)<packet->parameter_nb; i++) {
                ui8 id = packet->parameters[i+2];

                if (devicePorts[id]) {
                    struct serial *port = serials[devicePorts[id]];
                    if (port->syncReadCount == 0) {
                        port->syncReadCurrent = 0xff;
                        syncReadDevices++;
                    }
                    port->syncReadIds[port->syncReadCount] = packet->parameters[i+2];
                    port->syncReadOffsets[port->syncReadCount] = i;
                    port->syncReadCount++;
                    total++;
                }
            }

            syncReadTimer.refresh();
            syncReadResponse = (struct dxl_packet*)&self->packet;
            syncReadResponse->error = 0;
            syncReadResponse->parameter_nb = (syncReadLength+1)*total;
            syncReadResponse->process = false;
            syncReadResponse->id = packet->id;
        } else {
            // Forwarding the packet to the serial bus
            if (packet->id == DXL_BROADCAST || packet->id < 200) {
                self->packet.dxl_state = 0;
                self->packet.process = false;
                sendSerialPacket(serial, packet);
            }
        }
    }
}
Esempio n. 8
0
void FLYMAPLEScheduler::init(void* machtnichts)
{
    delay_us(2000000); // Wait for startup so we have time to connect a new USB console
    // 1kHz interrupts from systick for normal timers
    systick_attach_callback(_timer_procs_timer_event);

    // Set up Maple hardware timer for 1khz failsafe timer
    // ref: http://leaflabs.com/docs/lang/api/hardwaretimer.html#lang-hardwaretimer
    _failsafe_timer.pause();
    _failsafe_timer.setPeriod(1000); // 1000us = 1kHz
    _failsafe_timer.setChannelMode(TIMER_CH1, TIMER_OUTPUT_COMPARE);// Set up an interrupt on channel 1
    _failsafe_timer.setCompare(TIMER_CH1, 1);  // Interrupt 1 count after each update
    _failsafe_timer.attachInterrupt(TIMER_CH1, _failsafe_timer_event);
    _failsafe_timer.refresh();// Refresh the timer's count, prescale, and overflow
    _failsafe_timer.resume(); // Start the timer counting
    // We run this timer at a higher priority, so that a broken timer handler (ie one that hangs)
    // will not prevent the failsafe timer interrupt.
    // Caution: the timer number must agree with the HardwareTimer number
    nvic_irq_set_priority(NVIC_TIMER2, 0x14);
}
void setup() {
    // Set up the LED to blink
    pinMode(D13, OUTPUT);

    // Pause the timer while we're configuring it
    timer.pause();

    // Set up period
    timer.setPeriod(LED_RATE); // in microseconds

    // Set up an interrupt on channel 1
    timer.setChannel1Mode(TIMER_OUTPUT_COMPARE);
    timer.setCompare(TIMER_CH1, 1);  // Interrupt 1 count after each update
    timer.attachCompare1Interrupt(handler_led);

    // Refresh the timer's count, prescale, and overflow
    timer.refresh();

    // Start the timer counting
    timer.resume();
}
void setup( void )
{
    hardwareSetup();
    // Setup the LED to steady on
    pinMode(BOARD_LED_PIN, OUTPUT);
    digitalWrite(BOARD_LED_PIN, HIGH);
    
    // Setup the button as input
    pinMode(BOARD_BUTTON_PIN, INPUT);
    digitalWrite(BOARD_BUTTON_PIN, HIGH);
    
    // Setup the sensor pin as an analog input
    pinMode(sensor_pin,INPUT_ANALOG);
    
    setupKeywords();
    registerAction(_DIR_, &DIRaction);
    registerAction(_TYP_, &TYPaction);
    setupRadioModule();
    
    timer.pause();
    
    // Set up period
    timer.setPeriod(1000); // in microseconds
    
    // Set up an interrupt on channel 1
    timer.setMode(TIMER_CH1,TIMER_OUTPUT_COMPARE);
    timer.setCompare(TIMER_CH1, 1);  // Interrupt 1 count after each update
    timer.attachInterrupt(TIMER_CH1,ledTask);
    
    
    // Refresh the timer's count, prescale, and overflow
    timer.refresh();
    
    // Start the timer counting
    timer.resume();
    setupRadioModule();
    
}
Esempio n. 11
0
void motor_restart_traj_timer() {
  timer3.pause();
  timer3.refresh();
  timer3.resume();
}
Esempio n. 12
0
void init_ppm_timer()
{

    timer4.pause();
    timer4.setPrescaleFactor(TIMER_PRESCALE);
    timer4.setOverflow(65535);
    timer4.setCount(0);

    // use channel 2 to detect when we stop receiving
    // a ppm signal from the encoder.
    timer4.setMode(TIMER_CH2, TIMER_OUTPUT_COMPARE);
    timer4.setCompare(TIMER_CH2, 65535);
    timer4.attachCompare2Interrupt(ppm_timeout_isr);


    timer4.refresh();

    //capture compare regs TIMx_CCRx used to hold val after a transition on corresponding ICx

    //when cap occurs, flag CCXIF (TIMx_SR register) is set,
    //and interrupt, or dma req can be sent if they are enabled.

    //if cap occurs while flag is already high CCxOF (overcapture) flag is set..

    //CCIX can be cleared by writing 0, or by reading the capped data from TIMx_CCRx
    //CCxOF is cleared by writing 0 to it.

    //Clear the CC1E bit to disable capture from the counter as we set it up.
    //CC1S bits aren't writeable when CC1E is set.
    //CC1E is bit 0 of CCER (page 401)
    bitClear(r.gen->CCER,0);


    //Capture/Compare 1 Selection
    //  set CC1S bits to 01 in the capture compare mode register 1.
    //  01 selects TI1 as the input to use. (page 399 stm32 reference)
    //  (assuming here that TI1 is D16, according to maple master pin map)
    //CC1S bits are bits 1,0
    bitClear(r.gen->CCMR1, 1);
    bitSet(r.gen->CCMR1, 0);


    //Input Capture 1 Filter.
    //  need to set IC1F bits according to a table saying how long
    //  we should wait for a signal to be 'stable' to validate a transition
    //  on the input.
    //  (page 401 stm32 reference)
    //IC1F bits are bits 7,6,5,4
    bitClear(r.gen->CCMR1, 7);
    bitClear(r.gen->CCMR1, 6);
    bitSet(r.gen->CCMR1, 5);
    bitSet(r.gen->CCMR1, 4);

    //sort out the input capture prescaler IC1PSC..
    //00 no prescaler.. capture is done at every edge detected
    bitClear(r.gen->CCMR1, 3);
    bitClear(r.gen->CCMR1, 2);

    //select the edge for the transition on TI1 channel using CC1P in CCER
    //CC1P is bit 1 of CCER (page 401)
    // 0 = rising (non-inverted. capture is done on a rising edge of IC1)
    // 1 = falling (inverted. capture is done on a falling edge of IC1)
    bitClear(r.gen->CCER,1);

    //set the CC1E bit to enable capture from the counter.
    //CC1E is bit 0 of CCER (page 401)
    bitSet(r.gen->CCER,0);

    //enable dma for this timer..
    //sets the Capture/Compare 1 DMA request enable bit on the DMA/interrupt enable register.
    //bit 9 is CC1DE as defined on page 393.
    bitSet(r.gen->DIER,9);
}