Introduction: SBUS to PPM and PWM Decoder Using Arduino Timer Interrupts. PART 3: Porting to ESP01 and STM32F103

About: Hardware and firmware freelance developer proficient in Arduino C++ and PIC assembler. Experienced in microprocessed devices, IOT and PC peripherals. Bilingual (Spanish/English). Available for hire.

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 2 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 3:

Porting the code to other MCUs, namely ESP8266 and STM32F103C8T6


Supplies

  • ESP01 (1Mb version will do)
  • Voltage Regulator: AMS1117-3.3V (you may adapt any 3.3V voltage regulator of at least 500mA output)
  • Capacitors: 100uF (6V or 16V) electrolytic, 2x 100nF (100nF = 0,1uF) ceramic
  • Transistor: BC337 or BC547
  • Resistors: 470ohm, 1K, 2K2 and 4 x 10K
  • LED: 3mm red
  • Female "imperial" (2.54mm) 2 way PCB pin strip: a 4x2 pin piece to make a socket for the ESP01
  • Male Pin strip: 2 pins for the jumper (and 1 jumper)
  • Receiver plug: male connector (from a Futaba extension cable) or equivalent Dupont connector
  • Plug: 3.5mm (mono or stereo depending on the target dongle)
  • A piece of 3 way cable for the 3.5mm plug (a piece from the Futaba extension or the Dupont cables will do)
  • A piece of perforated prototyping PCB (see photo)
  • A piece of exposed wire or Wire Wrapping wire

If you build the STM32 version (see step 2 below) you will only need the inverter from PART 1 of this instructable and a Dupont to mini plug adapter cable (which you have to make)

Step 1: SBUS to PPM Converter for the ESP8266 (ESP01)

The ESP01 is nicely suited for this task because it’s cheap and we only need a serial port for the SBUS stream and a digital port for the output. Be warned that the digital output ports in the ESP01 will spit some data at strange serial speeds during the first 100mS of initialization immediately after power up. The USB R/C dongle I used for testing is not affected by the bogus initial data. If your dongle does not work or stops responding during startup try turning your radio off and then on (which will output a LOW PPM reset signal). Use another MCU if that doesn’t fix the problem.

As you know, we have to be creative to take advantage of all ESP01 ports, since pulling down on GP0 or GP2 will prevent the MCU from booting from flash. As you can see, the LED (D1) which has the cathode connected to a resistor coming from 3.3V is actually pulling up on the port (the LED is active LOW). Also, the PPM_OUT pin, even being an output, must have an external pull up resistor (R4). That’s because GP2 is an input until the program starts, and obviously the program cannot execute the pinMode(2, OUTPUT) instruction until after is has started. As an additional precaution, R6 is there just in case the ESP8266 tries to output something during boot, before turning into an INPUT. As a matter of fact, when we initialize the UART and before repurposing the port for the configuration jumper, TX is an output.

The component mounting photo is a bottom view while the PCB is a top view. The unpopulated resistor pad is there in case we needed a 4K7/10K voltage divider for the 5V signal from the receiver, which it seems, is not necessary.

All resistors and capacitors are SMD 0805. You can use this template to build the device in a perforated board (see prototype photos). The ESP01 used is a 1Mb version (nothing is saved to the filesystem, so, the infamous PUYA chip will be no problem). You don't need more flash (like the ESP01S' 4Mb) for this project.

If you don't make the ESP01 PCB above, you will need to build the 3.3V inverter found in PART 1 of this instructable series.

The following sketch will work in ESP01, ESP12, nodeMCU, Wemos D1 mini, etc.

CODE:

// SBUS to PPM converter
// (c) 2023 Pablo Montoreano

/*********************************************************
  @file       SBUS2PPM8_ESP.ino
  @brief      SBUS to PPM protocol converter
  @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

  for ESP01, nodeMCU, Wemos D1 mini or any ESP8266 (no debugging possible)

  Select "nodeMcu 1.0" for 4Mb boards, "Generic ESP8266 Module" for 1Mb boards
  Set MMU to "32K cache + 32Kb IRAM" if using ESP8266 Boards Manager version 3.1.2
  Set flash size as you like, no data saved
*********************************************************/

// 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

