Graupner R700 FM receiver – get the PPM signal


This must have already been discussed on plenty of other forums, but here I am, I want to use my Graupner FM transmitter / receiver with my quadcopter.

As Jordi from DIY Drones saysIntercept the PPM signal is the best way to obtain all the channels from any receiver, for a lot of reasons. The first one is performance, and the second is the simplicity (in code =P).

First of all, here’s a quite useful diagram that explains well how the PPM works, and the relationship between this signal and the individual channels:

RC Receiver Timing Diagram

The Graupner/JR R700 FM receiver is quite easy to hack.

Update 18Apr

While working on this other project, I needed to control the tank with this same Graupner Rx/Tx and hence needed to port this code to C# for the .NET micro framework, so that it runs on the FEZ Domino board.

Here’s the code, BUT BEWARE, while it works, it’s UNRELIABLE, and generates A LOT OF NOISE. I’m not sure, but I imagine it’s due to the non real time of the managed code, that can randomly introduce delays in the pulses… or so I think, DO let me know if you believe otherwise and/or find a problem in my code…


using System;
using System.Threading;
using Microsoft.SPOT;
using Microsoft.SPOT.Hardware;
using GHIElectronics.NETMF.FEZ;

public delegate void RadioDelegate(sbyte[] values);
public delegate void RadioSignalLostDelegate();

