SBUS to PPM and PWM Decoder Using Arduino Timer Interrupts. PART 4: SBUS to Servo Decoder

by blopa1961 in Circuits > Arduino

732 Views, 3 Favorites, 0 Comments

SBUS to PPM and PWM Decoder Using Arduino Timer Interrupts. PART 4: SBUS to Servo Decoder

SBUS2PPM2PWM12_Nano.jpg

This project is a set of programs used to decode Futaba’s Serial Bus (SBUS) protocol and output the received values via a Serial port, a PPM stream (for use with flight simulator USB dongles) and/or multiple PWM servo outputs (up to 12). The input is always an inverted pulse train which must be connected to a hardware serial port in the target MCU.

Click here to go to PART 3 of this instructable


Target audience:

The project is targeted at Arduino developers who would like to learn and understand how to use bare bones hardware timer interrupts for various Arduino processors, namely Pro Micro (ATMega32U4), Nano (ATMega328P), STM32F103 (bluepill) and ESP8266 (ESP01, ESP12, nodeMCU, Wemos D1 mini, etc) by analyzing the source code which does not use third party libraries nor external calls. The beauty of this project is that it has no display, no buttons to debounce, no external hardware. It’s a simple signal processor nicely fitted to learn interrupts.

The project is also targeted at radio control hobbyists who have knowledge of Arduino and its IDE. It’s not meant as a way to learn Arduino nor to teach how to setup a programming environment for the target MCU (like the ST-Link V2 necessary to program the bluepill MCU). I will assume you know all this and have some knowledge of electronics (resistors, transistors, Arduinos, etc.)

You will also need to build a signal inverter with a single NPN transistor and a couple of resistors. In the case of the ESP01 circuit below, the signal inverter will also work as a level shifter from 5V to the 3.3V required by the MCU.

Disclaimer:

No Warranty: THE SUBJECT SOFTWARE IS PROVIDED "AS IS" WITHOUT ANY WARRANTY OF ANY KIND, EITHER EXPRESSED OR IMPLIED, INCLUDING, BUT NOT LIMITED TO, ANY WARRANTY THAT THE SUBJECT SOFTWARE WILL CONFORM TO SPECIFICATIONS, ANY IMPLIED WARRANTIES OF MERCHANTABILITY, FITNESS FOR A PARTICULAR PURPOSE, OR FREEDOM FROM INFRINGEMENT, ANY WARRANTY THAT THE SUBJECT SOFTWARE WILL BE ERROR FREE, OR ANY WARRANTY THAT DOCUMENTATION, IF PROVIDED, WILL CONFORM TO THE SUBJECT SOFTWARE.

In other words: use at YOUR OWN RISK, if you crash a 50000 dollar R/C Jet because an SBUS decoder fails or stops responding you are on your own. As a matter of fact, if you have a 50000 dollar R/C jet (or a 100 dollar balsa R/C plane for that matter) I suggest you buy a commercial SBUS decoder when needed.

License:

Attribution Non-commercial (by-nc)

Description:

These interrupt routines are different for every MCU platform and sometimes require low level access to MCU registers (i.e. ATMega328P and ATMega32U4 which share the same register structure), sometimes interrupts are directly supported by the board manager (but not clearly documented), but overall, the code is highly incompatible between different MCU architectures.

To make the code clear I decided to create an individual sketch for each MCU architecture and refrained from using conditional ifs to compile a single sketch with multiple MCU architectures and different interrupt structures. You will find a list of target MCUs in the header of each .ino file. Unless explicitly mentioned, no third party libs are used.

All the sketches in this instructable were created using Arduino IDE 2.2.1 with the latest Board Manager of each target MCU.


PART 4:

SBUS to PPM converter with up to 12 PWM servo outputs.


Supplies

SBUS2PPM_PCA9685.jpg
  • Arduino Nano
  • Arduino Nano Shield Expander
  • Dupont female to female prototyping cables
  • Dupont to mini plug cable (you will have to make 1)
  • LEDs with 470ohm resistors in the anode (positive, longer) leg and Dupont female connectors (make 3)
  • (optional) PCA9685 I2C PWM driver (Adafruit or compatible)

PWM Servo Pulses

ServoPulses.jpg

As you can see in the photo above, servos expect 900 to 2100 microsecond pulses every 20mS (or so). Standard servos are not picky with the signal separation, but should not be refreshed faster than 50 times per second because they may overheat (depends on the brand and model). Analog servos will keep the position even when more than 20mS elapse between pulses unless subject to loads. Nothing bad will happen if more than 20mS elapse between pulses, which gives us some liberty as to how and when to generate the signal if we have to give priority to the PWM (Pulse Wave Modulation) pulse train. Digital servos will keep the last received position even when loaded or no signal is present.

I didn’t design an SBUS to servo decoder using and ESP8266 because it requires a 3.3V voltage regulator and it’s a power hog MCU not fit for R/C battery power (the only advantage is the price and maybe the size).

Warning: any sketches driving servos require a suitable external power supply. Do **NOT** connect servos to USB powered MCUs. Using only USB power you can only test a small servo without loads (if the MCU resets it’s because of the lack of power). Be warned that cheap servos like the SG90 or bootleg Tower Pros are not good at centering. The problem is the servo, not the timing; try using a good servo like the (original) MG92B (which I tested) or a Futaba servo.

Using a PCA9685 to Drive 16 Servos (and PPM)

PCA9685.jpg

Let’s start by the easiest way to manage servos, that is, use external hardware, namely a PCA9685 I2C PWM driver. The PCA9685 works, but if you want precision and resolution it is not the way to go. Not only does the PCA9685 require calibration because of low quality crystals, but we will be using about 12% of the SBUS' 11 bits of resolution.

Explanation:

We use the PCA9685 at 50Hz because we need 20mS bandwidth (1/50 sec= 20mS) for the servos pulses and pulse separation. The PCA9685 has 12 bits of resolution which gives us 4095 values (0 is not valid). Dividing the 20mS by 4095 we get about 4.88 microseconds per PCA9685 tick. Since servos operate in the range of 900 to 2100 uS (0.9 to 2.1mS), we have 2100-900= 1200 uS bandwidth pulses, which in turn gives us 1200/4.88= 245 valid positions out of the SBUS’ 2048 possible values for each servo. SBUS data is 11 bit wide ranging from 0 (900 uS servo pulse) to 2047 (1200uS servo pulse). SBUS data does not have anything to do with the 20mS servo pulse plus separation which we have to account for in the 4095 tick divisions a PCA9685 has; which is applied to the full range of 20mS (not 2.1mS) in a servo stream at 50Hz. Please notice that the 20mS bandwidth used in the PCA9685 includes both the servo pulse and separation, thus, a 2.1mS servo pulse will be followed by a 17.9mS separation, not 20 (anyways, it's not critical).

This sketch decodes SBUS, outputs an 8 channel PPM stream (again flawless, double buffering and interrupts) and sends the data for 16 servos connected to a PCA9687 by use of Adafruit_PWM_Servo_Driver_Library (3.0.0) by Adafruit. This sketch works with Pro Micro, Leonardo, Nano and UNO. It should also work with STM32F103 (untested, may require tweaking).

CODE:

// SBUS to PPM and PCA9685 (with 16 servos) converter
// (c) 2023 Pablo Montoreano

/*********************************************************
  @file       SBUS2PPM8_PCA9685.ino
  @brief      SBUS to PPM protocol converter and PCA9685 Servo driver
  @author     Pablo Montoreano
  @copyright  2023 Pablo Montoreano
  @version    1.1 - 05/oct/23 - bug fix (0x0F is a valid SBUS value)

  3rd party library: Adafruit_PWM_Servo_Driver_Library (3.0.0) - PCA9685 library

  for Arduino Pro Micro (ATMega32U4) or Arduino Leonardo (I needed at least 2 serial ports for debugging)
  added support for Arduino Nano or UNO (no debugging possible)
  Compile as Arduino Leonardo if using a Pro Micro
*********************************************************/

// define PPM output, LED and config ports in constants below

// PPM signal is idle high, low 0.5 ms (start), 0.400 to 1.600 milliseconds channel pulse, 0.5 ms channel separation
// pulse train separation is 10.5 ms

// 16 servo outputs are sent to PCA9685. See the Adafruit library for explanation and calibration

// connect PCA9685 to:
// Pro Micro    -> SDA pin   2, SCL pin 3
// Leonardo     -> SDA pin  D2, SCL pin D3
// Arduino Nano -> SDA pin  A4, SCL pin A5
// Arduino UNO  -> SDA pin D18, SCL pin D19

// if you want precision and resolution, the PCA9585 is *NOT* a good solution. Not only does the PCA9685 require
// calibration because of low quality crystals, but we are using 12% of the SBUS' 11 bits.
// Explanation:
// we are using the PCA9685 at 50Hz because we need 20mS (1/50 sec= 20mS) for the servos pulses and pulse separation.
// the PCA9685 has 12 bits of resolution which gives us 4095 values (0 is not valid). Dividing the 20mS by 4095 we get
// about 4.88 microseconds per PCA9685 tick. Since servos operate in the range of 900 to 2100 uS, we have 2100-900= 1200 uS
// bandwidth, which in turn gives us 1200/4.88= 245 valid positions out of the SBUS 2048 possible values for each servo.

// PCA9685 lib declarations
#include <Wire.h>
#include <Adafruit_PWMServoDriver.h>
Adafruit_PWMServoDriver pwm = Adafruit_PWMServoDriver();
// end PCA9685

#define SHOWSIGNAL
#define LEDON HIGH
#define LEDOFF LOW
static const unsigned int PPM_out= 9;  // PPM output port (Pro Micro port A9)
static const unsigned int portCfg= 10; // resolution configuration (Jumper= 10 bits)
static const unsigned int LED_noSignal= 8;  // low speed indicator LED
static const unsigned int maxChan= 8;  // number of PPM channels in pulse train
static const unsigned int maxServos= 16; // number of Servos in PCA9685
static const unsigned int trainSepStart= (maxChan+1)<<1;  // start of pulse train separation
static const unsigned int trainSep= 21000; // 10500 uS * 2 MHz (0.5 uS per tick using timer prescaler= 8)
static const unsigned int chanSep= 1000;   // 500 uS * 2 MHz
// failsafe in channel 3 when value below signalLost
// for chinese receivers that do not report failsafe in SBUS (i.e. Microzone MC9002)
static const unsigned int signalLost= 100;
static const unsigned long timeOutMs= 1000; // timeout if no packet received after 1 sec
static const unsigned long SBUSbaudRate= 100000; // SBUS baudrate 100K

static unsigned int sbusByte, byteNmbr;
static byte frame[25];  // SBUS frame
static unsigned int channel[17]; // 16 channels in SBUS stream + channels 17, 18 & failsafe in channel[0]
static unsigned int ppm1[maxChan+1], ppm2[maxChan+1];  // double buffering for interrupt data
static volatile unsigned int pTrain;  // pulse train pointer
static bool lock1;  // use pulse train 2 when 1 locked
static bool resol1024;  // low resolution. lose a bit for a steadier output using 10 bits instead of 11
static unsigned long lastReception;  // millis of last reception
static unsigned int i; // general counter
static bool newFrame;

// Timer1 interrupt
ISR (TIMER1_COMPA_vect) {
  TIMSK1= 0;  // disable timer
  if (pTrain == 0)
    digitalWrite(PPM_out, LOW);  // disable PPM output
  else  {
    pTrain++;
    if (pTrain < trainSepStart) { // still processing channels
      if (pTrain & 1) { // now odd, process channel separation
        digitalWrite(PPM_out, LOW);
        OCR1A= chanSep; // channel separation pulse= 0.5mS
      }
      else {
        digitalWrite(PPM_out, HIGH); // start of channel output (0.4 to 1.6 mS)
        // pTrain counts both the pulse separations and the channel pulses, that's why we have to divide
        // by two the ppm pulses index with the >> 1
        if (lock1) OCR1A= ppm2[pTrain >> 1];  // if ppm1 array is being written to use ppm2
        else OCR1A= ppm1[pTrain >> 1];
      }
    }
    else if (pTrain > trainSepStart) {  // end of 10.5mS pulse train separation, start a channel separation pulse
      digitalWrite(PPM_out, LOW);
      OCR1A= chanSep; // channel separation pulse= 0.5mS
      pTrain= 1; // start new pulse train
    }
    else {  // pTrain == trainSepStart (start pulse train separation)
      digitalWrite(PPM_out, HIGH);
      OCR1A= trainSep;
    }
    TIMSK1= bit(OCIE1A);  // start timer
  }
}

void initTimer1() {
// setup timer prescaler to 8. This is equivalent to a 2MHz timer (16MHz/8), equal to 0.5uS per tick
  cli();  // clear interrupts
  TCCR1A= 0;  // disable compare mode (for timer 3 use TCCR3A)
  TCCR1B= 0;  // no clock source (timer stopped)
  TCNT1= 0;
  OCR1A= trainSep; // defaults to pulse separation
  TCCR1B= bit(WGM12) | bit(CS11);  // WGM12 -> CTC(Clear Timer on Compare Match), only CS11 -> prescaler = 8
  //  CS12    CS11    CS10
  //  0       0       0     no clock source, timer stopped
  //  0       0       1     no prescale
  //  0       1       0     clk/8
  //  0       1       1     clk/64
  //  1       0       0     clk/256
  //  1       0       1     clk/1024
  //  1       1       0     extclk falling
  //  1       1       1     extclk rising
  TIMSK1= 0;  // disable timer
  sei();  // enable interrupts
}

void decodeChannels() {
int bitPtr;   // bit pointer in SBUS byte being decoded
int bytePtr;  // byte pointer in SBUS frame
int chan;     // channel number being decoded
int chanBit;  // current channel bit being proccessed

  channel[0]= frame[23];
  bytePtr= 1;
  bitPtr= 0;
  for (chan= 1; chan <= 16; chan++){
    channel[chan]= 0;
    for (chanBit= 0; chanBit < 11; chanBit++) {
      channel[chan] |= ((frame[bytePtr] >> bitPtr) & 1) << chanBit;
      if (++bitPtr > 7) { // change byte every 8 bits
        bitPtr=0;
        bytePtr++;
      }
    }
  }
}

bool getFrame() {
#ifdef __AVR_ATmega32U4__ // Arduino Pro Micro expected
  while (Serial1.available()) {
    sbusByte= Serial1.read();
#endif
#ifdef __AVR_ATmega328P__ // Arduino nano detected, use Serial only
  while (Serial.available()) {
    sbusByte= Serial.read();
#endif
// Bug fix: 0x0F is a valid value in the SBUS stream
// so we use a flag to detect the end of a packet (0) before enabling the capture of next frame
    if ((sbusByte == 0x0F) && newFrame) { // if this byte is SBUS start byte start counting bytes
      newFrame= false;
      byteNmbr= 0;
    }
    else if (sbusByte == 0) newFrame= true; // end of frame, enable start of next frame (to distinguish from 0x0F channel values)
    if (byteNmbr <= 24) { // 25 bytes total
      frame[byteNmbr]= sbusByte;  // save a byte
      byteNmbr++;
// if a valid frame is complete (check pointer position, start byte 0F and end byte 0)
      if ((byteNmbr == 25) && (sbusByte == 0) && (frame[0] == 0x0F)) return true;  // byteNmbr is now > 24, so this routine will now wait for next frame
    }
  }
  return false; // keep buffering
}

void setup() {
  pinMode(PPM_out, OUTPUT);
  digitalWrite(PPM_out, LOW);  // disable PPM output
  pinMode(LED_noSignal, OUTPUT);
#ifdef SHOWSIGNAL
  digitalWrite(LED_noSignal, LEDON);
#else
  digitalWrite(LED_noSignal, LEDOFF);
#endif
  pinMode(portCfg, INPUT_PULLUP);
// PCA9685
  pwm.begin();
  pwm.setOscillatorFrequency(27000000);
  pwm.setPWMFreq(50);  // Analog servos updated @59 Hz (about 20mS between pulses)
// end PCA9685
#ifdef __AVR_ATmega32U4__  // Arduino Pro Micro
  Serial1.begin(SBUSbaudRate, SERIAL_8E2);
#endif
#ifdef __AVR_ATmega328P__ // Arduino Nano
  Serial.begin(SBUSbaudRate, SERIAL_8E2);
#endif
  byteNmbr= 255; // invalidate SBUS byte number
  lastReception= 0;
  newFrame= false;
  pTrain= 0;  // idle
  lock1= true;
  initTimer1(); // initialize timer registers
}

void loop() {
  if (getFrame()) {
    lastReception= millis();
    decodeChannels(); // decode channel bitstream into 0 - 2047 channel values
    resol1024= (digitalRead(portCfg) == LOW); // can change resolution while running
#ifndef SHOWSIGNAL    
    digitalWrite(LED_noSignal, (resol1024) ? LEDON : LEDOFF); // reflect in LED
#endif
    for (i= 1; i <= maxChan; i++) {
      // each PPM channel pulse is 400 to 1600 uS while SBUS data is 0 to 2047, ajust values to timer
      // ((int) (channel[i] * 1200.0 / 2047.0) + 400) << 1; simplified with a single float operation
      // We multiply by 2 with the << 1 because we have 2 ticks per uS in the timer and we are working in uS
      // as an alternative we can use map(channel[i],0,2047,800,3200);
      // or map(channel[i] >> 1,0,1023,800,3200); for half resolution
      if (resol1024) {
        if (lock1) ppm1[i]= 800 + (int) ((channel[i] >> 1) * 2.344895);  // low (1024) resolution
        else ppm2[i]= 800 + (int) ((channel[i] >> 1) * 2.344895);
      }
      else {
        if (lock1) ppm1[i]= 800 + (int) (channel[i] * 1.172447);  // full 2048 resolution
        else ppm2[i]= 800 + (int) (channel[i] * 1.172447);
      }
    }
    lock1= !lock1;  // new stream is now valid, switch it. Timer interrupt will output next channel from new reading
// PCA9685
// map the SBUS 11 bits to 900 to 2100 uS servo pulses
    for (i=1 ; i <= maxServos; i++) pwm.writeMicroseconds(i-1, map(channel[i],0,2047,900,2100));
// end PCA9685
    if ((channel[3] < signalLost) || (channel[0] & 8)) { // if signal lost disable PPM out
      pTrain= 0;
      TIMSK1= 0;
      digitalWrite(PPM_out, LOW);
#ifdef SHOWSIGNAL
      digitalWrite(LED_noSignal, LEDON);
#endif
    }
    else if (pTrain == 0) { // if we got signal and PPM is idle
      OCR1A= trainSep;  // start train separation pulse= 10.5mS (1/3)
      pTrain= trainSepStart; // start new channel separation (PPM output was LOW)
      digitalWrite(PPM_out, HIGH); // start pulse for channel sep
      TCNT1= 0; // reset timer counter to 0
      TIMSK1= bit(OCIE1A);  // start timer
#ifdef SHOWSIGNAL
      digitalWrite(LED_noSignal, LEDOFF);
#endif
    }
  }
  if (lastReception != 0) if ((millis() - lastReception) > timeOutMs) lastReception= 0;
  if (lastReception == 0) {
    pTrain= 0;
    TIMSK1= 0;
    digitalWrite(PPM_out, LOW);
#ifdef SHOWSIGNAL
    digitalWrite(LED_noSignal, LEDON);
#endif
  }
}

Driving Up to 12 Servos (and PPM) With Only a Nano

SBUS2PPM2PWM12_Nano.jpg

Now, let’s squeeze an Arduino Nano to the max and drive an 8 channel PPM output plus 12 servos without external hardware.

The next sketch decodes the SBUS data and creates an array with the microsecond values for the 12 servos and the whole PPM pulse train. This array is then sorted (dragging the port number and LOW/HIGH state) and pulses are output to the corresponding pin in microsecond order using a very tight timing loop. Which requires us to disable (reset) Arduino’s watchdog timer or it will interrupt servo output resetting every 8 seconds (I know this empirically LOL).

No interrupts are used in this sketch. PPM output is “about right”. Works with Nano or UNO (12 servos + 1 PPM) and Pro Micro or Leonardo (9 servos + 1 PPM).

CODE:

// SBUS to PPM and PWM decoder
// (c) 2023 Pablo Montoreano

/*********************************************************
  @file       SBUS2PPM8PWM12.ino
  @brief      SBUS to PPM protocol converter and PWM servo driver
  @author     Pablo Montoreano
  @copyright  2023 Pablo Montoreano
  @version    1.1 - 05/oct/23  - bug fix (0x0F is a valid SBUS value)

  no 3rd party libraries used
  no additional hardware used (PCA9685 not necessary)

  Arduino Pro Micro with 1 PPM output and 9 PWM servo channels (debugging possible).
  Arduino Nano or UNO supported with 1 PPM and 12 PWM servo outputs but no debugging possible.
*********************************************************/

// 8 channel PPM output on Nano pin A0, Pro Micro pin 14
// 12 PWM Servo outputs on Nano pins D2 to D13
// or 9 PWM Servo outputs on Pro Micro pins 2 to 10
// signal LED (ON= no signal) on Nano or Pro Micro pin A3.
// failsafe LED (ON= failsafe) on Nano pin A4 or Pro Micro pin A0.
// low resolution LED on Nano pin A5 or Pro Micro pin A1.
// config pin A2 (Nano) or pin 16/MOSI (Pro Micro). Use 10K pullup, and jumper to ground

// Use 470 Ohm resistors for all LEDs

// **** PPM ****
// PPM signal is idle high, low 0.5 ms (start), 0.400 to 1.600 milliseconds channel pulse, 0.5 ms channel separation
// PPM output will be driven LOW when there is no signal or SBUS reports failsafe
// PPM pulse train separation is 10.5 ms.
// Max time for an 8 channel PPM train where all pulses are 1.6mS is 27.8mS
// PPM High/Low resolution (2048/1024) config jumper (1024 when pulled LOW)
// this config is used to reduce PPM flight simulator shaking

// **** Servos PWM ***
// use suitable external power supply for Servos ***do NOT use USB power***
// PWM servo pulses are 900 to 2100uS, 20mS minimum pulse separation
// output of 12 servos is done concurrently within the first 2.1mS (max pulse width)
// servo pulse separation is not critical so the 20mS depend on the end of the PPM stream

#include <avr/wdt.h>  // we need to disable watchdog interruptions during servo output

#define LEDON HIGH
#define LEDOFF LOW
static const unsigned int PPM_out= 14; // PPM output port (A0)
static const unsigned int portCfg= 16; // resolution configuration (A2), jumper to GND= 10 bits
static const unsigned int LED_failsafe= 18; // failsafe LED (A4)
static const unsigned int LED_lowRes= 19;   // low resolution LED (A5)
#ifdef __AVR_ATmega32U4__
static const unsigned int LED_noSignal= 21; // no signal LED (A2)
static const unsigned int maxServos= 9; // only 9 servos (ports 2 to 10) if using Pro Micro
#endif
#ifdef __AVR_ATmega328P__
static const unsigned int LED_noSignal= 17; // no signal LED (A3)
static const unsigned int maxServos= 12;  // number of servos. We will output up to 12 servos in ports 2 to 13
#endif
static const unsigned int maxChan= 8;  // number of PPM channels in pulse train
static const unsigned int trainSepStart= (maxChan+1)<<1;  // 2*(maxChan+1) start of train separation pulse pointer
static const unsigned int trainSep= 21000-5000;  // 10500 uS * 2 MHz (0.5 uS per tick using timer prescaler= 8) - 2.5mS overhead
static const unsigned int chanSep= 1000;    // 500 uS * 2 MHz
static const unsigned long servoSep= 20;     // servo pluse separation in millis
// failsafe in channel 3 when value below signalLost
// for chinese receivers that do not report failsafe in SBUS (i.e. Microzone MC9002)
static const unsigned int signalLost= 100;
static const unsigned int localFailsafe= (signalLost << 1)+1800; // 0.5uS per tick starting from 900uS
static const unsigned long timeOutMs= 1000;    // timeout if no packet received after 1 sec
static const unsigned long SBUSbaudRate= 100000; // SBUS baudrate 100K

static unsigned int sbusByte, byteNmbr;
static byte frame[25];  // SBUS frame
static unsigned int channel[17]; // 16 channels in SBUS stream + channels 17, 18 & failsafe in channel[0]
static unsigned int ppm[maxChan+1];  // double buffering for interrupt data
static unsigned long lastReception;  // millis of last reception
static unsigned long lastServoPulse;
static unsigned int tempPulse;
static unsigned int numPulses;
static bool resol1024;  // low (1024) resolution flag
static bool gotData,updData;
static bool failsafeMode;
static bool noSignalMode;
static bool newFrame;
static unsigned int i,j; // general counters

struct pulseArray {
  unsigned int pulseWidth;  // pulse width in uS
  unsigned int outputPin;   // pin number
  unsigned int outputLevel; // LOW or HIGH
};

// array dimension: pulses for servos + 1 for array[0] + 2 pulses for each PPM + 2 for trainSep
static pulseArray pulses[maxServos+1+((maxChan+1)<<1)];

void initTimer1() {
// setup timer prescaler to 8. This is equivalent to a 2MHz timer (16MHz/8), equal to 0.5uS per tick
  cli();  // clear interrupts
  TCCR1A= 0;  // disable compare mode
  TCCR1B= 0;  // no clock source (timer stopped)
  TCNT1= 0;
  TCCR1B= bit(CS11);  // only CS11 -> prescaler = 8
  //  CS12    CS11    CS10
  //  0       0       0     no clock source, timer stopped
  //  0       0       1     no prescale
  //  0       1       0     clk/8
  //  0       1       1     clk/64
  //  1       0       0     clk/256
  //  1       0       1     clk/1024
  //  1       1       0     extclk falling
  //  1       1       1     extclk rising
  TIMSK1= 0;  // disable timer1
  sei();  // enable interrupts
}

void addPulse(unsigned int thisPW, unsigned int thisOP, unsigned int thisOL) {  // add a pulse to the list
  numPulses++;
  pulses[numPulses].pulseWidth= thisPW;
  pulses[numPulses].outputPin= thisOP;
  pulses[numPulses].outputLevel= thisOL;
}

void decodeChannels() {
int bitPtr;   // bit pointer in SBUS byte being decoded
int bytePtr;  // byte pointer in SBUS frame
int chan;     // channel number being decoded
int chanBit;  // current channel bit being proccessed

  channel[0]= frame[23];
  bytePtr= 1;
  bitPtr= 0;
  for (chan= 1; chan <= 16; chan++){
    channel[chan]= 0;
    for (chanBit= 0; chanBit < 11; chanBit++) {
      channel[chan] |= ((frame[bytePtr] >> bitPtr) & 1) << chanBit;
      if (++bitPtr > 7) { // change byte every 8 bits
        bitPtr=0;
        bytePtr++;
      }
    }
  }
}

bool getFrame() {
#ifdef __AVR_ATmega32U4__ // Arduino Pro Micro expected
  while (Serial1.available()) {
    sbusByte= Serial1.read();
#endif
#ifdef __AVR_ATmega328P__ // Arduino nano detected, use Serial only
  while (Serial.available()) {
    sbusByte= Serial.read();
#endif
// Bug fix: 0x0F is a valid value in the SBUS stream
// so we use a flag to detect the end of a packet (0) before enabling the capture of next frame
    if ((sbusByte == 0x0F) && newFrame) { // if this byte is SBUS start byte start counting bytes
      newFrame= false;
      byteNmbr= 0;
    }
    else if (sbusByte == 0) newFrame= true; // end of frame, enable start of next frame (to distinguish from 0x0F channel values)
    if (byteNmbr <= 24) { // 25 bytes total
      frame[byteNmbr]= sbusByte;  // save a byte
      byteNmbr++;
// if a valid frame is complete (check pointer position, start byte 0F and end byte 0)
      if ((byteNmbr == 25) && (sbusByte == 0) && (frame[0] == 0x0F)) return true;
// byteNmbr is now > 24, so this routine will now wait for next frame
    }
  }
  return false; // keep buffering
}

void sortPulses() { // a simple bubble sort
  for (i= 1; i < numPulses; i++) {
    for (j= i+1; j <= numPulses; j++) {
      if (pulses[j].pulseWidth < pulses[i].pulseWidth) {
        tempPulse= pulses[i].pulseWidth;
        pulses[i].pulseWidth= pulses[j].pulseWidth;
        pulses[j].pulseWidth= tempPulse;
        tempPulse= pulses[i].outputPin;
        pulses[i].outputPin= pulses[j].outputPin;
        pulses[j].outputPin= tempPulse;
        tempPulse= pulses[i].outputLevel;
        pulses[i].outputLevel= pulses[j].outputLevel;
        pulses[j].outputLevel= tempPulse;
      }
    }
  }
}

void setup() {
  pinMode(PPM_out, OUTPUT);
  digitalWrite(PPM_out, LOW);  // disable PPM output
  pinMode(LED_noSignal, OUTPUT);
  pinMode(LED_failsafe, OUTPUT);
  pinMode(LED_lowRes, OUTPUT);
  for (i= 2; i <= (maxServos + 1); i++) { // all servos to idle (LOW)
    pinMode(i, OUTPUT);
    digitalWrite(i, LOW);
  }
  digitalWrite(LED_noSignal, LEDON);  // assume there is no signal on startup
  digitalWrite(LED_failsafe, LEDOFF);
  digitalWrite(LED_lowRes, LEDOFF);
  pinMode(portCfg, INPUT_PULLUP);
// Arduino Pro Micro pin definitions
#ifdef __AVR_ATmega32U4__
  Serial1.begin(SBUSbaudRate, SERIAL_8E2);
#endif
// Arduino nano pin definitions
#ifdef __AVR_ATmega328P__
  Serial.begin(SBUSbaudRate, SERIAL_8E2);
#endif
  byteNmbr= 255; // invalidate SBUS byte number
  lastReception= 0;
  newFrame= false;
  failsafeMode= false;
  noSignalMode= true;
  gotData= false;
  updData= false;
  lastServoPulse= millis();
  initTimer1(); // initialize timer registers
}

void loop() {
  if (getFrame()) {
    lastReception= millis();  // we have just received this
    decodeChannels(); // decode channel bitstream into 0 - 2047 channel values from frames into channels[i]
    resol1024= (digitalRead(portCfg) == LOW); // can change resolution while running
    digitalWrite(LED_lowRes, resol1024 ? LEDON : LEDOFF); // reflect in LED
    for (i= 1; i <= maxChan; i++) {
      // each PPM channel pulse is 400 to 1600 uS while SBUS data is 0 to 2047, ajust values to timer
      // ((int) (channel[i] * 1200.0 / 2047.0) + 400) << 1; simplified with a single float operation
      // We multiply by 2 with the << 1 because we have 2 ticks per uS in the timer and we are working in ticks
      // as an alternative we can use map(channel[i],0,2047,800,3200);
      // or map(channel[i] >> 1,0,1023,800,3200); for half resolution
      if (resol1024)
        ppm[i]= 800 + (int) ((channel[i] >> 1) * 2.344895);  // low (1024) resolution
      else
        ppm[i]= 800 + (int) (channel[i] * 1.172447);  // full 2048 resolution
    }
    noSignalMode= false;
    digitalWrite(LED_noSignal, LEDOFF);
    if ((channel[3] < signalLost) || (channel[0] & 8)) { // if signal lost disable PPM out and enable failsafe
      digitalWrite(LED_failsafe, LEDON);
      lastReception= 0; // we use lastReception as a no signal flag
      failsafeMode= true;
    }
    else if (failsafeMode) { // if we got signal and PPM is idle
      digitalWrite(LED_failsafe, LEDOFF);
      failsafeMode= false;
    }
    gotData= true;
    updData= true;
  }
  if (lastReception != 0) if ((millis() - lastReception) > timeOutMs) {  // SBUS cable disconnected
    lastReception= 0;
    digitalWrite(LED_noSignal, LEDON);
    noSignalMode= true;
    updData= true; // need to update servo data with failsafe
  }
  if (noSignalMode || failsafeMode) digitalWrite(PPM_out, LOW); // invalidate PPM output
  if (updData) {
// prepare pulses for the servos
    updData=false;
    numPulses= 0;
    // map channels (0-2047) into servo pulses in ticks (900-2100 uS x2)
    for (i= 1; i <= maxServos; i++) addPulse(((resol1024) ? map(channel[i] >> 1,0,1023,1800,4200) : map(channel[i],0,2047,1800,4200)),i+1,LOW);
    if (noSignalMode) pulses[3].pulseWidth= localFailsafe;  // if no signal we can't use SBUS failsafe
    if (!(noSignalMode || failsafeMode)) {  // if we got new data -> PPM active
      tempPulse= 0;
      for (i= 1; i <= maxChan; i++) { // create PPM stream in contiguous pulses (time added, not concurrent)
        tempPulse+= chanSep;
        addPulse(tempPulse, PPM_out, HIGH); // start for channel
        tempPulse+= ppm[i];
        addPulse(tempPulse, PPM_out, LOW);
      }
      tempPulse+= chanSep;
      addPulse(tempPulse, PPM_out, HIGH);
      tempPulse+= trainSep;
      addPulse(tempPulse, PPM_out, HIGH); // this will not change PPM output, but will make sure 10.5mS elapsed
    }
    sortPulses(); // sort the pulses so we can output in ascending (time) order
  }

// even if there is no signal we drive the servos (in case failsafe is active channel 3 should have changed)
  if (((millis() - lastServoPulse) >= servoSep) && gotData) { // if at least 20mS elapsed
    lastServoPulse= millis() + 1; // shortest servo pulse is about 1 mS, start counting servo pulse separation
    // servo pulses (concurrent)
    wdt_reset();  // lets make sure the watchdog does not interrupt this
    digitalWrite(PPM_out, LOW); // start (or disable) PPM
    for (i= 1; i <= maxServos; i++) digitalWrite(i+1, HIGH); // start pulse for all servos
    TCNT1= 0; // reset timer1 to start measuring pulses
    for (i= 1; i <= numPulses; i++) {
      while (TCNT1 < pulses[i].pulseWidth); // hang here until pulse[i] expires (sorted)
      digitalWrite(pulses[i].outputPin, pulses[i].outputLevel); // ok, pulse time expired
    }
    wdt_reset();
    yield(); // phew, free some CPU time now (not necessary because we are at the end of the loop, but doesn't hurt)
  }
}

Interrupt Driven PPM With 12 Servos Using a Nano

Reaching the end of this instructable, how can we improve the sketch in step 3? Obviously we should use interrupts and double buffering to build the “flawless” PPM stream we are used to, but if we have to manage 12 servos and PPM in the interrupt routine it would be incredibly complicated.

What would happen if we needed to output 2 pulses that are 4uS apart? Remember a flawless PPM stream is asynchronous, we can’t assume this will not happen.

So, we can’t do it… except… wait… what if we output the 12 servo pulses during the PPM train separation? We have 10.5mS and the longest servo pulse is 2.1mS.

We already output the 12 servo pulses concurrently in the previous sketch. We only need to add a flag (for the main loop) during the PPM pulse separation pause, so, let’s do it!

The hardware is the same from STEP 3, only the firmware changes.

Next sketch works with Nano or UNO (12 servos + 1 PPM), Pro Micro or Leonardo (9 servos + 1 PPM). PPM signal is interrupt driven and PWM servo signals are output concurrently for all servos during the PPM train separation pause.

CODE:

// SBUS to PPM and PWM decoder (with interrupt driven PPM)
// (c) 2023 Pablo Montoreano
// for Arduino Nano or UNO (no debugging possible).
// Arduino Pro Micro supported but limited to 9 PWM servo channels (debugging possible).

/*********************************************************
  @file       SBUS2PPM8PWM12INT.ino
  @brief      SBUS to PPM protocol converter (interrupt driven) and PWM servo driver
  @author     Pablo Montoreano
  @copyright  2023 Pablo Montoreano
  @version    1.1 - 05/oct/23 - bug fix (0x0F is a valid SBUS value)

  This version generates a flawless PPM stream using interrupts with double buffering for PPM data

  no 3rd party libraries used
  no additional hardware used (PCA9685 not necessary)

  Arduino Pro Micro with 1 PPM output and 9 PWM servo channels (debugging possible).
  Arduino Nano or UNO supported with 1 PPM and 12 PWM servo outputs but no debugging possible.
*********************************************************/

// 8 channel timer interrupt driven PPM output on Nano pin A0, Pro Micro pin 14
// 12 PWM Servo outputs on Nano pins D2 to D13
// or 9 PWM Servo outputs on Pro Micro pins 2 to 10
// signal LED (ON= no signal) on Nano or Pro Micro pin A3.
// failsafe LED (ON= failsafe) on Nano pin A4 or Pro Micro A0.
// low resolution LED on Nano pin A5 or Pro Micro pin A1.
// config pin A2 (Nano) or 16/MOSI (Pro Micro). Use 10K pullup, and jumper to ground

// Use 470 Ohm resistors for all LEDs

// **** PPM ****
// PPM signal is idle high, low 0.5 ms (start), 0.400 to 1.600 milliseconds channel pulse, 0.5 ms channel separation
// PPM output will be driven LOW when there is no signal or SBUS reports failsafe
// PPM pulse train separation is 10.5 ms. The whole PPM stream is continuous and driven by timer interrupts.
// Max time for an 8 channel PPM train where all pulses are 1.6mS is 27.8mS
// PPM High/Low resolution (2048/1024) config jumper (1024 when pulled LOW)
// this config is used to reduce PPM flight simulator shaking

// **** Servos PWM ***
// use suitable external power supply for Servos ***do NOT use USB power***
// PWM servo pulses are 900 to 2100uS, 20mS minimum pulse separation
// concurrent output of the 12 servos is done during PPM train separation using a max of 2.1mS of the 10.5mS train sep
// servo pulse separation is not critical so the 20mS pulse separation is measured in the main loop using millis()
// the servo pulses are delayed until the start of the PPM train separation if necessary

#include <avr/wdt.h>  // we need to disable watchdog during servo output

#define LEDON HIGH
#define LEDOFF LOW
static const unsigned int PPM_out= 14; // PPM output port (A0)
static const unsigned int portCfg= 16; // resolution configuration (A2), jumper= 10 bits
static const unsigned int LED_failsafe= 18; // failsafe LED (A4)
static const unsigned int LED_lowRes= 19;   // low resolution LED (A5)
#ifdef __AVR_ATmega32U4__
static const unsigned int LED_noSignal= 21; // no signal LED (A2)
static const unsigned int maxServos= 9; // only 9 servos (ports 2 to 10) if using Pro Micro
#endif
#ifdef __AVR_ATmega328P__
static const unsigned int LED_noSignal= 17; // no signal LED (A3)
static const unsigned int maxServos= 12;  // number of servos. We will output up to 12 servos in ports 2 to 13
#endif
static const unsigned int maxChan= 8;  // number of PPM channels in pulse train
static const unsigned int trainSepStart= (maxChan+1)<<1;  // 2*(maxChan+1) start of train separation pulse pointer
static const unsigned int trainSep= 21000;  // 10500 uS * 2 MHz (0.5 uS per tick using timer prescaler= 8)
static const unsigned int chanSep= 1000;    // 500 uS * 2 MHz
static const unsigned long servoSep= 20;     // servo pluse separation in millis
// failsafe in channel 3 when value below signalLost
// for chinese receivers that do not report failsafe in SBUS (i.e. Microzone MC9002)
static const unsigned int signalLost= 100;
static const unsigned int localFailsafe= (signalLost << 1)+1800; // 0.5uS per tick starting from 900uS
static const unsigned long timeOutMs= 1000;    // timeout if no packet received after 1 sec
static const unsigned long SBUSbaudRate= 100000; // SBUS baudrate 100K

static unsigned int sbusByte, byteNmbr;
static byte frame[25];  // SBUS frame
static unsigned int channel[17]; // 16 channels in SBUS stream + channels 17, 18 & failsafe in channel[0]
static unsigned int ppm1[maxChan+1], ppm2[maxChan+1];  // double buffering for interrupt data
static bool lock1;  // use pulse train 2 when 1 locked
static unsigned long lastReception;  // millis of last reception
static unsigned long lastServoPulse;
static unsigned int tempPulse;
static volatile unsigned int pTrain;  // pulse train pointer
static volatile bool inPause; // true during PPM train separation
static bool resol1024;  // low (1024) resolution flag
static bool gotData, updData;
static bool failsafeMode;
static bool noSignalMode;
static unsigned int i,j; // general counters
static bool newFrame;

struct pulseArray {
  unsigned int pulseWidth;  // pulse width in uS
  unsigned int outputPin;   // pin number
};

static pulseArray pulses[maxServos+1];  // 10 pulses for servos + 1 for [0]
static unsigned int newPulseWithds[maxServos+1];

// Timer1 interrupt
ISR (TIMER1_COMPA_vect) {
  TIMSK1= 0;  // disable timer1 interrupt
  if (pTrain == 0)
    digitalWrite(PPM_out, LOW);  // disable PPM output (just in case)
  else  {
    pTrain++;
    if (pTrain < trainSepStart) { // still processing channels
      if (pTrain & 1) { // now odd, process channel separation
        digitalWrite(PPM_out, LOW);
        OCR1A= chanSep; // channel separation pulse= 0.5mS
      }
      else {
        digitalWrite(PPM_out, HIGH); // start of channel output (0.4 to 1.6 mS)
        // pTrain counts both the pulse separations and the channel pulses, that's why we have to divide
        // by two the ppm pulses index with the >> 1
        if (lock1) OCR1A= ppm2[pTrain >> 1];  // if ppm1 array is being written to use ppm2
        else OCR1A= ppm1[pTrain >> 1];
      }
    }
    else if (pTrain > trainSepStart) {  // end of 10.5mS pulse train separation, start a channel separation pulse
      digitalWrite(PPM_out, LOW);
      OCR1A= chanSep; // channel separation pulse= 0.5mS
      pTrain= 1; // start new pulse train
      inPause= false;
    }
    else {  // pTrain == trainSepStart (start pulse train separation)
      digitalWrite(PPM_out, HIGH);
      OCR1A= trainSep;
      inPause= true;
    }
    TIMSK1= bit(OCIE1A);  // start timer interrupt
  }
}

void initTimer1() {
// setup timer prescaler to 8. This is equivalent to a 2MHz timer (16MHz/8), equal to 0.5uS per tick
  cli();  // clear interrupts
  TCCR1A= 0;  // disable compare mode (for timer 3 use TCCR3A)
  TCCR1B= 0;  // no clock source (timer stopped)
  TCNT1= 0;
  OCR1A= trainSep; // defaults to pulse separation
  TCCR1B= bit(WGM12) | bit(CS11);  // WGM12 -> CTC(Clear Timer on Compare Match), only CS11 -> prescaler = 8
  //  CS12    CS11    CS10
  //  0       0       0     no clock source, timer stopped
  //  0       0       1     no prescale
  //  0       1       0     clk/8
  //  0       1       1     clk/64
  //  1       0       0     clk/256
  //  1       0       1     clk/1024
  //  1       1       0     extclk falling
  //  1       1       1     extclk rising
  TIMSK1= 0;  // disable timer1 interrupt
  sei();  // enable interrupts
}

void decodeChannels() {
int bitPtr;   // bit pointer in SBUS byte being decoded
int bytePtr;  // byte pointer in SBUS frame
int chan;     // channel number being decoded
int chanBit;  // current channel bit being proccessed

  channel[0]= frame[23];
  bytePtr= 1;
  bitPtr= 0;
  for (chan= 1; chan <= 16; chan++){
    channel[chan]= 0;
    for (chanBit= 0; chanBit < 11; chanBit++) {
      channel[chan] |= ((frame[bytePtr] >> bitPtr) & 1) << chanBit;
      if (++bitPtr > 7) { // change byte every 8 bits
        bitPtr=0;
        bytePtr++;
      }
    }
  }
}

bool getFrame() {
#ifdef __AVR_ATmega32U4__ // Arduino Pro Micro expected
  while (Serial1.available()) {
    sbusByte= Serial1.read();
#endif
#ifdef __AVR_ATmega328P__ // Arduino nano detected, use Serial only
  while (Serial.available()) {
    sbusByte= Serial.read();
#endif
// Bug fix: 0x0F is a valid value in the SBUS stream
// so we use a flag to detect the end of a packet (0) before enabling the capture of next frame
    if ((sbusByte == 0x0F) && newFrame) { // if this byte is SBUS start byte start counting bytes
      newFrame= false;
      byteNmbr= 0;
    }
    else if (sbusByte == 0) newFrame= true; // end of frame, enable start of next frame (to distinguish from 0x0F channel values)
    if (byteNmbr <= 24) { // 25 bytes total
      frame[byteNmbr]= sbusByte;  // save a byte
      byteNmbr++;
// if a valid frame is complete (check pointer position, start byte 0F and end byte 0)
      if ((byteNmbr == 25) && (sbusByte == 0) && (frame[0] == 0x0F)) return true;
// byteNmbr is now > 24, so this routine will now wait for next frame
    }
  }
  return false; // keep buffering
}

void sortPulses() {
  for (i= 1; i < maxServos; i++) {
    for (j= i+1; j <= maxServos; j++) {
      if (pulses[j].pulseWidth < pulses[i].pulseWidth) {
        tempPulse= pulses[i].pulseWidth;
        pulses[i].pulseWidth= pulses[j].pulseWidth;
        pulses[j].pulseWidth= tempPulse;
        tempPulse= pulses[i].outputPin;
        pulses[i].outputPin= pulses[j].outputPin;
        pulses[j].outputPin= tempPulse;
      }
    }
  }
}

void setup() {
  pinMode(PPM_out, OUTPUT);
  digitalWrite(PPM_out, LOW);  // disable PPM output
  pinMode(LED_noSignal, OUTPUT);
  pinMode(LED_failsafe, OUTPUT);
  pinMode(LED_lowRes, OUTPUT);
  for (i= 2; i <= (maxServos + 1); i++) { // all servos to idle (LOW)
    pinMode(i, OUTPUT);
    digitalWrite(i, LOW);
  }
  digitalWrite(LED_noSignal, LEDON);
  digitalWrite(LED_failsafe, LEDOFF);
  digitalWrite(LED_lowRes, LEDOFF);
  pinMode(portCfg, INPUT_PULLUP);
// Arduino Pro Micro pin definitions
#ifdef __AVR_ATmega32U4__
  Serial1.begin(SBUSbaudRate, SERIAL_8E2);
#endif
// Arduino nano pin definitions
#ifdef __AVR_ATmega328P__
  Serial.begin(SBUSbaudRate, SERIAL_8E2);
#endif
  byteNmbr= 255; // invalidate SBUS byte number
  lastReception= 0;
  newFrame= false;
  failsafeMode= false;
  noSignalMode= true;
  pTrain= 0;  // idle
  lock1= true;
  inPause= false;
  gotData= false; // if we ever received data this is true
  updData= false; // true if data changed in the loop
  lastServoPulse= millis();
  initTimer1(); // initialize timer registers
}

void loop() {
  if (getFrame()) {
    lastReception= millis();
    decodeChannels(); // decode channel bitstream into 0 - 2047 channel values
    resol1024= (digitalRead(portCfg) == LOW); // can change resolution while running
    digitalWrite(LED_lowRes, resol1024 ? LEDON : LEDOFF); // reflect in LED if we are not showing signal
    for (i= 1; i <= maxChan; i++) {
      // each PPM channel pulse is 400 to 1600 uS while SBUS data is 0 to 2047, ajust values to timer
      // ((int) (channel[i] * 1200.0 / 2047.0) + 400) << 1; simplified with a single float operation
      // We multiply by 2 with the << 1 because we have 2 ticks per uS in the timer and we are working in uS
      // as an alternative we can use map(channel[i],0,2047,800,3200);
      // or map(channel[i] >> 1,0,1023,800,3200); for half resolution
      if (resol1024) {
        if (lock1) ppm1[i]= 800 + (int) ((channel[i] >> 1) * 2.344895);  // low (1024) resolution
        else ppm2[i]= 800 + (int) ((channel[i] >> 1) * 2.344895);
      }
      else {
        if (lock1) ppm1[i]= 800 + (int) (channel[i] * 1.172447);  // full 2048 resolution
        else ppm2[i]= 800 + (int) (channel[i] * 1.172447);
      }
    }
    lock1= !lock1;  // new stream is now valid, switch it. Timer interrupt will output next channel from new reading
    noSignalMode= false;
    digitalWrite(LED_noSignal, LEDOFF);
    if ((channel[3] < signalLost) || (channel[0] & 8)) { // if signal lost disable PPM out
      lastReception= 0; // we use lastReception as a no signal flag
      digitalWrite(LED_failsafe, LEDON);
      failsafeMode= true;
    }
    else if (pTrain == 0) { // if we got signal and PPM is idle
      OCR1A= trainSep;  // start train separation pulse= 10.5mS (1/3)
      pTrain= trainSepStart; // start new channel separation (PPM output was LOW)
      digitalWrite(PPM_out, HIGH); // start pulse for channel sep
      TCNT1= 0; // reset timer counter to 0
      TIMSK1= bit(OCIE1A);  // enable Timer1 interrupts
      digitalWrite(LED_failsafe, LEDOFF);
      failsafeMode= false;
    }
    gotData= true;
    updData= true;
  }
  if (lastReception != 0) if ((millis() - lastReception) > timeOutMs) {  // SBUS cable disconnected
    lastReception= 0;
    digitalWrite(LED_noSignal, LEDON);
    noSignalMode= true;
    updData= true;
  }
  if (noSignalMode || failsafeMode) {
    TIMSK1= 0;  // disable timer1 interrupts
    pTrain= 0;  // PPM pulse train to idle
    digitalWrite(PPM_out, LOW); // invalidate PPM output
    TCNT1= 0; // start from 0. Timer interrupts are disabled (TIMSK1= 0 above)
    OCR1A= trainSep;  // timer has to keep running for servo pulses
    inPause= true;
  }
  if (updData)   {
    updData= false;
// prepare pulses for the servos
    for (i= 1; i <= maxServos; i++){
      if (resol1024)
        pulses[i].pulseWidth= map(channel[i] >> 1,0,1023,1800,4200);
      else
        pulses[i].pulseWidth= map(channel[i],0,2047,1800,4200);
      pulses[i].outputPin= i+1;
    }
    if (noSignalMode) pulses[3].pulseWidth= localFailsafe;  // if no signal we can't use SBUS failsafe
    sortPulses();
  }
// even if there is no signal we drive the servos (in case failsafe is active channel 3 should have changed)
  if ((millis() - lastServoPulse) < servoSep)
    inPause= false; // invalidate pause mode if servoSep has not yet elapsed
  else if (inPause && gotData) { // if at least 20mS elapsed and PPM is pausing output servo pulses
    // servo pulses (concurrent)
    inPause= false;
    wdt_reset();  // lets make sure the watchdog does not interrupt this
    for (i= 1; i <= maxServos; i++) {
// we can't touch the timer but we can use it. Add current timer counter to pulse width. We have a bit less than 10.5mS to work here
// also we can't modify pulses[i] because we don't know if it was updated in this loop or not
// we must not accumulate TCNT1 in pulseWidth, it has to be preserved for next loop in case we do not receive another frame
      newPulseWithds[i]= pulses[i].pulseWidth+TCNT1;
      digitalWrite(i+1, HIGH); // start pulse for all servos
    }
    for (i= 1; i <= maxServos; i++) {
      while (TCNT1 < newPulseWithds[i]); // hang here until pulse[i] expires (sorted and TCNT1 adjusted)
      digitalWrite(pulses[i].outputPin, LOW); // ok, pulse time expired, finish Servo pulse
    }
    wdt_reset();
    yield(); // free some CPU time now
    lastServoPulse= millis(); // all servo pulses are done, now wait 20mS for next pulse
  }
}

PPM to PWM Servo Decoder

As a bonus, now that we know the PPM protocol, we can decode it and use the same hardware from STEP 3 above to drive 8 servos with an Arduino Nano.

We now need to use hardware interrupts to capture the PPM pulse train and output PWM servo pulses concurrently.

This program also captures and displays (via PC serial port at 115200 baud) the 8 servo pulses (in microseconds).

We will use port 2 for the PPM input because we need an interrupt enabled port. Servo outputs start from port 3 (port 3 is channel 1, port 4 channel 2, etc).

Arduino Nano valid ports for external interrupts are ports 2 and 3 only. In the Pro Micro you can use ports 0,1,2,3 or 7.

CODE:

// PPM to PWM servo decoder
// (c) 2023 Pablo Montoreano

/*********************************************************
 @file      PPM2PWM8.ino
 @brief     PPM to PWM Servo decoder
 @author    Pablo Montoreano
 @copyright 2023 Pablo Montoreano
 @version   1.0

 no 3rd party libraries used
 no additional hardware used

 Arduino Leonardo, Pro Micro, Nano or UNO
*********************************************************/

// 8 PWM Servo outputs on Pro Micro pins 2 to 9 or Nano pins D2 to D9

// **** PPM ****
// PPM signal is idle high, low 0.5 ms (start), 0.400 to 1.600 milliseconds channel pulse, 0.5 ms channel separation
// PPM pulse train separation is 10.5 ms.
// Max time for an 8 channel PPM train where all pulses are 1.6mS is 27.8mS

// **** Servos PWM ***
// use suitable external power supply for Servos ***do NOT use USB power***
// PWM servo pulses are 900 to 2100uS, 20mS minimum pulse separation
// output of 8 servos is done while the PPM stream is received
// servo pulse separation is not critical so the 20mS depend on the end of the PPM stream

// PPM input port:
// only ports 2 and 3 are usable for interrupts in the Nano or UNO
// ports 0,1,2,3 and 7 in the Leonardo or Pro Micro; if you use ports 0 or 1 do not initialize the Serial port
static const unsigned int PPM_in= 2; // D2
static const int maxChannels= 8; // number of PPM channels in pulse train
static const unsigned long minSep= 7500; // min pulse separation
static const unsigned long maxSep= 15000; // max pulse separation
static const unsigned long minPulse= 900;  // minimum valid servo pulse
static const unsigned long maxPulse= 2100; // max valid servo pulse
static const unsigned int servoPinDelta= 2;
static volatile unsigned long myMicros;
static volatile unsigned long startTiming;
static volatile long capturePPM[10];
static volatile int pTrain; // pulse train pointer
static unsigned int i;

void pulsePPM () {
 myMicros= micros()-startTiming;
 if ((myMicros >= minPulse) && (myMicros <= maxPulse) && (pTrain > 0)) {
   digitalWrite(pTrain+servoPinDelta, LOW);
   capturePPM[pTrain]= myMicros;
   if (++pTrain <= maxChannels)
     digitalWrite(pTrain+servoPinDelta, HIGH);
   else
     pTrain= 0;
   capturePPM[9]= -1; // clear error
 }
 else if ((myMicros >= minSep) && (myMicros <= maxSep)) { // train separation pulse
   pTrain= 1;
   digitalWrite(pTrain+servoPinDelta, HIGH);
   capturePPM[0]= myMicros; // save pulse separation
   capturePPM[9]= -1; // clear error
 } 
 else { // invalid pulse
   digitalWrite(pTrain+servoPinDelta, LOW); // stop this servo
   capturePPM[9]= myMicros; // save invalid pulse
   pTrain= -1;
 }
 startTiming+= myMicros; // prepare to measure next pulse (makes starTiming= micros() above)
}

void setup() {
 pinMode(PPM_in, INPUT);
 Serial.begin(115200);
 for (i= 1; i <= maxChannels; i++) { // all servos to idle (LOW)
   pinMode(i+servoPinDelta, OUTPUT);
   digitalWrite(i+servoPinDelta, LOW);
   capturePPM[i]= 0;
 }
 capturePPM[9]= -1; // clear error
 while (!Serial);
 Serial.println("Start");
 pTrain= -1;
 startTiming= micros();
 attachInterrupt(digitalPinToInterrupt(PPM_in), pulsePPM, FALLING);
}

void loop() {
 /*
 if ((micros()-startTiming) > 30000) { // max time is 27.8mS
   pTrain= 0;
   startTiming= micros();
 }*/

 if (pTrain < 0) {
   Serial.print("No Signal: ");
   Serial.println(capturePPM[9]);
 }
 else {
   for (i=0; i <= maxChannels; i++) {
     Serial.print(capturePPM[i]);
     if (i < maxChannels)
       Serial.print(",");
     else
       Serial.println();
   }
 }
 delay(1000);
}

PPM PC Joystick

Now that we captured the PPM stream, the obvious application would be a PPM joystick.

In this case we will use an Arduino Pro Micro (or Leonardo) with the same hardware used in STEP 3 of PART 1 of this instructable. This code will not work in a Nano or UNO.

This is only a joystick, no PWM servo outputs.

Once again, this joystick does NOT emulate a copy protection dongle; you will need a free (or properly licensed) flight simulator supporting third party joysticks to use it.

It uses the Joystick (2.1.1) library by Matthew Heironimus and requires an MCU which can emulate HID devices like an Arduino Pro Micro or Leonardo.

CODE:

// PPM to Joystick interface
// (c) 2023 Pablo Montoreano

/*********************************************************
  @file       PPM2JOY.ino
  @brief      PPM to Joystick interface
  @author     Pablo Montoreano
  @copyright  2023 Pablo Montoreano
  @version    1.0

  3rd party library: Joystick (2.1.1) by Matthew Heironimus
  no additional hardware used

  for Arduino Pro Micro or Leonardo
*********************************************************/

// **** PPM ****
// PPM signal is idle high, low 0.5 ms (start), 0.400 to 1.600 milliseconds channel pulse, 0.5 ms channel separation
// PPM pulse train separation is 10.5 ms.
// Max time for an 8 channel PPM train where all pulses are 1.6mS is 27.8mS

// PPM input port:
// ports 0,1,2,3 and 7 are usable for interrupts in the Leonardo or Pro Micro
// if you use ports 0 or 1 do not initialize the Serial port
static const unsigned int PPM_in= 2; // D1
static const int maxChannels= 8; // number of PPM channels in pulse train
static const unsigned long minSep= 7500;  // min pulse separation
static const unsigned long maxSep= 15000; // max pulse separation
static const unsigned long minPulse= 900;   // minimum valid servo pulse
static const unsigned long maxPulse= 2100;  // max valid servo pulse
static volatile int pTrain;  // pulse train pointer
static volatile unsigned long myMicros;
static volatile unsigned long startTiming;
static volatile unsigned long channel[maxChannels+1];
static volatile unsigned long lastReported[maxChannels+1];
static unsigned int i;

#include <Joystick.h>

Joystick_ Joystick(
  JOYSTICK_DEFAULT_REPORT_ID,
  JOYSTICK_TYPE_JOYSTICK,  // do not use JOYSTICK_TYPE_MULTI_AXIS because it is not recognized by Win10
  5,  // button count 5
  0,  // hat switch count
  true, // X axis Aileron
  true, // Y axis Elevator
  true, // Z axis throttle
  true,    // x rotation CH6
  false,   // y rotation
  false,   // z rotation
  true,    // rudder
  false,   // throttle
  false, false, false);  // no accelerator, no brake, no steering

void pulsePPM () {
  myMicros= micros()-startTiming;
  if ((myMicros >= minPulse) && (myMicros <= maxPulse) && (pTrain > 0)) {
    channel[pTrain]= myMicros;
    if (++pTrain > maxChannels) pTrain= 0;
  }
  else if ((myMicros >= minSep) && (myMicros <= maxSep)) { // train separation pulse
    pTrain= 1;
    channel[0]= myMicros;  // save pulse separation
  }  
  else pTrain= -1; // invalid pulse
  startTiming+= myMicros; // prepare to measure next pulse (makes starTiming= micros() above)
}

void setup() {
  pinMode(PPM_in, INPUT);
  Joystick.setXAxisRange(900, 2100);    // Aileron
  Joystick.setYAxisRange(900, 2100);    // Elevator
  Joystick.setZAxisRange(900, 2100);
  Joystick.setRxAxisRange(900, 2100);   // Channel 6
//  Joystick.setRyAxisRange(900, 2100);
  Joystick.setRudderRange(900, 2100);
//  Joystick.setThrottleRange(900, 2100);
  for (i= 1; i <= maxChannels; i++) lastReported[i]= 0;
  Joystick.begin();
  pTrain= -1;
  startTiming= micros();
  attachInterrupt(digitalPinToInterrupt(PPM_in), pulsePPM, FALLING);
}

void loop() {
  for (i= 1; i <= maxChannels; i++) if (lastReported[i] != channel[i]) {
    switch (i) {
      case 1: // Aileron
        Joystick.setXAxis(channel[i]);
        break;
      case 2: // Elevator
        Joystick.setYAxis(channel[i]);
        break;
      case 3: // throttle
        Joystick.setZAxis(channel[i]);
        break;
      case 4: // Rudder
        Joystick.setRudder(channel[i]);
        break;
      case 5:
        if (channel[i] <= 1500)
          Joystick.releaseButton(0);
        else
          Joystick.pressButton(0);
        break;
      case 6:
        Joystick.setRxAxis(channel[i]);
        break;
      case 7:
        if (channel[i] <= 1500)
          Joystick.releaseButton(1);
        else
          Joystick.pressButton(1);
        break;
      case 8:
        if (channel[i] <= 1200) {
          Joystick.releaseButton(4);
          Joystick.pressButton(3);
        }
        else if (channel[i] > 1800) {
          Joystick.releaseButton(3);
          Joystick.pressButton(4);
        }
        else {
          Joystick.releaseButton(3);
          Joystick.releaseButton(4);
        }
        break;
    }
    lastReported[i]= channel[i];
  }
}


Well, this completes everything you (never) wanted to know about SBUS, PPM and Arduino interrupts.

Any missing constants try 42 (and don't panic)...