Skip to content
Open
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
2 changes: 2 additions & 0 deletions README.md
Original file line number Diff line number Diff line change
Expand Up @@ -52,6 +52,8 @@ PPMReader ppm(interruptPin, channelAmount);

void setup() {
Serial.begin(115200);
// Add the following line if you are using an ESP32 board :
// ppm.begin();
}

void loop() {
Expand Down
Original file line number Diff line number Diff line change
@@ -1,4 +1,6 @@
/*
This example is compatible with AVR boards.

This example outputs values from all PPM channels to Serial
in a format compatible with Arduino IDE Serial Plotter
*/
Expand Down
29 changes: 29 additions & 0 deletions examples/PlotChannelsESP32/PlotChannelsESP32.ino
Original file line number Diff line number Diff line change
@@ -0,0 +1,29 @@
/*
This example is compatible with ESP32 Boards.

This example outputs values from all PPM channels to Serial
in a format compatible with Arduino IDE Serial Plotter
*/

#include <PPMReader.h>

// Initialize a PPMReader on digital pin 3 with 6 expected channels.
byte interruptPin = 3;
byte channelAmount = 6;
PPMReader ppm(interruptPin, channelAmount);

void setup() {
Serial.begin(115200);
ppm.begin();
}

void loop() {
// Print latest valid values from all channels
for (byte channel = 1; channel <= channelAmount; ++channel) {
unsigned value = ppm.latestValidChannelValue(channel, 0);
Serial.print(value);
if(channel < channelAmount) Serial.print('\t');
}
Serial.println();
delay(20);
}
48 changes: 47 additions & 1 deletion src/PPMReader.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -20,6 +20,7 @@ along with PPM Reader. If not, see <http://www.gnu.org/licenses/>.

#include "PPMReader.h"

#define ABS(X) (X < 0? -X : X)
PPMReader *PPMReader::ppm;

void PPMReader::PPM_ISR(void) {
Expand All @@ -36,10 +37,12 @@ PPMReader::PPMReader(byte interruptPin, byte channelAmount):
}
// Attach an interrupt to the pin
pinMode(interruptPin, INPUT);
#if !defined(ESP32)
if(ppm == NULL) {
ppm = this;
attachInterrupt(digitalPinToInterrupt(interruptPin), PPM_ISR, RISING);
}
#endif
}

PPMReader::~PPMReader(void) {
Expand All @@ -48,11 +51,21 @@ PPMReader::~PPMReader(void) {
delete [] rawValues;
}

#if defined(ESP32)
void PPMReader::begin()
{
if(ppm == NULL) {
ppm = this;
attachInterrupt(digitalPinToInterrupt(interruptPin), PPM_ISR, RISING);
}
}
#endif

void PPMReader::handleInterrupt(void) {
// Remember the current micros() and calculate the time since the last pulseReceived()
unsigned long previousMicros = microsAtLastPulse;
microsAtLastPulse = micros();
unsigned long time = microsAtLastPulse - previousMicros;
unsigned long time = ABS((unsigned)microsAtLastPulse - (unsigned)previousMicros);

if (time > blankTime) {
// Blank detected: restart from channel 1
Expand All @@ -78,6 +91,39 @@ unsigned PPMReader::rawChannelValue(byte channel) {
return value;
}

unsigned PPMReader::percentageChannelValue(byte channel){
unsigned raw = rawChannelValue(channel);

if(raw >= minChannelValue && raw <= maxChannelValue)
{
return map(raw, minChannelValue, maxChannelValue, 0, 100);
}
else if (raw < minChannelValue)
{
return 0;
} else
{
return 100;
}
}

unsigned PPMReader::latestValidPercentage(byte channel, unsigned defaultValue){
unsigned raw = latestValidPercentage(channel, defaultValue);

if(raw >= minChannelValue && raw <= maxChannelValue)
{
return map(raw, minChannelValue, maxChannelValue, 0, 100);
}
else if (raw < minChannelValue)
{
return 0;
} else
{
return 100;
}
}


unsigned PPMReader::latestValidChannelValue(byte channel, unsigned defaultValue) {
// Check for channel's validity and return the latest valid channel value or defaultValue.
unsigned value = defaultValue;
Expand Down
16 changes: 14 additions & 2 deletions src/PPMReader.h
Original file line number Diff line number Diff line change
Expand Up @@ -60,7 +60,6 @@ class PPMReader {
volatile unsigned long microsAtLastPulse = 0;

// Pointer to PPMReader object used by ISR. Replace by an array if multiple PPM reader instances are needed
static PPMReader *ppm;

public:

Expand All @@ -70,17 +69,30 @@ class PPMReader {
// Returns the latest raw (not necessarily valid) value for the channel (starting from 1)
unsigned rawChannelValue(byte channel);

unsigned percentageChannelValue(byte channel);
unsigned latestValidPercentage(byte channel, unsigned defaultValue);
// Returns the latest received value that was considered valid for the channel (starting from 1)
// Returns defaultValue if the channel hasn't received any valid values yet, or the PPM signal was absent for more than failsafeTimeout
unsigned latestValidChannelValue(byte channel, unsigned defaultValue);



#if defined(ESP32)
public:
static PPMReader *ppm;
static void PPM_ISR(void);
void begin();
#else
private:
static PPMReader *ppm;
static void PPM_ISR(void);
#endif
private:

// An interrupt service routine for handling the interrupts activated by PPM pulses
void handleInterrupt(void);

// Interrupt service routine function compatible with attachInterrupt. Add more funcitons if multiple PPM reader instances are needed
static void PPM_ISR(void);

};

Expand Down