11-bit time functions (instead of 8bit arduino ones)

This forum is dedicated to software development related to MultiWii.
It is not the right place to submit a setup problem.
Software download
Post Reply
ronco
Posts: 317
Joined: Thu Aug 18, 2011 2:58 pm

11-bit time functions (instead of 8bit arduino ones)

Post by ronco »

Hi,

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

User avatar
Hamburger
Posts: 2582
Joined: Tue Mar 01, 2011 2:14 pm
Location: air
Contact:

Re: 11-bit time functions (instead of 8bit arduino ones)

Post by Hamburger »

sounds good to get rid of the 2ms jitters many users have reported.
Since you are at it - what is actually left in the code that relies on the arduino environment?

Alexinparis
Posts: 1630
Joined: Wed Jan 19, 2011 9:07 pm

Re: 11-bit time functions (instead of 8bit arduino ones)

Post by Alexinparis »

Hi,
interesting ;)
the goal was to use timer 1 for the time functions and for HW PWM
I thought it was not possible to use both possibilities because setting for timer1 would be too fast or too slow if used also for HW PWM.
But configuring Timer1 to use a ~2ms loop is a very good idea to still use both !

ronco
Posts: 317
Joined: Thu Aug 18, 2011 2:58 pm

Re: 11-bit time functions (instead of 8bit arduino ones)

Post by ronco »

hi Hamburger,

Hamburger wrote:sounds good to get rid of the 2ms jitters many users have reported.

i think this wont remove the jitter complete .. it will reduce it .. the most jitter is caused by the RX interrupts

Hamburger wrote:Since you are at it - what is actually left in the code that relies on the arduino environment?

what i have in mid:
- delayMicroseconds
- pinMode
- constrain

Alexinparis wrote:I thought it was not possible to use both possibilities because setting for timer1 would be too fast or too slow if used also for HW PWM.
But configuring Timer1 to use a ~2ms loop is a very good idea to still use both !

it is not that good at it would be if timer 1 is free.. but i think its still better then the arduino function ;)

i have improved it to work with the same speed as the arduino func (same cycletime) and its size varies now between (-~100 & +~100 byte)

i didnt know why but my size tests varies with the chosen config: (compared with the same revision without this mod)

- promini & mega with itg3200 => +~50byte
- promini & mega with WMP => -~100byte

- promicro with itg3200 => +~100byte

so it dont think that this is a problem :)

to do this i had to use some unsigned long and short .. i know you dont like it .. but its better for this.

- branch is updated

regards felix

ronco
Posts: 317
Joined: Thu Aug 18, 2011 2:58 pm

Re: 11-bit time functions (instead of 8bit arduino ones)

Post by ronco »

to save some bytes i changed the type of checking the 50Hz to read the rx ..it is now called ervery 10timer1 overflows (20ms / 50hz) but it now dont needs a 32bit variable to check the micros

atmn in MWC

