i just tried some time calculations with the 16bit timer 1 (which is present on all proc's we use)
i get it to work now but it is a little larger then the arduino functions (~200-500byte in my tests)
the goal was to use timer 1 for the time functions and for HW PWM.. i took some things of ampere_dieters code ..
base changes
- different timer setup
- new time functions
Code: Select all
uint32_t micros32() { // 32-bit TIMER1/5 routine suitable for intervals up to 2147sec (36min)
uint32_t t_hi;
uint16_t t;
uint8_t temp=SREG;
cli();
t_hi = timer1OV;
t = TCNT1;
SREG = temp;
return ((t_hi << 12) + t) >> 1;
}
uint32_t millis32() { // 32-bit TIMER1/5 routine suitable for intervals up to 2147sec (36min)
return micros32() / 1000;
}
void delay1(uint16_t ms) { // modified delay routine with polled API delayMicroseconds(). delayMicroseconds is usable because it dont uses Timer0 at all
while (ms > 0) {
delayMicroseconds(1000);
ms--;
}
}
ISR(TIMER1_OVF_vect) {
timer1OV++;
}
- different "in interrupt" time measurment
for example
Code: Select all
// Read PPM SUM RX Data
#if defined(SERIAL_SUM_PPM)
void rxInt() {
uint16_t now,diff;
static uint16_t last = 0;
static uint8_t chan = 0;
now = ((timer1OV << 12) + TCNT1) >> 1; // <- instead of micros()
diff = now - last;
last = now;
if(diff>3000) chan = 0;
else {
if(900<diff && diff<2200 && chan<8 ) { //Only if the signal is between these values it is valid, otherwise the failsafe counter should move up
rcValue[chan] = diff;
#if defined(FAILSAFE)
if(failsafeCnt > 20) failsafeCnt -= 20; else failsafeCnt = 0; // clear FailSafe counter - added by MIS //incompatible to quadroppm
#endif
}
chan++;
}
}
#endif
the results till now are:
improvements:
- 11bit RX reading.. standard, ppm & spect. sat. RX (before it was 8 bit)
- all time calculations are now more accurate (8x)
- less background interrupts..no arduino interrupts on timer0
- less jitter (no interrupt stop with delay() & timer 1 overflows less.. ervery 2 ms .. with arduino functions timer0 overflows every ms)
- timer 0 can and is now used for HW PWM on pin 5 &6 (promini hexa without servos and PIN_A0_A1_hex)
disadvantages:
- its a little slower... cycletime is arround 20us slower (that also may be because of the more accurate measurment)
- code is arround 400byte larger (this may be improved)
you can find my current (working) state here http://code.google.com/p/multiwii/sourc ... es%2Fronco
it is based on r 794
warthox will test it soon .. ill report his rating

regards felix