/**
* It's here only as an EXAMPLE.
* IT DOES WORK, but it's UNRELIABLE !
* */
class RadioPPM : IDisposable
{
const byte CHANNELS_COUNT = 6;
const long SYNC_SIGNAL_LENGHT = 5 * TimeSpan.TicksPerMillisecond; // 5milliseconds in ticks
const long TICKS_PER_MICROSEC = TimeSpan.TicksPerMillisecond / 1000;
const long ACCEPTABLE_PULSE_DELTA = 30 * TICKS_PER_MICROSEC; //2 signals with less than 30 microsecs difference are considered equal
const long MIN_VALID_PULSE = 900 * TICKS_PER_MICROSEC; // below this we consider is a spurious signal
const long MAX_VALID_PULSE = 2100 * TICKS_PER_MICROSEC; // above this -> spurious signal
const sbyte MAX_INVALID_PULSES = 5; //after this number of consecutive invalid pulses we declare the signal LOST !

const long MIN_PULSE = 1100 * TICKS_PER_MICROSEC;
const long MAX_PULSE = 1900 * TICKS_PER_MICROSEC;
const long MID_PULSE = (MAX_PULSE + MIN_PULSE) / 2;
const long PULSE_SCALE = (MAX_PULSE - MIN_PULSE) / 2 / 100;

private readonly InterruptPort _PPMport;
private readonly RadioDelegate _newValuesCallback;
private readonly RadioSignalLostDelegate _signalLostCallback;
private bool _isSignalLost = true;

sbyte _rx_ch = 0;
sbyte _invalidPulsesCount = 0;
long[] _currPulses = new long[CHANNELS_COUNT];  // pulses currently being read by the ISR (width in ticks for performance)
long[] _readPulses = new long[CHANNELS_COUNT];  // pulses done reading, waiting for the callbackExecutor to deal with them
long[] _sentPulses = new long[CHANNELS_COUNT];
long _previousEdgeTime;

public RadioPPM(FEZ_Pin.Interrupt PPMpin, RadioDelegate newValuesCallback, RadioSignalLostDelegate signalLostCallback)
{
_newValuesCallback = newValuesCallback;
_signalLostCallback = signalLostCallback;

// whenever there is a raise in the PPM signal, deal with it
_PPMport = new InterruptPort((Cpu.Pin)PPMpin, false, Port.ResistorMode.Disabled, Port.InterruptMode.InterruptEdgeHigh);
_PPMport.OnInterrupt += new NativeEventHandler(PPM_OnInterrupt);

// start the executor thread. ONLY 1 thread, rather than creating and killing them...
// also the callbacks are called in this thread rather than in the interrupt ISR !
new Thread(CallbackExecutor).Start();
}

private void PPM_OnInterrupt(uint port, uint state, DateTime time)
{
// 1. update the current pulse length and store current time for future use
long currentPulse = time.Ticks - _previousEdgeTime;
_previousEdgeTime = time.Ticks;

// 2. is it a SYNC signal ?
if (currentPulse > SYNC_SIGNAL_LENGHT)
{
_rx_ch = 0;
}
else
{
// 3. is this pulse VALID ?
if (currentPulse < MIN_VALID_PULSE || currentPulse > MAX_VALID_PULSE)
{
// if the count is already negative -> we know about the problem useless to keep incrementing the number...
// also increment ONLY if _rc_ch >= 0 means we only increment ONCE per new signal...
if(_invalidPulsesCount >= 0 && _rx_ch >= 0) _invalidPulsesCount++;
// invalidate this whole signal
_rx_ch = -1;
}
else
{

// 4. pulse for one of the channels
if (_rx_ch >= 0) _currPulses[_rx_ch++] = currentPulse;

// 5. Have we read ALL the channels ? This should be the last pulse, don't accept other pulses until we get a new SYNC signal
if (_rx_ch >= CHANNELS_COUNT)
{
// move the fresh data into the array for the CallbackExecutor
lock (_readPulses) _readPulses = (long[])_currPulses.Clone();

// end of this transmission, will wait for futur SYNC gap...
_rx_ch = -1;
_invalidPulsesCount = 0; // only now it's safe to say we got at least one valid signal
}
}
}
}

private void CallbackExecutor()
{
sbyte[] values = new sbyte[CHANNELS_COUNT];
bool send = false;

while (true)
{
// do we have a valid signal !?
if (_invalidPulsesCount == 0)
{
send = false;
// needs lock as the interrupt thread accesses this too...
lock (_readPulses)
{
// only send IF something has changed
if (!areEqual(_readPulses, _sentPulses))
{
_sentPulses = (long[])_readPulses.Clone();
send = true;
}
}

// this HAS to be outside the locked block, as we don't know how long it will take...
if (send)
{
_isSignalLost = false;
extractValuesFromPulses(_sentPulses, values);
_newValuesCallback(values);
}
}
else if (_invalidPulsesCount >= MAX_INVALID_PULSES)
{
_isSignalLost = true;
_signalLostCallback();
// stop calling this method again,
_invalidPulsesCount = -1;
}

Thread.Sleep(10); // take it easy, the pulses are received, time is less of essence now...
}
}

private static bool areEqual(long[] a, long[] b)
{
if (a == null && b == null) return true;
if (a == null || b == null) return false;
if (a.Length != b.Length) return false;

for (uint i = 0; i < a.Length; i++) if (System.Math.Abs((int)(a[i] - b[i])) > ACCEPTABLE_PULSE_DELTA) return false;

return true;
}

// transforms pulses expresses in ticks into percentages -100 to +100% .
private static void extractValuesFromPulses(long[] pulses, sbyte[] values)
{
long currPulse;
for (uint i = 0; i < pulses.Length; i++)
{
currPulse = pulses[i];
if (currPulse < MIN_PULSE) currPulse = MIN_PULSE;
if (currPulse > MAX_PULSE) currPulse = MAX_PULSE;
values[i] = (sbyte)((currPulse - MID_PULSE) / PULSE_SCALE);
}
}

public bool getIsSignalLost()
{
return _isSignalLost;
}

public void Dispose()
{
_PPMport.Dispose();
}
}

____________________________________________________________________________________

Aside of the 7 channels connectors, it has one extra “battery” connector which actually has a “diagnostic” signal on its signal pin (I have no idea what kind of diagnostic is really providing !).

So the clean solution is to :

  1. remove a 470 Ohms resistor to simply disconnect the battery connector from the diagnostic signal
  2. wire the signal pin on this connector to te indicated pin of a transitor to get he PPM signal

Graupner / JR R700 - Access to PPM Signal

And here’s some Arduino code, loosely based on Jose’s code from here:


#define PPM_PIN     8          // Input Capture Pin (PPM Rx signal reading)
// We need to now the number of channels to read from radio
// If this value is not well adjusted you will have bad radio readings... (you can check the radio at the begining of the setup process)
#define SYNC_GAP_LEN    8000    // we assume a space at least 4000us is sync (note clock counts in 0.5 us ticks)
#define MIN_IN_PULSE_WIDTH 750  //a valid pulse must be at least 750us
#define MAX_IN_PULSE_WIDTH 2250 //a valid pulse must be less than  2250us

