PPM Sum Input for CRIUS AIO V2 (aka PL1 / ICP5)

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
Spacefish
Posts: 9
Joined: Wed Aug 07, 2013 12:26 pm

PPM Sum Input for CRIUS AIO V2 (aka PL1 / ICP5)

Post by Spacefish »

Please see attached .patch file..

Some new Boards use the PL1 Pin as PPM Input, as it can calculate the timediff between pulse very accuratly via a timer and is hardware filtered (to filter noise). In my patch i did´nt use the counter, as we have to handle overflow and such, but used the normal routine and just started timer 5 to handle capture events on PL1.

Requesting merge :)
Attachments
MultiWii_shared.7z
(1.45 KiB) Downloaded 316 times

Spacefish
Posts: 9
Joined: Wed Aug 07, 2013 12:26 pm

Re: PPM Sum Input for CRIUS AIO V2 (aka PL1 / ICP5)

Post by Spacefish »

sorry for adding this as 7z, the Forum software told me that extension .patch is not allowed..

here is the .patch inline (for fast preview)

Code: Select all

Index: MultiWii_shared/config.h
===================================================================
--- MultiWii_shared/config.h   (revision 1664)
+++ MultiWii_shared/config.h   (working copy)
@@ -140,6 +140,7 @@
       //#define Bobs_10DOF_BMP_V1 // BobsQuads 10DOF V1 with ITG3200, BMA180, HMC5883L & BMP180 - BMP180 is software compatible with BMP085
       //#define FLYDUINO_MPU       // MPU6050 Break Out onboard 3.3V reg
       //#define CRIUS_AIO_PRO_V1
+      //#define CRIUS_AIO_PRO_V2
       //#define DESQUARED6DOFV2GO  // DEsquared V2 with ITG3200 only
       //#define DESQUARED6DOFV4    // DEsquared V4 with MPU6050
       //#define LADYBIRD
Index: MultiWii_shared/def.h
===================================================================
--- MultiWii_shared/def.h   (revision 1664)
+++ MultiWii_shared/def.h   (working copy)
@@ -1388,6 +1388,32 @@
   #define SERVO_3_PIN_LOW            PORTL &= ~(1<<3);
 #endif
 
+#if defined(CRIUS_AIO_PRO_V2)
+  #define MPU6050
+  #define HMC5883
+  #define MS561101BA
+  #define ACC_ORIENTATION(X, Y, Z)  {imu.accADC[ROLL]  = -X; imu.accADC[PITCH]  = -Y; imu.accADC[YAW]  =  Z;}
+  #define GYRO_ORIENTATION(X, Y, Z) {imu.gyroADC[ROLL] =  Y; imu.gyroADC[PITCH] = -X; imu.gyroADC[YAW] = -Z;}
+  #define MAG_ORIENTATION(X, Y, Z)  {imu.magADC[ROLL]  =  X; imu.magADC[PITCH]  =  Y; imu.magADC[YAW]  = -Z;}
+  #define MPU6050_I2C_AUX_MASTER // MAG connected to the AUX I2C bus of MPU6050
+  #undef INTERNAL_I2C_PULLUPS
+  #define I2C_SPEED 400000L         //400kHz fast mode
+  //servo pins on AIO board is at pins 44,45,46, then release pins 33,34,35 for other usage
+  //eg. pin 33 on AIO can be used for LEDFLASHER output
+  #define SERVO_1_PINMODE            pinMode(44,OUTPUT);        // TILT_PITCH
+  #define SERVO_1_PIN_HIGH           PORTL |= 1<<5;
+  #define SERVO_1_PIN_LOW            PORTL &= ~(1<<5);
+  #define SERVO_2_PINMODE            pinMode(45,OUTPUT);        // TILT_ROLL
+  #define SERVO_2_PIN_HIGH           PORTL |= 1<<4;
+  #define SERVO_2_PIN_LOW            PORTL &= ~(1<<4);
+  #define SERVO_3_PINMODE            pinMode(46,OUTPUT);        // CAM TRIG
+  #define SERVO_3_PIN_HIGH           PORTL |= 1<<3;
+  #define SERVO_3_PIN_LOW            PORTL &= ~(1<<3);
+  #if defined(SERIAL_SUM_PPM)
+    #define PPM_ON_PL1
+  #endif
+#endif
+
 #if defined(LADYBIRD)
   #define MPU6050
   #define ACC_ORIENTATION(X, Y, Z)  {imu.accADC[ROLL]  = -X; imu.accADC[PITCH]  = -Y; imu.accADC[YAW]  =  Z;}