Code: Select all

  if (currentTime > rcTime ) { // 50Hz
    rcTime = currentTime + 20000;
    computeRC();


the new way:

Code: Select all

static uint8_t  timer1_OV8 = 0; // counts form 0 till 9 (50Hz) used for short periodes like RX input
static uint8_t  rxReadDone = 0; // indicates that the RC data was readed
...
void loop(){
...
  if(!rxReadDone){ // 50Hz
    rxReadDone = 1;
    computeRC();
...
///////////////////////// in output
// timer 1 overflowes every 2047us
ISR(TIMER1_OVF_vect) {     
   timer1_OV32++;
   timer1_OV8++;
   if(timer1_OV8 == 10){
     rxReadDone = 0;
     timer1_OV8 = 0;
   }
}


regards felix

ronco
Posts: 317
Joined: Thu Aug 18, 2011 2:58 pm

Re: 11-bit time functions (instead of 8bit arduino ones)

Post by ronco »

Hi,

i think i found a good way to measure the overall interrupt jitter ..

i just record the PCINT RX pin jitter of the throttle pin and check the average. to dont have corrupted values by a bad RX i use a promini programmed to do a constand HW PWM value of 1500us

code of the RX imitating promini

Code: Select all

void setup(){
  TIMSK0 = B00000000; // HW PWM isnt affacted by other interrupts but just to be sure i desable the arduino interrupts
  pinMode(9,OUTPUT);
  TCCR1A |= (1<<WGM11); // fast PWM mode & prescaler to 8
  TCCR1A &= ~(1<<WGM10);
  TCCR1B &=  ~(1<<CS10) & ~(1<<CS12);
  TCCR1B |= (1<<WGM13) | (1<<CS11) | (1<<WGM12);
  ICR1   |= 32767;
  TCCR1A |= _BV(COM1A1);
  OCR1A = 3000;  //1500us with 61Hz
}
void loop(){}


code to measure the jitter of the first RX pin (throttle on mega & mini || yaw on the promicro)

Code: Select all

  ISR(RX_PC_INTERRUPT) { //this ISR is common to every receiver channel, it is call everytime a change state occurs on a RX input pin
    uint8_t mask;
    uint8_t pin;
    uint16_t cTime,dTime;
    static uint16_t edgeTime[8];
    static uint8_t PCintLast;

    static uint16_t jmax=0; //value is  higher then average
    static uint16_t jmin=4000; // value is lower then average
    static uint8_t jitters[101]; // records 100 total jitter measurments to get a average
    static uint8_t jitterCounter1 = 0; //counts till 100  before a value is recorded to jitters
    static uint8_t jitterCounter2 = 0; // counts up everytime a value is recorded to jitters (also till 100)
   
 
    pin = RX_PCINT_PIN_PORT; // RX_PCINT_PIN_PORT indicates the state of each PIN for the arduino port dealing with Ports digital pins
   
    mask = pin ^ PCintLast;   // doing a ^ between the current interruption and the last one indicates wich pin changed
    cTime = (timer1_OV8 << 11) + (TCNT1 >> 1);
    sei();                    // re enable other interrupts at this point, the rest of this interrupt is not so time critical and can be interrupted safely
    PCintLast = pin;          // we memorize the current state of all PINs [D0-D7]

   // cTime = micros();         // micros() return a uint32_t, but it is not usefull to keep the whole bits => we keep only 16 bits
   
    #if (PCINT_PIN_COUNT > 0)
      RX_PIN_CHECK(0,2);
      if(rcValue[2]>jmax || rcValue[2]<jmin){ // rises the min and max values if the jitter is more then it was before
        if(rcValue[2]>jmax){
          jmax = rcValue[2];
        }
        if(rcValue[2]<jmin){
          jmin = rcValue[2];
        }
        debug1 = jmax-jmin; // debug 1 showes the current max jitter
      }
      jitterCounter1++;
      if(jitterCounter1 == 100){
        jitterCounter1 = 0;
        jitters[jitterCounter2] = debug1;
        jitterCounter2++;
        jmax = 0;
        jmin = 4000;
        if(jitterCounter2 == 100){
          jitterCounter2 = 0;
          debug2 = 0;
          for(uint8_t i = 0; i<100;i++){
            debug2 += jitters[i]; // debug 2 showes the average of 100 recordings (250 = 2,5us)
          }
        }
      }
    #endif


it takes ~5minutes to show the first average in debug 2..

now my results measured in "standby" (not armed just the gui active):

- jitter average with current arduino time functions = 6,4 - 8 us
- jitter average with timer 1 time functions = 2,2 - 2,8 us

so if i get warthox feedbak (and i dont think it will be bad) i would like to implement it to shared trunk.

regards felix

Alexinparis
Posts: 1630
Joined: Wed Jan 19, 2011 9:07 pm

Re: 11-bit time functions (instead of 8bit arduino ones)

Post by Alexinparis »

Except still unknown effects, I see only advantages to switch to Timer1.
The important thing is to still be able to use HW PWM of Timer1 and to keep the current pin assignment, and it's the case.
So feel free to modify the shared trunk if you feel confident enough with your feedback.

LenzGr
Posts: 166
Joined: Wed Nov 23, 2011 10:50 am
Location: Hamburg, Germany
Contact:

Re: 11-bit time functions (instead of 8bit arduino ones)

Post by LenzGr »

Slightly off-topic, but would this code also help in my case by any chance?

I'm currently trying to port the MultiWii 2.0 code to the ArduIMU v2 (flat) from DIYDrones/Sparkfun, which uses an Atmega328@16MHz with analog sensors. I've already managed to add support for the analog gyros (LPR530AL and LY530ALH, connected to Analog ports A3, A6 and A7, the ADXL335 accelerometer is connected to A0-A2) and reconfigured the code to use pins 10,11,12,13 for PWM output, but am struggling with reading the PPM receiver input.

There are only very few external pins available (see the connection diagram and schematics (PDF)), so I need to use either digital pin 8 (PB0/ICP, physical pin 12) or PWM0 (PB1/OC1a, physical pin 13) for the PPM input signal.

Is it actually possible to use D8 for reading the PPM input?

ronco
Posts: 317
Joined: Thu Aug 18, 2011 2:58 pm

Re: 11-bit time functions (instead of 8bit arduino ones)

Post by ronco »

LenzGr wrote:Slightly off-topic, but would this code also help in my case by any chance?

I'm currently trying to port the MultiWii 2.0 code to the ArduIMU v2 (flat) from DIYDrones/Sparkfun, which uses an Atmega328@16MHz with analog sensors. I've already managed to add support for the analog gyros (LPR530AL and LY530ALH, connected to Analog ports A3, A6 and A7, the ADXL335 accelerometer is connected to A0-A2) and reconfigured the code to use pins 10,11,12,13 for PWM output, but am struggling with reading the PPM receiver input.

There are only very few external pins available (see the connection diagram and schematics (PDF)), so I need to use either digital pin 8 (PB0/ICP, physical pin 12) or PWM0 (PB1/OC1a, physical pin 13) for the PPM input signal.

Is it actually possible to use D8 for reading the PPM input?


you can use pin D8 for it.. just like it is used for normal rx reading..

this should work ;) (but its not tested)

Code: Select all

// setup 

pinMode(8,INPUT);
PORTB |= (1<<0); // enable Pullups for pin 8
PCICR |= (1<<0); // activate Port Change Interrupt for port B
PCMSK0 = (1<<0); // activate Port Change Interrupt Request for Port B0
 

// read

ISR(PCINT0_vect) { // is called everytime pin 8 changes its state
  if ((PINB & 1<<0)){ // D8 is high -> we use the rising edge
    uint16_t now,diff;
    static uint16_t last = 0;
    static uint8_t chan = 0;
 
    now = 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++;
    }
  }
}


regards felix

LenzGr
Posts: 166
Joined: Wed Nov 23, 2011 10:50 am
Location: Hamburg, Germany
Contact:

Re: 11-bit time functions (instead of 8bit arduino ones)

Post by LenzGr »

ronco wrote:you can use pin D8 for it.. just like it is used for normal rx reading..

this should work ;) (but its not tested)

Awesome. I'll take a look at that and report back, thank you Felix!

LenzGr
Posts: 166
Joined: Wed Nov 23, 2011 10:50 am
Location: Hamburg, Germany
Contact:

Re: 11-bit time functions (instead of 8bit arduino ones)

Post by LenzGr »

It works! I now see the RX readings in the GUI. Thanks a lot for your help. I've merged your proposed changes with the existing code base: http://bazaar.launchpad.net/~lenzgr/+ju ... evision/55

Next I need to fix the channel ordering - I'm using a Spektrum2PPM board that seems to arrange the channels slightly different order...

LenzGr
Posts: 166
Joined: Wed Nov 23, 2011 10:50 am
Location: Hamburg, Germany
Contact:

Re: 11-bit time functions (instead of 8bit arduino ones)

Post by LenzGr »

Thanks again for the help with acquiring the PPM signal on the ArduIMU, much appreciated! I hope you don't mind if I have a follow-up question (it's somehow related to timers :) ).