volatile uint8_t  _rx_ch = 0;
volatile unsigned int _timeCaptures[ MAX_CHANNELS + 1];  // timer values for pulses width calculation
volatile byte _radio_status = 0;           // radio_status = 1 => OK, 0 => No Radio signal
volatile unsigned int _timer1_last_value;  // to store the last timer1 value before a reset. Needs to be volatile to be accessible from ISR
volatile unsigned int _ICR1_old = 0;

void setup_radio(){
 // PPM signal initialisation
 pinMode(PPM_PIN, INPUT);

 // Timer 1 used for PPM input signal
 //TCCR1A = 0xA0;           // Normal operation mode, PWM Operation disabled, clear OC1A/OC1B on Compare Match
 TCCR1A = 0x00;         // COM1A1=0, COM1A0=0 => Disconnect Pin OC1 from Timer/Counter 1 -- PWM11=0,PWM10=0 => PWM
 TCCR1B = 1 << CS11 | 1 << ICES1;         // TCNT1 prescaler/8 (16Mhz => 0.5useg, 8 Mhz => 1useg) |  RISING edge
 TIMSK1 = _BV(ICIE1) | _BV (TOIE1);   // Enable interrupts : Timer1 Capture and Timer1 Overflow
}

// Timer1 Overflow
// Detects radio signal lost and generate servo outputs (overflow at 22ms (45Hz))
ISR(TIMER1_OVF_vect){
 TCNT1 = 0;
 _timer1_last_value=0xFFFF;  // Last value before overflow...

 // Radio signal lost...
 _radio_status = 0;
}