Index: MultiWii_shared/MultiWii.cpp
===================================================================
--- MultiWii_shared/MultiWii.cpp   (revision 1664)
+++ MultiWii_shared/MultiWii.cpp   (working copy)
@@ -689,6 +689,13 @@
     plog.armed_time = 0;   // lifetime in seconds
     //plog.running = 0;       // toggle on arm & disarm to monitor for clean shutdown vs. powercut
   #endif
+  #ifdef PPM_ON_PL1
+    // initialize timer 5 and trigger on rising flank
+    TCCR5A =((1<<WGM50)|(1<<WGM51));
+    TCCR5B = ((1<<WGM53)|(1<<WGM52)|(1<<CS51)|(1<<ICES5));
+    OCR5A = 40000; // 0.5us per timertick
+    TIMSK5 |= (1<<ICIE5); // activate input capture for PL1
+  #endif
   
   debugmsg_append_str("initialization completed\n");
 }
Index: MultiWii_shared/RX.cpp
===================================================================
--- MultiWii_shared/RX.cpp   (revision 1664)
+++ MultiWii_shared/RX.cpp   (working copy)
@@ -264,6 +264,11 @@
   ISR(INT6_vect){rxInt();}
 #endif
 
+// attach ISR to input trigger for PL1
+#if defined(PPM_ON_PL1) && defined(SERIAL_SUM_PPM)
+  ISR(TIMER5_CAPT_vect) { rxInt(); } // bind rxInt() to capture event
+#endif
+
 // PPM_SUM at THROTTLE PIN on MEGA boards
 #if defined(PPM_ON_THROTTLE) && defined(MEGA) && defined(SERIAL_SUM_PPM)
   ISR(PCINT2_vect) { if(PINK & (1<<0)) rxInt(); }


Spacefish
Posts: 9
Joined: Wed Aug 07, 2013 12:26 pm

Re: PPM Sum Input for CRIUS AIO V2 (aka PL1 / ICP5)

Post by Spacefish »

did i post in the wrong subforum? How do i get this merged?

Udeste
Posts: 6
Joined: Sat Feb 08, 2014 1:09 pm

Re: PPM Sum Input for CRIUS AIO V2 (aka PL1 / ICP5)

Post by Udeste »

I just added your code in my multiwii 2.3 nav release and there are some problems reading channels. This video below will explain better. My Receiver is a frsky d4r-II.
Randomly some channels seems to go down quickly to 0, and this problem reflects on the motors.

http://www.youtube.com/watch?v=ywqIAs2POtk

-ralf-
Posts: 215
Joined: Mon Dec 03, 2012 7:08 pm

Re: PPM Sum Input for CRIUS AIO V2 (aka PL1 / ICP5)

Post by -ralf- »

Udeste wrote:I just added your code in my multiwii 2.3 nav release and there are some problems reading channels. This video below will explain better. My Receiver is a frsky d4r-II.
Randomly some channels seems to go down quickly to 0, and this problem reflects on the motors.

http://www.youtube.com/watch?v=ywqIAs2POtk


Can you check it again with WinGUI? There is still no MultiWiiConf that supports GPS-Nav .....

Spacefish
Posts: 9
Joined: Wed Aug 07, 2013 12:26 pm

Re: PPM Sum Input for CRIUS AIO V2 (aka PL1 / ICP5)

Post by Spacefish »

I don´t think thats a problem with GPS/Nav

I see these possible Problems:
- Software error due to number overflows in my code / the MultiWii RX PPM Code
- Noise on the PPM Channel, so the Chip misses some flanks / triggers when there is no flank.
- Problem with generation of PPM Signal in Receiver (i don´t think so).

I haven´t noticed the problem with my OpenLRS Receiver, but hadn´t checked in depth. I know that the Atmel does some internal filtering of the input signal, but that shouldn´t be a problem...

As the detection errors are not periodic, i suspect it´s somehow a noise problem.. Maybe i can implement some "validation" so it will discard Frames that have to many or too few Pulses as seen by MultiWii

edit:
You may try to enable Hardware Noise Cancellation via replacing:

Code: Select all

TCCR5B = ((1<<WGM53)|(1<<WGM52)|(1<<CS51)|(1<<ICES5));

with

Code: Select all

TCCR5B = ((1<<WGM53)|(1<<WGM52)|(1<<CS51)|(1<<ICES5)|(1<<ICNC5)); 


ICNC5 = Input Capture Noise Cancellation 5

Udeste
Posts: 6
Joined: Sat Feb 08, 2014 1:09 pm

Re: PPM Sum Input for CRIUS AIO V2 (aka PL1 / ICP5)

Post by Udeste »