Similar to the PPM input and analog sensors, I am quite constrained about which pins I can use to attach the ESCs to. In fact, I can only use pins 10,11,12 and 13.

I changed the PWM_PIN array in Output.pde as follows:

Code: Select all

#if defined(PROMINI)
  #if defined(ARDUIMUv2)
    uint8_t PWM_PIN[4] = {13,10,11,12};   //ArduIMU only has pins for four motors. For a quad+: rear,right,left,front
  #else
    uint8_t PWM_PIN[8] = {9,10,11,3,6,5,A2,12};   //for a quad+: rear,right,left,front
  #endif
#endif

I defined it as QUADP in config.h and the GUI correctly reflects this change - the PWM values change when I arm the motors and increase the throttle. However, only the left and right motor (Pin 10 and 11) actually start, front and rear (12,13) don't seem to receive a PWM signal. I assume I need to initialize and configure these two pins for PWM output somehow, but I am at loss on how to do that. Before I switched to MultiWii, I used a custom quadrocopter firmware that utilized the ServoTimer2 arduino library to drive the ESCs. But I'm not that deep into low-level AVR coding (messing with timers, interrupts) yet to fix this myself. I'd appreciate any hint on how to enable PWM output on pin 12 and 13 on this board. Thanks!

ronco
Posts: 317
Joined: Thu Aug 18, 2011 2:58 pm