// Capture RX pulse train using TIMER 1 CAPTURE INTERRUPT
// And also send Servo pulses using OCR1A and OCR1B [disabled now]
// Servo output is synchronized with input pulse train
ISR(TIMER1_CAPT_vect)
{
 if(!bit_is_set(TCCR1B ,ICES1)){        // falling edge?
 if(_rx_ch == MAX_CHANNELS) {        // This should be the last pulse...
 _timeCaptures[_rx_ch ++] = ICR1;
 _radio_status = 1;              // Rx channels ready...
 }

 TCCR1B |= _BV(ICES1);        // Next time : RISING edge
 _timer1_last_value = TCNT1;  // Take last value before reset
 TCNT1 = 0;                  // Clear counter

 // Servo Output on OC1A/OC1B... (syncronised with radio pulse train)
 //TCCR1A = 0xF0;        // Set OC1A/OC1B on Compare Match
 //TCCR1C = 0xC0;        // Force Output Compare A/B (Start Servo pulse)
 //TCCR1C = 0x00;
 //TCCR1A = 0xA0;      // Clear OC1A/OC1B on Compare Match
 }else {                  // Rise edge
 if ((ICR1 - _ICR1_old) >= SYNC_GAP_LEN){   // SYNC pulse?
 _rx_ch = 1;              // Channel = 1
 _timeCaptures[0] = ICR1;
 }else {
 if(_rx_ch > 1;        // The pulse width = _timeCaptures[n] - _timeCaptures[n-1] and move to microsegundos (resolution is 0.5us)

 // Out of range?
 if ((result > MIN_IN_PULSE_WIDTH) && (result < MAX_IN_PULSE_WIDTH))  return result;
 else return -1;
}

boolean isPulseDifferent(int pulseA, int pulseB){
  int delta = pulseA - pulseB;
  return delta < -20 || delta > 20;
}

This code does work, however I’m not too pleased with it as :

  • it seems far too complicated, I’m not sure we need to care about falling edges ! Just count the rising ones as from the diagram is the time elapsed between these that determines the pulses ! (makes sense, the falling of the signal is there only to allow for a new rise later on… 🙂 )
  • it uses timer 1, which is also used by Arduino’s Servo library. This forces use to use another timer to control the ESCs, rather than the convenient out of the box Arduino library. I plan on moving this to using Timer2 (which is on 8bits as oposed to 16 for Timer1, but the resolution should still be enough !)
  • it does some rather “dodgy” double reading of array values to allow concurrency (due to the Interrupt Service Routine that updates this same array)

That’s it, let me know if anybody want more details or has any feedback.

And finally, here’s my latest version of the Arduino code to read the PPM:

  1. it is shorter
  2. it is clearer (or so I think 🙂 )
  3. it uses timer2 rather than 1, and counting with a resolution of “only” 16us (which is more than enough as the FM receiver has comparable errors too, and we don’t care about 16us when a pulse is between 1000 and 2000)
  4. it allows me to use the Servo library (based on Timer1) for controling the ESCs
#define PPM_PIN     2          // External Interrupt 0 - Input Capture Pin (PPM Rx signal reading)
const byte TIMER_MULT = 16;        // has to correspond to the prescaler we set in TCCR2B
#define TIMER_COUNT TCNT2
#define MIN_IN_PULSE_WIDTH 750  //a valid pulse must be at least 750us
#define MAX_IN_PULSE_WIDTH 2250 //a valid pulse must be less than  2250us

volatile int8_t  _rx_ch = 0;
volatile unsigned int _pulses[MAX_CHANNELS + 1];  // pulses width in ticks for performance

void setup_radio(){
 // PPM signal initialisation
 pinMode(PPM_PIN, INPUT);

 // TIMER 2   Pins 5 & 6  will have PPM disabled  TCNT2 increments every 16uS
 TCCR2A = 0x00;
 TCCR2B = 1 << CS22 | 1 << CS21; // prescaler /256 (16MHz => 16usec)
 TIMSK2 = 1 << TOIE2; //Timer2 Overflow Interrupt Enable

// whenever there is a raise in the PPM signal, deal with it
 attachInterrupt(0, changeInSignalISR, RISING);
}
// Timer2 Overflow
ISR(TIMER2_OVF_vect){
  // turns out that with our prescaler, the timer gets overflown every 4ms (8 bit counter so 256 x 16 us each tick = 4096. So every 4096us the counter gets re-set...)
  // which is definitely more than a normal pulse, so we can consider this as a sync gap, between a new PPM signal
  _rx_ch = 0;
}
void changeInSignalISR(){
  if(_rx_ch >= 0) _pulses[_rx_ch ++] = TIMER_COUNT;
   // always re-init the times as we always start counting "something" on a rising change
   TIMER_COUNT = 0;

   // this should be the last pulse, don't accept oter pulses until we get a new SYNC signal
   if(_rx_ch > MAX_CHANNELS) _rx_ch = -1;
}

int rxGetChannelPulseWidth( uint8_t channel){
 unsigned int result = _pulses[channel] * TIMER_MULT; // do the multiplication only now when it's requested, for performance

 // Out of range?
 if ((result > MIN_IN_PULSE_WIDTH) && (result < MAX_IN_PULSE_WIDTH))  return result;
 else return -1;
}

P.S. here’s another page on the mikrokopter.de site, where a German guy briefly explains the same hack

Advertisement

21 Responses to Graupner R700 FM receiver – get the PPM signal

  1. Robert says:

    why when i use this code the PWM 3 output no longer works?

    • trandi says:

      Can’t really remember, I’ll may have to try at some point for my quadcopter and will let you know, but there’s no guarantee…

      Dan

      • Robert says:

        thank you for the reply 🙂
        ok i’ll explain my problem, i’m using a graupner r700 hacked in your way, and i want to use multiwii software, but when it’s all connected and working some RC input signals glitches from a value of 50 to 200 randomly!
        so i’ve started to use your code and mixing the method that you use:
        TCCR2A = 0x00;
        TCCR2B = 1 << CS22 | 1 < 16usec)
        TIMSK2 = 1 << TOIE2; //Timer2 Overflow Interrupt Enable
        and seems that now the RC signal is stable but motors on pin 3 and 11 doesn't sincronize.
        can you help me?

        thank you
        Rob

      • Robert says:

        another thing, i’ve tried also to use:
        TCCR0A = 0×00;
        TCCR0B = 1 << CS22 | 1 < 16usec)
        cause if i've understand use pin 5 and 6 instead of 3 and 11 but does'nt work, cause i don't receive anything from RC.

        Rob

      • trandi says:

        Sorry, I’m not sure I understand your setup or what you want to do, and I’m not familiar with the multiwii.

        Dan

  2. Brian says:

    I’m trying to implement your PPM decoder above on my own R700. I’m having some trouble getting a reliable signal out though. I opened my R700 and soldered a jumper wire to the transistor that you pointed out in the picture above and plugged it into digital pin 2 on my arduino uno. The output is mostly invalid results “-1” and every now and then I get a seemingly real value but it doesn’t correspond with my Tx.

    I wrote a short script to just see what the pulses look like and I get mostly random looking pulse widths.

    Any advice?

    Brian

    My test code:

    Serial.print(“Pin was high: “);
    Serial.println(pulseIn(2, HIGH));

    Serial.print(“Pin was low : “);
    Serial.println(pulseIn(2, LOW));

    Short example of my output:

    Pin was low : 1082
    Pin was high: 7466
    Pin was low : 7381
    Pin was high: 368
    Pin was low : 23
    Pin was high: 402
    Pin was low : 52
    Pin was high: 25
    Pin was low : 7734
    Pin was high: 407
    Pin was low : 661

    • trandi says:

      Hi Brian,

      I’m not sure what to say…

      Have you also removed the 470Ohms resistor as per this picture:

      Have you actually tried my latest version of the code (the last code snipped in the post, that was actually badly copy/pasted and that I have just fixed) which uses INTERRUPTS (still on pin 2) ?
      Try that and let me know how it goes ?

      Dan

      • Brian says:

        Hey Dan,

        Thanks for the quick response.

        I didn’t remove the resistor because I’m trying to avoid permanent damage to the receiver just yet. Instead I just soldered a jumper to the transistor and ran it directly to my arduino pin 2.

        I did try your code snippet above. I noticed the copy/paste mixup and straightened it out. My code looks the same as how you fixed it above except I added a few things to make it run as an individual arduino sketch.

        I added this to view output immediately:

        void loop() {
        Serial.print(rxGetChannelPulseWidth(0));
        Serial.print(“:”);
        Serial.print(rxGetChannelPulseWidth(1));
        Serial.print(“:”);
        Serial.print(rxGetChannelPulseWidth(2));
        // … you get the idea
        Serial.print(“:”);
        Serial.println(rxGetChannelPulseWidth(7));
        }

        changed your “void setup_radio()” to “void setup()” and added a define for MAX_CHANNELS that it seems you left out.

        The response I get is a lot of “-1″s because of the out of range check and every now and then I get a valid number that seems random and for random channels.

        Thanks for the help

        Brian

      • Brian says:

        Hey Dan,

        It works! I guess it was a problem with the reference voltage in my arduino. I had been powering the arduino from my +5V usb and powering the receiver with the usual 4.8V battery. The arduino uses the supply voltage as Vref by default (I believe, still need to do more reading on this).

        Anyway I used the usb to power the arduino and used the 5V out(from the arduino) to power the receiver and now it works like a charm. Your code is a great help by the way.

        Thanks for posting this article. It saved me a lot of poking around my receiver to find the PPM.

        Brian

      • trandi says:

        I’m really glad you found the problem, and also that my blog was helpful ! I must admit it’s frustrating when things “are supposed to work” but they don’t … so it’s always good to hear that you found the problem !

        I think your problem was not the +5V, but simply that you did NOT have a COMMON GROUND. 4.8 and 5V are definitely close enough. However all these voltages are relative to the reference GND, and if that’s not common then all bets are off…

        dan

      • Brian says:

        Indeed. A few minutes after I posted that I realized that I was using two power sources with no common ground and that was most likely my problem. It’s always the simple things that cause the biggest problems.

        Brian

  3. Hi,

    How do you plug the receiver on the map FEZ DOMINO?

    Thank you 🙂

  4. ezio says:

    Hi. Great explanation. Thanks a lot.
    I have a question. If I want to use it with arduino 8Mhz what I have to change in timer ?
    I’m not very good in timers.

    • trandi says:

      The CSxx bits in TCCR2B needs changing so that the prescaler becomes 128 rather than 256. This way the rest of the code should remain identical.
      I don’t know exactly which bits to set for prescaler 128, but try doing a Google search on “arduino timer 2 prescaler 128″… Or look in the atmega328 doc…

      Hope this helps,
      Dan

Leave a Reply

Fill in your details below or click an icon to log in:

WordPress.com Logo

You are commenting using your WordPress.com account. Log Out /  Change )

Facebook photo

You are commenting using your Facebook account. Log Out /  Change )

Connecting to %s

%d bloggers like this: