├── CPPM.cpp ├── CPPM.h ├── LICENSE ├── README.md └── examples └── multicolor └── multicolor.ino /CPPM.cpp: -------------------------------------------------------------------------------- 1 | #include 2 | #include 3 | #include "CPPM.h" 4 | 5 | 6 | /** 7 | * Enable the input capture interrupt. 8 | */ 9 | void CPPMReceiver::begin(uint8_t numChannels) 10 | { 11 | _numChannels = numChannels; 12 | 13 | // Configure the input capture pin 14 | pinMode(ICP1, INPUT); 15 | 16 | // Configure timer1: disable PWM, set prescale = 8x (0.5 usec ticks) 17 | TCCR1A = 0; 18 | TCCR1B = _BV(CS11); 19 | TCCR1C = 0; 20 | 21 | // Enable the interrupt and clear the mask 22 | bitSet(TIFR1, ICF1); 23 | bitSet(TIMSK1, ICIE1); 24 | } 25 | 26 | /** 27 | * Disable the input capture interrupt. 28 | */ 29 | void CPPMReceiver::end() 30 | { 31 | bitClear(TIMSK1, ICIE1); 32 | } 33 | 34 | /** 35 | * Return true if a sane CPPM signal has recently been detected on the input pin. 36 | */ 37 | bool CPPMReceiver::ok(void) 38 | { 39 | // Need to devise a watchdog; this is never cleared when signal is lost 40 | return CPPM._synced; 41 | } 42 | 43 | /** 44 | * Atomically read the current CPPM channel values into the array pointed to by `channels`. 45 | * 46 | * Each channel value is mapped from a raw pulse width to an int16_t value (nominally 0-255). 47 | */ 48 | void CPPMReceiver::read(int16_t *channels) 49 | { 50 | noInterrupts(); 51 | for (int i = 0; i < _numChannels; ++i) 52 | { 53 | channels[i] = map(_channels[i], 54 | CPPM_CHAN_PULSE_WIDTH_MIN, 55 | CPPM_CHAN_PULSE_WIDTH_MAX, 56 | 0, 255); 57 | } 58 | interrupts(); 59 | } 60 | 61 | /** 62 | * TIMER1_CAPT_vect is invoked by the AVR timer hardware when a pulse appears on the input pin. 63 | * 64 | * On entry, the width of the pulse (as measured by timer1) will have been moved into ICR1. 65 | * 66 | * As usual, interrupts are disabled inside the handler. 67 | */ 68 | ISR(TIMER1_CAPT_vect) 69 | { 70 | static uint8_t channel; 71 | 72 | // Reset counter to measure next pulse 73 | TCNT1 = 0; 74 | 75 | // Read the captured pulse width 76 | uint16_t width = ICR1; 77 | 78 | switch (CPPM._state) 79 | { 80 | case CPPMReceiver::SYNC_PULSE: 81 | // If we've received a tolerable sync pulse, prepare 82 | // to read the channel pulses (starting with channel 0) 83 | if ((width >= CPPM_SYNC_PULSE_WIDTH_FLOOR) && (width <= CPPM_SYNC_PULSE_WIDTH_CEIL)) 84 | { 85 | CPPM._state = CPPMReceiver::CHAN_PULSE; 86 | channel = 0; 87 | } 88 | // If we've received an untolerable sync pulse, 89 | // we may have suffered a framing error 90 | else 91 | { 92 | CPPM._synced = false; 93 | } 94 | break; 95 | 96 | case CPPMReceiver::CHAN_PULSE: 97 | // If we've received a tolerable channel pulse, 98 | // record it and advance to the next channel 99 | if ((width >= CPPM_CHAN_PULSE_WIDTH_FLOOR) && (width <= CPPM_CHAN_PULSE_WIDTH_CEIL)) 100 | { 101 | CPPM._channels[channel] = width; 102 | channel++; 103 | 104 | // If the complete frame has been received, 105 | // prepare to read the sync pulse for the next frame 106 | if (channel == CPPM._numChannels) 107 | { 108 | CPPM._synced = true; 109 | CPPM._state = CPPMReceiver::SYNC_PULSE; 110 | } 111 | } 112 | // If we've received an untolerable channel pulse, 113 | // we may have suffered a framing error 114 | else 115 | { 116 | CPPM._synced = false; 117 | CPPM._state = CPPMReceiver::SYNC_PULSE; 118 | } 119 | break; 120 | } 121 | } 122 | 123 | // Preinstantiate object 124 | CPPMReceiver CPPM; 125 | -------------------------------------------------------------------------------- /CPPM.h: -------------------------------------------------------------------------------- 1 | #ifndef CPPM_H 2 | #define CPPM_H 3 | 4 | #include 5 | #include 6 | 7 | #define ICP1 8 // Input capture pin 1 8 | 9 | #define CPPM_MAX_CHANNELS 16 10 | #define CPPM_FRAME_SIZE_IN_MS 27 // FrSky D4R-II CPPM frame size 11 | 12 | #define CPPM_SYNC_PULSE_WIDTH_FLOOR 10000 // Minimum tolerable value 13 | #define CPPM_SYNC_PULSE_WIDTH_CEIL 50000 // Maximum tolerable value 14 | #define CPPM_CHAN_PULSE_WIDTH_MIN 2000 // Minimum expected value 15 | #define CPPM_CHAN_PULSE_WIDTH_MAX 4000 // Maximum expected value 16 | #define CPPM_CHAN_PULSE_WIDTH_FLOOR 1500 // Minimum tolerable value 17 | #define CPPM_CHAN_PULSE_WIDTH_CEIL 4500 // Maximum tolerable value 18 | 19 | ISR(TIMER1_CAPT_vect); 20 | 21 | class CPPMReceiver 22 | { 23 | private: 24 | enum PulseState { SYNC_PULSE, CHAN_PULSE }; 25 | 26 | uint8_t _numChannels; 27 | volatile bool _synced; 28 | volatile PulseState _state; 29 | volatile int16_t _channels[CPPM_MAX_CHANNELS]; 30 | 31 | public: 32 | CPPMReceiver() : _synced(false), _state(SYNC_PULSE) {}; 33 | void begin(uint8_t numChannels); 34 | void end(); 35 | bool ok(); 36 | void read(int16_t *channels); 37 | 38 | friend void TIMER1_CAPT_vect(); 39 | }; 40 | 41 | extern CPPMReceiver CPPM; 42 | 43 | #endif 44 | -------------------------------------------------------------------------------- /LICENSE: -------------------------------------------------------------------------------- 1 | The MIT License (MIT) 2 | 3 | Copyright (c) 2014 Clay McClure 4 | 5 | Permission is hereby granted, free of charge, to any person obtaining a copy 6 | of this software and associated documentation files (the "Software"), to deal 7 | in the Software without restriction, including without limitation the rights 8 | to use, copy, modify, merge, publish, distribute, sublicense, and/or sell 9 | copies of the Software, and to permit persons to whom the Software is 10 | furnished to do so, subject to the following conditions: 11 | 12 | The above copyright notice and this permission notice shall be included in 13 | all copies or substantial portions of the Software. 14 | 15 | THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR 16 | IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, 17 | FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE 18 | AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER 19 | LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, 20 | OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN 21 | THE SOFTWARE. 22 | -------------------------------------------------------------------------------- /README.md: -------------------------------------------------------------------------------- 1 | Combined PPM (CPPM) Receiver Library for Arduino 2 | ================================================ 3 | 4 | This library provides a simple interface for reading 5 | up to 16 channels of RC input from a single CPPM signal: 6 | 7 | void setup(void) 8 | { 9 | CPPM.begin(NUM_CHANNELS); 10 | } 11 | 12 | void loop(void) 13 | { 14 | int16_t channels[NUM_CHANNELS]; 15 | 16 | if (CPPM.ok()) 17 | { 18 | CPPM.read(channels); 19 | 20 | // do something fun with the channel values, like fly a quadcopter... 21 | } 22 | } 23 | 24 | In its current form, it most likely only works on Arduino Uno. It requires 25 | exclusive access to timer1, preventing the use of PWM on digital output pins 26 | 9 & 10 (whose waveform generator also use timer1). 27 | -------------------------------------------------------------------------------- /examples/multicolor/multicolor.ino: -------------------------------------------------------------------------------- 1 | /** 2 | * Simple demonstration of the Combined PPM (CPPM) receiver library using a multi-color LED. 3 | * 4 | * Moving the sticks on the RC transmitter will change the LED's color and brightness. 5 | */ 6 | 7 | #include 8 | 9 | const uint8_t NUM_CHANNELS = 8; 10 | 11 | // CPPM channel assignments 12 | const uint8_t Y_CHAN = 2; // throttle = luminance (brightness) 13 | const uint8_t R_CHAN = 3; // rudder = red 14 | const uint8_t G_CHAN = 0; // aileron = green 15 | const uint8_t B_CHAN = 1; // elevator = blue 16 | 17 | // OUTPUT: Multi-color LED pins 18 | const uint8_t R_LED_PIN = 5; // uses timer0 19 | const uint8_t G_LED_PIN = 6; // uses timer0 20 | const uint8_t B_LED_PIN = 11; // uses timer2 21 | 22 | void setup(void) 23 | { 24 | CPPM.begin(NUM_CHANNELS); 25 | } 26 | 27 | void loop(void) 28 | { 29 | int16_t channels[NUM_CHANNELS]; 30 | 31 | if (CPPM.ok()) 32 | { 33 | CPPM.read(channels); 34 | 35 | double brightness = channels[Y_CHAN] / 255.0; 36 | 37 | analogWrite(R_LED_PIN, constrain(channels[R_CHAN] * brightness, 0, 255)); 38 | analogWrite(G_LED_PIN, constrain(channels[G_CHAN] * brightness, 0, 255)); 39 | analogWrite(B_LED_PIN, constrain(channels[B_CHAN] * brightness, 0, 255)); 40 | } 41 | else 42 | { 43 | analogWrite(R_LED_PIN, 0); 44 | analogWrite(G_LED_PIN, 0); 45 | analogWrite(B_LED_PIN, 0); 46 | } 47 | 48 | delay(50); 49 | } 50 | --------------------------------------------------------------------------------