I checked both with wingui and multiwiiconf but the problem still here. So i think, as suggested by spacefish, that could be a filtering or overflow problem. I will check the ICNC5 solution as soon as i came back in my town this weekend. :)

Udeste
Posts: 6
Joined: Sat Feb 08, 2014 1:09 pm

Re: PPM Sum Input for CRIUS AIO V2 (aka PL1 / ICP5)

Post by Udeste »

With ICNC5 suggestion the problem was not fixed. So I think that could be some overflow problem or the code used by multiwii with interrupt rxInt() could not be good for timer events.

djborden
Posts: 3
Joined: Tue Feb 25, 2014 7:40 pm

Re: PPM Sum Input for CRIUS AIO V2 (aka PL1 / ICP5)

Post by djborden »

Do you guys have a feel for the robustness / reliability of PPM sum on the Crius AIO (I have v1)

I recently upgraded to EzUHF and using PPM sum would really clean up the wiring. I just dont know much about it so dont have a feel for how solid it is on this board running multiwii.

scrat
Posts: 925
Joined: Mon Oct 15, 2012 9:47 am
Location: Slovenia

Re: PPM Sum Input for CRIUS AIO V2 (aka PL1 / ICP5)

Post by scrat »

Just use PPM. It is working.

rubadub
Posts: 154
Joined: Mon Apr 28, 2014 2:36 am

Re: PPM Sum Input for CRIUS AIO V2 (aka PL1 / ICP5)

Post by rubadub »

found this thread.
I'm trying to setup PPM for AIRPLANE mode on a CRIUS AIOP V2 board.

The code suggested above by SpaceFish works fine for reading PPM on PL1.
The problem now is that TIMER5 is used for both PPM and for generating PWM servo output on MEGA boards with MEGA_HW_PWM_SERVOS disabled (these pins not available on CRIUS AIOP V2).

Can someone please suggest a work-around for getting servos & PPM to work on this board???

EDIT:
Nevermind, I figured out that it is, in fact, possible to run MEGA_HW_PWM_SERVOS on the crius AIOP V2. Using this option fixed the problem...

User avatar
Leo
Posts: 372
Joined: Wed Sep 17, 2014 7:01 am
Location: Germany
Contact:

Re: PPM Sum Input for CRIUS AIO V2 (aka PL1 / ICP5)

Post by Leo »

Dear MultiWii team,

Please implement this code in the next release for us CRIUS AIO Pro V2.x users.

Thanks!

Leo

User avatar
Leo
Posts: 372
Joined: Wed Sep 17, 2014 7:01 am
Location: Germany
Contact:

Re: PPM Sum Input for CRIUS AIO V2 (aka PL1 / ICP5)

Post by Leo »

Leo wrote:Dear MultiWii team,

Please implement this code in the next release for us CRIUS AIO Pro V2.x users.

Thanks!

Leo


I'm retracting my request as I have found out today that it really is not needed. Looking into the code more closely I was able to find the solution.
I tried it with my RC setup and it worked fine.

However maybe you could change the #define CRIUS_AIO_PRO_V1 to #define CRIUS_AIO_PRO_V1_V2 or just #define CRIUS_AIO_PRO
It would make life a bit easier.

Thanks.

Leo

User avatar
Plüschi
Posts: 433
Joined: Thu Feb 21, 2013 6:09 am

Re: PPM Sum Input for CRIUS AIO V2 (aka PL1 / ICP5)

Post by Plüschi »

Sorry but

Your not using input capture at all, you just bend the ICP interrupt vector to the old ppmsum routine which uses micros() ?
You run fast pwm mode with OCR5A as top set to 40000? Why?

WTF ? This whole mod doesent make any sense ...

rubadub
Posts: 154
Joined: Mon Apr 28, 2014 2:36 am

Re: PPM Sum Input for CRIUS AIO V2 (aka PL1 / ICP5)

Post by rubadub »

Plüschi wrote:Sorry but

Your not using input capture at all, you just bend the ICP interrupt vector to the old ppmsum routine which uses micros() ?
You run fast pwm mode with OCR5A as top set to 40000? Why?

WTF ? This whole mod doesent make any sense ...


so then what's the proper way to do it?

User avatar
Plüschi
Posts: 433
Joined: Thu Feb 21, 2013 6:09 am

Re: PPM Sum Input for CRIUS AIO V2 (aka PL1 / ICP5)

Post by Plüschi »

There are enough examples of reading stuff with ICP.

- You cant have a top value for the counter, or you will get fucked up readings because of wrap-arounds.
-> Top must be 0xFFFF, choose different counter mode.
- The hardware stores the counter value at external pin change, the interrupt then reads this stored value.
-> Read the ICR5 register instead of micros().

This way you get NO problems with wrap-arounds (do 16bit uint).
This way you get ZERO jitter even if interrupt is delayed.
This way you get much FINER resolution than micros() can ever give you.

You may not be able to use the icp timer for pwm, or you may have to compromise on pwm / icp frequency.
Using ICP you may then ditch the whole RC signal averaging/deadband stuff and enjoy the snappiness of hardware enhanced precision.

Good read on topic:
http://www.atmel.com/images/doc2549.pdf

I consider the possibility for such a patch to make it into the mainstream "shared" as pretty low. Unless we make a lot of noise.

This is some timer1 code ICP from another project (dumbed down to 8 bit resolution):

Code: Select all

  volatile uint16_t last = 0;
  volatile uint8_t chan = 0;

#if defined(ICP)

  ISR(TIMER1_CAPT_vect)
  {
    uint16_t now,diff;
    now = ICR1;
    diff = now - last;
    last = now;
    if      (diff>6000) chan = 0; // Sync gap
    else if (chan < RC_CHANNELS)
    {
      if (1800<diff && diff<4200)
      {
        if      (diff <= 2000) rcValue[chan] = 0;
        else if (diff >= 4000) rcValue[chan] = 255;
        else rcValue[chan] = (diff - 1976) >> 3;
        chan++;
      }
      else chan = 20;
    }
    else if (chan == RC_CHANNELS)
    {
      gotir = 1;
      chan++;
    }
  }

  void InitPPMin()
  {
    // Setup timer1 for input capture (PSC=8 -> 0.5ms precision, top at 20ms)
    TCCR1A = 0;
    TCCR1B = (1 << CS11) | (1 << ICNC1) | (1 << ICES1);
    TIMSK1 |= (1 << ICIE1);   // Enable timer1 input capture interrupt
  }

#else // sample PPM using pinchange interrupt

rubadub
Posts: 154
Joined: Mon Apr 28, 2014 2:36 am

Re: PPM Sum Input for CRIUS AIO V2 (aka PL1 / ICP5)

Post by rubadub »

did anyone ever make any progress on this given pluschi's feedback?

So, basically, is this what needs to be done?
- TIMER5 needs to be configured for 0.5us
- PWM output for servos using TIMER5 needs to be disabled/prevented
- the existing PPM routine needs to measure elapsed time using the value from ICR5 instead of micros(), but yet it has to take into account the register value & possible wrap-around
- RC averaging needs to be bypassed/disabled

Is that pretty much it? Am I missing something?

User avatar
Plüschi
Posts: 433
Joined: Thu Feb 21, 2013 6:09 am

Re: PPM Sum Input for CRIUS AIO V2 (aka PL1 / ICP5)

Post by Plüschi »

rubadub wrote:but yet it has to take into account the register value & possible wrap-around


Not a problem when counter TOP is 0xFFFF. Do the math:

initial value 0xFFF0 + elapsed time 0x030 = final value 0x10020
0x10020 is truncated to 16 bit since ICP is only 16 bit -> result is 0x0020

Means we get a full wrap around and still the result is 100% correct.
0x020 - 0xFFF0 = 0x030 elapsed time IF we do 16bit unsigned int math.

I have published something like this for 2560 and 32u4 years ago, but zero feedback.

rubadub
Posts: 154
Joined: Mon Apr 28, 2014 2:36 am

Re: PPM Sum Input for CRIUS AIO V2 (aka PL1 / ICP5)

Post by rubadub »

Plüschi wrote:I have published something like this for 2560 and 32u4 years ago, but zero feedback.


ok, can I take a look at it? where is it published? Do you have a link please?

rubadub
Posts: 154
Joined: Mon Apr 28, 2014 2:36 am

Re: PPM Sum Input for CRIUS AIO V2 (aka PL1 / ICP5)

Post by rubadub »

wtf? pluschi, you had published a response, but now it's gone... I don't understand why.

anyway, finding examples on how to do ICP and PPM reads is pretty easy. Dennis Frie has published some good examples.

So, just to clarify, is the lack of precision/accuracy in using micros() for RC processing the main reason why MW uses the RC averaging routines? (I've always had questions about why this is done). In your opinion, are you 100% positive that the main benefit of using ICP is that we can do away with the averaging routine and just use the raw ICP PPM reads as the final RC input?

User avatar
Plüschi
Posts: 433
Joined: Thu Feb 21, 2013 6:09 am

Re: PPM Sum Input for CRIUS AIO V2 (aka PL1 / ICP5)

Post by Plüschi »

I had already post the code up there, no need to have it twice.

MWii works good "as is" without icp. This icp thing is personal preference, not a "must have".
The resolution gets better, but the main thing (for me) is the jitter free hardware sampling.

The averaging / deadband is cosmetical. It doesent look good on the GUI if values are jumping. For flight no averaging and no deadband is better since you get a finer resolution trough temporal dithering. Averaging DOES make sense using a 72mhz analog radio, but not on a purely digital 2.4ghz radio.

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

Re: PPM Sum Input for CRIUS AIO V2 (aka PL1 / ICP5)

Post by Alexinparis »

Hi,

The way RC signal are measured in MultiWii is mainly historical : Arduino.
Arduino people decided since the beginning (and long time before MultiWii exists) to use Timer0 for all the timing functions.
Especially micros().

Basically, Timer0 is a 8 bit timer which is configured to raise an interrupt when a overflow counter is detected.
Each tick lasts 64 CPU clock time of 62.5ns on 16mHz proc, ie 4 microseconds(6,25ns x 64).
So an interrupt is raised every 4x256 = 1,024 ms
This interrupt is responsible to increase a 32 bit counter which is the output of micros().

So since the beginning, Multiwii uses pin change interrupt principle + micros() inside the interrupt to update the rc signal values.
=> that explains the resolution of 4 microseconds.

On 328p proc, only lefts Timer1 and Timer2 to drive 4 pins using hardware PWM.
Many boards were built with this schematic.

But it’s too bad Arduino didn’t use Timer1 at a higher resolution to design the timing functions,
because we could have had a much better resolution and less interrupts just to update the counter inside micros().
I suppose they did this to leave free the only 16 bit timer.
It’s too bad also we can’t remove the Timer0 interrupt without modifying Arduino sources.
(I did it in a variant project to drive successfully a WS2812 strip led)
And it was my choice to not modify Arduino IDE to compile multiwii sktech, so the supplied micros() is still used.
Using another Timer would be also complicated now because hardware PWM is expected only on specific PINs.

Note the 4 microseconds resolution is not the only reason why averaging is used.
PPM is basically an analogical signal where a numerical value is converted into a time pulse, introducing jitter.
The numerical value comes also from analogical pots of TX where jitter can occurs.
Take an oscilloscope and look at the PPM accuracy of RX signal to see by yourself.
You will see jitter can be much larger than 4 microseconds with some old school brands.
It’s true however most 2.4gHz systems have a much better signal jitter (nearly 100% end to end numerical), removing the need for averaging.

rubadub
Posts: 154
Joined: Mon Apr 28, 2014 2:36 am

Re: PPM Sum Input for CRIUS AIO V2 (aka PL1 / ICP5)

Post by rubadub »

hey, I just wanted to say that I finally got this working correctly based on pluschi's recommendations and by using the code from the initial patch as an example. I've got the PPM code to read the ICR5 register instead of using micros(). I've also disabled the RC averaging routine. It's working pretty good now, much snappier than before. Anyone interested in this & that needs the code, just PM me (I'm too lazy to post it here).

User avatar
Plüschi
Posts: 433
Joined: Thu Feb 21, 2013 6:09 am

Re: PPM Sum Input for CRIUS AIO V2 (aka PL1 / ICP5)

Post by Plüschi »

Recently i did read some of the megapirate (apm) code, and they do intresting stuff. Refering to file libraries/AP_HALMPNG/RCInput_MPNG.cpp

First they use timer5 for ICP PPM capture and the still get two 50hz pwm channels out of timer5. Unluckily most older MWii boards dont have ICP5 connected so ICP will not be mainstream.

Then, on boards where ICP is not connected they still use timer5 for capure instead of micros(). Timer5 runs 0.5us ticks, and instead of micros() they read TCNT5. This gives 8 times the resolution of the MWii system and works on ANY 2560 board. Most people run PPM on 2560 ... mainstream !

I wouldnt even bother with the two 50hz pwm channels they use on timer5, skipping the wrap-around problem of 40000. Who needs those 2 chans that anyway.

rubadub
Posts: 154
Joined: Mon Apr 28, 2014 2:36 am

Re: PPM Sum Input for CRIUS AIO V2 (aka PL1 / ICP5)

Post by rubadub »

So, they use TIMER5 as a multi-purpose 0.5us timer instead of micros()?
How do they manage to do the two 50hz pwm's off the same timer? I'm not clear on that.
But, I agree that it really wouldn't be worth the hassle (I don't personally need it).
My understanding is that MW uses TIMER5 for the MEGA_HW_PWM_SERVOS stuff, so that's why it's tied up and can't be used for other things, but I'm by no means an expert in this stuff :(

Post Reply