Re: 11-bit time functions (instead of 8bit arduino ones)

Post by ronco »

hi,

it isnt that simple .. in Multiwii we use the hardware PWM capabilities of the MCUs as good as possible .. so that differs from servo timer2 lib and other software PWM methods becaus it works only on some specific pins (on arduinos thay are marked with a "~" or a white ring arround it).. the benefits of this is that the cause no interrupt jitter and also work without any jitter in the resulting signals (http://code.google.com/p/multiwii/wiki/PWM_Generation :D )

so to use pin 12 & 13 you will need to do it with software PWM .. i have less time atm -> here is just a fast overview how to do it:

disable the HW PWM init in init output for pin 11 & 3

Code: Select all

/********  Specific PWM Timers & Registers for the atmega328P (Promini)   ************/
  #if defined(PROMINI)
    #if (NUMBER_MOTOR > 0)
      TCCR1A |= _BV(COM1A1); // connect pin 9 to timer 1 channel A
    #endif
    #if (NUMBER_MOTOR > 1)
      TCCR1A |= _BV(COM1B1); // connect pin 10 to timer 1 channel B
    #endif
    #if (NUMBER_MOTOR > 2)
     // TCCR2A |= _BV(COM2A1); // connect pin 11 to timer 2 channel A <-- disabled
    #endif
    #if (NUMBER_MOTOR > 3)
      //TCCR2A |= _BV(COM2B1); // connect pin 3 to timer 2 channel B <-- disabled
    #endif



init software PWM for timer 2 comperator A & B

Code: Select all

// to 8bit variables to precalculate the dutytimes (ist better then doing it inside of a ISR)
volatile uint8_t pin12_high;
volatile uint8_t pin12_low;

volatile uint8_t pin13_high;
volatile uint8_t pin13_low;

// pin 12 & 13 must be set as output but thay are if you changed the Motors order

// set timer 2 to normal counting mode
TCCR2A = 0; // normal counting mode

// note because it is now in normal mode (that is more like fast PWM mode you may need rise the prescaler of timer 2 -> http://arduino.cc/playground/Code/PwmFrequency)

//enable the two interrupts for timer2's comperators a & B
TIMSK2 |= (1<<OCIE2A); // enable comperatorA'a ISR
TIMSK2 |= (1<<OCIE2B); // enable comperatorA'a ISR


The ISR's that will do the PWM to the pins

Code: Select all

// for comperator A // pin 12
ISR(TIMER2_COMPA_vect){
     static uint8_t state = 0;
     if(state==0){
           PORTB |= (1<<4); // pin 12 high
           OCR2A += pin12_high; // wait for the dutytime
           state = 1;
     }else{
           PORTB &= ~(1<<4); // pin 12 low
           OCR2A += pin12_low; // wait for the rest
           state = 0;
     }
}
// for comperator B // pin 13
ISR(TIMER2_COMPB_vect){
     static uint8_t state = 0;
     if(state==0){
           PORTB |= (1<<5); // pin 13 high
           OCR2B += pin13_high; // wait for the dutytime
           state = 1;
     }else{
           PORTB &= ~(1<<5); // pin 13 low
           OCR2B += pin13_low; // wait for the rest
           state = 0;
     }
}


to write the motors values to it: (to put in write motors .. instead of OCR2A = motor[2]>>3; and OCR2B = motor[3]>>3; )

Code: Select all

          pin12_high = motor[2]>>3;
          pin12_low = 255-pin12_high;

          pin13_high = motor[3]>>3;
          pin12_low = 255-pin13_high;     


ok that was not so fast ;) .. but it is untested ..

regrads felix

LenzGr
Posts: 166
Joined: Wed Nov 23, 2011 10:50 am
Location: Hamburg, Germany
Contact:

Re: 11-bit time functions (instead of 8bit arduino ones)

Post by LenzGr »

Felix, thanks a ton for this example and the explanation. I'll take a closer look and will try to get this working in my branch! This at least gives me an idea what I'm up to - at least it seems to be possible somehow. Kudos! If we ever meet in person, I owe you at least a beverage of choice :)

LenzGr
Posts: 166
Joined: Wed Nov 23, 2011 10:50 am
Location: Hamburg, Germany
Contact:

Re: 11-bit time functions (instead of 8bit arduino ones)

Post by LenzGr »

Felix, I've tried to apply your suggested changes, but was not very successful yet. I've posted a followup to this thread to avoid this getting too off-topic. I'd appreciate your advice.

Post Reply