ardupilot/libraries/AP_HAL_AVR/Scheduler_Timer.cpp

166 lines
4.6 KiB
C++
Raw Normal View History

#include <AP_HAL.h>
#if (CONFIG_HAL_BOARD == HAL_BOARD_APM1 || CONFIG_HAL_BOARD == HAL_BOARD_APM2)
#include <avr/io.h>
#include <avr/interrupt.h>
#include "HAL_AVR.h"
#include "Scheduler.h"
using namespace AP_HAL_AVR;
#define cbi(sfr, bit) (_SFR_BYTE(sfr) &= ~_BV(bit))
#define sbi(sfr, bit) (_SFR_BYTE(sfr) |= _BV(bit))
static volatile uint32_t timer0_overflow_count = 0;
static volatile uint32_t timer0_millis = 0;
static uint8_t timer0_fract = 0;
void AVRTimer::init() {
// this needs to be called before setup() or some functions won't
// work there
sei();
// set timer 0 prescale factor to 64
// this combination is for the standard 168/328/1280/2560
sbi(TCCR0B, CS01);
sbi(TCCR0B, CS00);
// enable timer 0 overflow interrupt
sbi(TIMSK0, TOIE0);
// timers 1 and 2 are used for phase-correct hardware pwm
// this is better for motors as it ensures an even waveform
// note, however, that fast pwm mode can achieve a frequency of up
// 8 MHz (with a 16 MHz clock) at 50% duty cycle
TCCR1B = 0;
// set timer 1 prescale factor to 64
sbi(TCCR1B, CS11);
sbi(TCCR1B, CS10);
// put timer 1 in 8-bit phase correct pwm mode
sbi(TCCR1A, WGM10);
sbi(TCCR3B, CS31); // set timer 3 prescale factor to 64
sbi(TCCR3B, CS30);
sbi(TCCR3A, WGM30); // put timer 3 in 8-bit phase correct pwm mode
sbi(TCCR4B, CS41); // set timer 4 prescale factor to 64
sbi(TCCR4B, CS40);
sbi(TCCR4A, WGM40); // put timer 4 in 8-bit phase correct pwm mode
sbi(TCCR5B, CS51); // set timer 5 prescale factor to 64
sbi(TCCR5B, CS50);
sbi(TCCR5A, WGM50); // put timer 5 in 8-bit phase correct pwm mode
// set a2d prescale factor to 128
// 16 MHz / 128 = 125 KHz, inside the desired 50-200 KHz range.
// XXX: this will not work properly for other clock speeds, and
// this code should use F_CPU to determine the prescale factor.
sbi(ADCSRA, ADPS2);
sbi(ADCSRA, ADPS1);
sbi(ADCSRA, ADPS0);
// enable a2d conversions
sbi(ADCSRA, ADEN);
// the bootloader connects pins 0 and 1 to the USART; disconnect them
// here so they can be used as normal digital i/o; they will be
// reconnected in Serial.begin()
UCSR0B = 0;
}
#define clockCyclesPerMicrosecond() ( F_CPU / 1000000L )
#define clockCyclesToMicroseconds(a) ( ((a) * 1000L) / (F_CPU / 1000L) )
// the prescaler is set so that timer0 ticks every 64 clock cycles, and the
// the overflow handler is called every 256 ticks.
#define MICROSECONDS_PER_TIMER0_OVERFLOW (clockCyclesToMicroseconds(64 * 256))
// the whole number of milliseconds per timer0 overflow
#define MILLIS_INC (MICROSECONDS_PER_TIMER0_OVERFLOW / 1000)
// the fractional number of milliseconds per timer0 overflow. we shift right
// by three to fit these numbers into a byte. (for the clock speeds we care
// about - 8 and 16 MHz - this doesn't lose precision.)
#define FRACT_INC ((MICROSECONDS_PER_TIMER0_OVERFLOW % 1000) >> 3)
#define FRACT_MAX (1000 >> 3)
SIGNAL(TIMER0_OVF_vect)
{
// copy these to local variables so they can be stored in registers
// (volatile variables must be read from memory on every access)
uint32_t m = timer0_millis;
uint8_t f = timer0_fract;
m += MILLIS_INC;
f += FRACT_INC;
if (f >= FRACT_MAX) {
f -= FRACT_MAX;
m += 1;
}
timer0_fract = f;
timer0_millis = m;
timer0_overflow_count++;
}
uint32_t AVRTimer::millis()
{
uint32_t m;
uint8_t oldSREG = SREG;
// disable interrupts while we read timer0_millis or we might get an
// inconsistent value (e.g. in the middle of a write to timer0_millis)
cli();
m = timer0_millis;
SREG = oldSREG;
return m;
}
uint32_t AVRTimer::micros() {
uint32_t m;
uint8_t t;
uint8_t oldSREG = SREG;
cli();
m = timer0_overflow_count;
t = TCNT0;
if ((TIFR0 & _BV(TOV0)) && (t < 255))
m++;
SREG = oldSREG;
return ((m << 8) + t) * (64 / clockCyclesPerMicrosecond());
}
/* Delay for the given number of microseconds. Assumes a 16 MHz clock. */
void AVRTimer::delay_microseconds(uint16_t us)
{
// for the 16 MHz clock on most Arduino boards
// for a one-microsecond delay, simply return. the overhead
// of the function call yields a delay of approximately 1 1/8 us.
if (--us == 0)
return;
// the following loop takes a quarter of a microsecond (4 cycles)
// per iteration, so execute it four times for each microsecond of
// delay requested.
us <<= 2;
// account for the time taken in the preceeding commands.
us -= 2;
// busy wait
__asm__ __volatile__ (
"1: sbiw %0,1" "\n\t" // 2 cycles
"brne 1b" : "=w" (us) : "0" (us) // 2 cycles
);
}
#endif