#define SHOWSIGNAL  // if defined LED will light when there is no radio signal, else it will reflect the PPM resolution mode (1024 ON or 2048 OFF)
#define LEDOFF HIGH
#define LEDON LOW
static const unsigned int PPM_out= 2;  // PPM output port
static const unsigned int portCfg= 1;  // resolution configuration (Jumper= 10 bits) GPIOTX
static const unsigned int LED_noSignal= 0;  // LED (low speed or lost signal)
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= 52500; // 10500 uS * 5 MHz DIV16
static const unsigned int chanSep= 2500;   // 500 uS * 5 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 (volatile because it is modified by ISR)
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
// default MMU (32K cache + 32Kb IRAM) will work ok
void IRAM_ATTR timerRoutine() {
  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);
        timer1_write(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) timer1_write(ppm2[pTrain >> 1]);  // if ppm1 array is being written to use ppm2
        else timer1_write(ppm1[pTrain >> 1]);
      }
    }
    else if (pTrain > trainSepStart) {  // end of 10.5mS pulse train separation, start a channel sep pulse
      digitalWrite(PPM_out, LOW);
      pTrain= 1; // start new pulse train
      timer1_write(chanSep); // channel separation pulse= 0.5mS
    }
    else {  // ptrain == trainSepStart
      digitalWrite(PPM_out, HIGH);
      timer1_write(trainSep); // start pulse train separation
    }
  }
}

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() {
  while (Serial.available()) {
    sbusByte= Serial.read();
// 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;
    }
  }
  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  
  Serial.begin(SBUSbaudRate, SERIAL_8E2);
  delay(100);
// since we do not transmit anything, after the Serial port is initialized we can change TX pin to input and use it for a config jumper
  pinMode(portCfg, FUNCTION_3);  // convert TX to GPIO 1 (serial RX still works ok)
  pinMode(portCfg, INPUT_PULLUP);
  byteNmbr= 255; // invalidate SBUS byte number
  lastReception= 0;
  newFrame= false;
  pTrain= 0;  // idle
  lock1= true;
  timer1_isr_init();
  timer1_attachInterrupt(timerRoutine);
  timer1_enable(TIM_DIV16, TIM_EDGE, TIM_SINGLE);
}

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++) {
      // TIM_DIV16 at 80MHz gives 0.2 uS per tick, so we have 5 ticks per uS
      // 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) * 5; simplified with a single float operation
      // as an alternative we can use ppmx[i]= map(channel[i],0,2047,2000,8000);
      // or map(channel[i] >> 1,0,1023,2000,8000); for half resolution
      if (resol1024) {
        if (lock1) ppm1[i]= 2000 + (int) ((channel[i] >> 1) * 5.862237);  // low (1024) resolution
        else ppm2[i]= 2000 + (int) ((channel[i] >> 1) * 5.862237);
      }
      else {
        if (lock1) ppm1[i]= 2000 + (int) (channel[i] * 2.93112);  // full 2048 resolution
        else ppm2[i]= 2000 + (int) (channel[i] * 2.93112);
      }
    }
    lock1= !lock1;  // new stream is now valid, switch it. Timer interrupt will output next channel from new reading
    if ((channel[3] < signalLost) || (channel[0] & 8)) { // if signal lost disable PPM out
      pTrain= 0;
      timer1_disable();
      digitalWrite(PPM_out, LOW);
#ifdef SHOWSIGNAL
      digitalWrite(LED_noSignal, LEDON);
#endif
    }
    else if (pTrain == 0) { // if we got signal and PPM is idle
      pTrain= trainSepStart; // start new channel separation (PPM output was LOW)
      digitalWrite(PPM_out, HIGH); // start pulse for channel sep
      timer1_enable(TIM_DIV16, TIM_EDGE, TIM_SINGLE);
      timer1_write(trainSep);
#ifdef SHOWSIGNAL
      digitalWrite(LED_noSignal, LEDOFF);
#endif
    }
  }
  if ((millis() - lastReception) > timeOutMs) lastReception= 0;
  if (lastReception == 0) {
    pTrain= 0;
    timer1_disable();
    digitalWrite(PPM_out, LOW);
#ifdef SHOWSIGNAL
    digitalWrite(LED_noSignal, LEDON);
#endif
  }
}

Step 2: SBUS to PPM Converter for the STM32F103C8T6 (bluepill)

Fortunately, the STM32F1's Arduino Board Manager has native support for interrupts; but guess what, it's incompatible with the other MCUs. So, here we go again...


CODE:

// SBUS to PPM converter
// (c) 2023 Pablo Montoreano

/*********************************************************
  @file       SBUS2PPM8_STM.ino
  @brief      SBUS to PPM protocol converter
  @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

  for STM32F103 (bluepill)
  compile selecting Generic STM32F1 board
*********************************************************/

// STM32F103: PPM output in pin B9 (next to 5V and GND). Connect inverted SBUS signal to RXD1 (A10)

// 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

#define SHOWSIGNAL  // if defined LED will light when there is no radio signal, else it will reflect the PPM resolution mode (1024 ON or 2048 OFF)
#define LEDOFF HIGH
#define LEDON LOW

#ifdef STM32F1
static const unsigned int PPM_out= PB9;  // PPM output port
static const unsigned int portCfg= PA0;  // resolution configuration (Jumper= 10 bits)
static const unsigned int LED_noSignal= PA1;     // low speed indicator LED
#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= 10500;  // 10500 uS
static const unsigned int chanSep= 500;     // 500 uS
// 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 (volatile because it is modified by ISR)
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;

HardwareTimer timer(TIM1);

// Timer1 interrupt
void timerRoutine() {
  timer.pause();
  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);
        timer.setOverflow(chanSep, MICROSEC_FORMAT);
      }
      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) timer.setOverflow(ppm2[pTrain >> 1], MICROSEC_FORMAT);  // if ppm1 array is being written to use ppm2
        else timer.setOverflow(ppm1[pTrain >> 1], MICROSEC_FORMAT);
      }
    }
    else if (pTrain > trainSepStart) {  // end of 10.5mS pulse train separation, start a channel sep pulse
      digitalWrite(PPM_out, LOW);
      pTrain= 1; // start new pulse train
      timer.setOverflow(chanSep, MICROSEC_FORMAT); // channel separation pulse= 0.5mS
    }
    else {  // ptrain == trainSepStart
      digitalWrite(PPM_out, HIGH);
      timer.setOverflow(trainSep, MICROSEC_FORMAT); // start pulse train separation
    }
    timer.refresh();
    timer.setCount(0);
    timer.resume();
  }
}

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() {
  while (Serial1.available()) {
    sbusByte= Serial1.read();
// 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;
    }
  }
  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  
  Serial1.begin(SBUSbaudRate, SERIAL_8E2);
  delay(100);
// since we do not transmit anything, after the Serial port is initialized we can change TX pin to input and use it for a config jumper
  pinMode(portCfg, INPUT_PULLUP);
  byteNmbr= 255; // invalidate SBUS byte number
  lastReception= 0;
  newFrame= false;
  pTrain= 0;  // idle
  lock1= true;
  timer.pause();
  timer.setCount(0);
  timer.attachInterrupt(timerRoutine);
}

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++) {
      // TIM_DIV16 at 80MHz gives 0.2 uS per tick, so we have 5 ticks per uS
      // 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); simplified with a single float operation
      // as an alternative we can use ppmx[i]= map(channel[i],0,2047,400,1600);
      // or map(channel[i] >> 1,0,1023,400,1600); for half resolution
      if (resol1024) {
        if (lock1) ppm1[i]= map(channel[i] >> 1,0,1023,400,1600);
        else ppm2[i]=  map(channel[i] >> 1,0,1023,400,1600);
      }
      else {
        if (lock1) ppm1[i]=  map(channel[i],0,2047,400,1600); // full 2048 resolution
        else ppm2[i]=  map(channel[i],0,2047,400,1600);;
      }
    }
    lock1= !lock1;  // new stream is now valid, switch it. Timer interrupt will output next channel from new reading
    if ((channel[3] < signalLost) || (channel[0] & 8)) { // if signal lost disable PPM out
      pTrain= 0;
      timer.pause();
      digitalWrite(PPM_out, LOW);
#ifdef SHOWSIGNAL
      digitalWrite(LED_noSignal, LEDON);
#endif
    }
    else if (pTrain == 0) { // if we got signal and PPM is idle
      pTrain= trainSepStart; // start new channel separation (PPM output was LOW)
      digitalWrite(PPM_out, HIGH); // start pulse for channel sep
      timer.setOverflow(trainSep, MICROSEC_FORMAT);
      timer.setCount(0);
      timer.refresh();
      timer.resume();
#ifdef SHOWSIGNAL
      digitalWrite(LED_noSignal, LEDOFF);
#endif
    }
  }
  if ((millis() - lastReception) > timeOutMs) lastReception= 0;
  if (lastReception == 0) {
    pTrain= 0;
    timer.pause();
    digitalWrite(PPM_out, LOW);
#ifdef SHOWSIGNAL
    digitalWrite(LED_noSignal, LEDON);
#endif
  }
}


In PART 4 of this instructable we will add support for servo outputs without losing PPM.

Click here to go to PART 4 of this instructable