// Tested with Flysky radio+arduino nano+raspberry pi+navio board (and PPM Example program set to 4/6 channels). // Accuracy seems to be in the 10's of microseconds (I found with the arduino quadcopter that a complementary average over say 10 frames // gives better results with a slower response time. // acuracy will be a little low, 16 millionths of a second for the micros() function and digitalRead/Write's are slower than direct // looking at the tests, a variation of around +-50 without the complementary average, closer to 30 with it enabled // and +- 25 if you average the ppm side (on the other device, not the arduino) // but easier to allow pin adjustments.const int numberofchannels = 6; // feel free to swipe/modify the code, no licence on this one. but no promises either ;) So be careful. (a lot depends on the "other" side of the transmission) #define ComplementaryAverage // comment out for raw PWM transfer const int numberofchannels = 6; const int channel1pin = 2; const int channel2pin = 3; const int channel3pin = 4; const int channel4pin = 5; const int channel5pin = 6; const int channel6pin = 7; const int channel7pin = 8; const int channel8pin = 9; const int outputpin = 10; const int ppmfrequency = 50; // hz, you can change this but the lower frequency the better the accuracy const int ppmchannelinterval = 64;// millionths of a second, probably doesnt need to be altered const int ppmpulseinterval = 5000;// minimum should be 4000 this is the sync period (it will go high for this period of time) const float pwmbase = 0.05f; // minimum pwm pulse time (pwm on radio's normally have a 1-2ms pulse, with a ~1ms pulse high initally followed by the actual timing // 1ms is represented on a 50hz radio as 0.05*the full cycle. you can 0 this if you want ppm to replicate the way pwm works const float pwmscale = 20.0f; // 20*0.05=1 so use the whole ppm bandwidth for this channel (the rest of the 1-2ms pwm pulse 1-2=1, // if you zero the pwmbase this should be 10 as 2ms/20ms (complete pwm pulse)*10=1.0) const long radiolosstime = 50000; // time without a channel 1 high before radio loss is assumed. const float ppmtime = 1000000/ppmfrequency; const float channelscale = 1.0f/(float)numberofchannels; const float ppmpulsespace = (ppmtime-ppmchannelinterval*(numberofchannels+1)-ppmpulseinterval);// constant that defines the "free" space available for all channels int pinstate1 = 0; int pinstate2 = 0; int pinstate3 = 0; int pinstate4 = 0; int pinstate5 = 0; int pinstate6 = 0; int pinstate7 = 0; int pinstate8 = 0; long pintimeup1 = 0; long pintimeup2 = 0; long pintimeup3 = 0; long pintimeup4 = 0; long pintimeup5 = 0; long pintimeup6 = 0; long pintimeup7 = 0; long pintimeup8 = 0; long pintimedown1 = 0; long pintimedown2 = 0; long pintimedown3 = 0; long pintimedown4 = 0; long pintimedown5 = 0; long pintimedown6 = 0; long pintimedown7 = 0; long pintimedown8 = 0; float pinpwm1 = 0.0f; float pinpwm2 = 0.0f; float pinpwm3 = 0.0f; float pinpwm4 = 0.0f; float pinpwm5 = 0.0f; float pinpwm6 = 0.0f; float pinpwm7 = 0.0f; float pinpwm8 = 0.0f; float pinpwmppm1 = 0.0f; float pinpwmppm2 = 0.0f; float pinpwmppm3 = 0.0f; float pinpwmppm4 = 0.0f; float pinpwmppm5 = 0.0f; float pinpwmppm6 = 0.0f; float pinpwmppm7 = 0.0f; float pinpwmppm8 = 0.0f; long pinppmdowntime = 0; long pinppmtime = 0; int ppmstate = 0; // convert to us long ppmlastchange = 0; void setup() { pinMode(channel1pin, INPUT); pinMode(channel2pin, INPUT); pinMode(channel3pin, INPUT); pinMode(channel4pin, INPUT); pinMode(channel5pin, INPUT); pinMode(channel6pin, INPUT); pinMode(channel7pin, INPUT); pinMode(channel8pin, INPUT); pinMode(outputpin, OUTPUT); Serial.begin(115200); } int val = 0; void loop() { // loop is improve accuracy while still freeing up at the end so OS stuff can run for (int r=0;r<1000;r++) { long currenttime = micros(); // only accurate to 16us // pin1 val = digitalRead(channel1pin); if ((val==HIGH) && (pinstate1==0)) {// start of high so record the time and move to next state if ((pintimedown1>0) && (pintimeup1>0)) { // we have both values, pwm is pintimeup1/(pintimeup1+pintimedown1) pinpwm1 = pintimeup1-pintimedown1; float t = (pintimeup1-pintimedown1)+(currenttime-pintimedown1); pinpwm1 = pinpwm1/t; } pintimedown1 = currenttime; pinstate1 = 1; } else if ((val==LOW) && (pinstate1==1)) { pintimeup1 = currenttime; pinstate1 = 0; } val = digitalRead(channel2pin); if ((val==HIGH) && (pinstate2==0)) {// start of high so record the time and move to next state if ((pintimedown2>0) && (pintimeup2>0)) { pinpwm2 = pintimeup2-pintimedown2; float t = (pintimeup2-pintimedown2)+(currenttime-pintimedown2); pinpwm2 = pinpwm2/t; } pintimedown2 = currenttime; pinstate2 = 1; } else if ((val==LOW) && (pinstate2==1)) { pintimeup2 = currenttime; pinstate2 = 0; } val = digitalRead(channel3pin); if ((val==HIGH) && (pinstate3==0)) {// start of high so record the time and move to next state if ((pintimedown3>0) && (pintimeup3>0)) { // we have both values, pwm is pintimeup1/(pintimeup1+pintimedown1) pinpwm3 = pintimeup3-pintimedown3; float t = (pintimeup3-pintimedown3)+(currenttime-pintimedown3); pinpwm3 = pinpwm3/t; } pintimedown3 = currenttime; pinstate3 = 1; } else if ((val==LOW) && (pinstate3==1)) { pintimeup3 = currenttime; pinstate3 = 0; } val = digitalRead(channel4pin); if ((val==HIGH) && (pinstate4==0)) {// start of high so record the time and move to next state if ((pintimedown4>0) && (pintimeup4>0)) { // we have both values, pwm is pintimeup1/(pintimeup1+pintimedown1) pinpwm4 = pintimeup4-pintimedown4; float t = (pintimeup4-pintimedown4)+(currenttime-pintimedown4); pinpwm4 = pinpwm4/t; } pintimedown4 = currenttime; pinstate4 = 1; } else if ((val==LOW) && (pinstate4==1)) { pintimeup4 = currenttime; pinstate4 = 0; } if (numberofchannels>4) { val = digitalRead(channel5pin); if ((val==HIGH) && (pinstate5==0)) {// start of high so record the time and move to next state if ((pintimedown5>0) && (pintimeup5>0)) { // we have both values, pwm is pintimeup1/(pintimeup1+pintimedown1) pinpwm5 = pintimeup5-pintimedown5; float t = (pintimeup5-pintimedown5)+(currenttime-pintimedown5); pinpwm5 = pinpwm5/t; } pintimedown5 = currenttime; pinstate5 = 1; } else if ((val==LOW) && (pinstate5==1)) { pintimeup5 = currenttime; pinstate5 = 0; } if (numberofchannels>5) {// read channel6 val = digitalRead(channel6pin); if ((val==HIGH) && (pinstate6==0)) {// start of high so record the time and move to next state if ((pintimedown6>0) && (pintimeup6>0)) { // we have both values, pwm is pintimeup1/(pintimeup1+pintimedown1) pinpwm6 = pintimeup6-pintimedown6; float t = (pintimeup6-pintimedown6)+(currenttime-pintimedown6); pinpwm6 = pinpwm6/t; } pintimedown6 = currenttime; pinstate6 = 1; } else if ((val==LOW) && (pinstate6==1)) { pintimeup6 = currenttime; pinstate6 = 0; } if (numberofchannels>6) { val = digitalRead(channel7pin); if ((val==HIGH) && (pinstate7==0)) {// start of high so record the time and move to next state if ((pintimedown7>0) && (pintimeup7>0)) { // we have both values, pwm is pintimeup1/(pintimeup1+pintimedown1) pinpwm7 = pintimeup7-pintimedown7; float t = (pintimeup7-pintimedown7)+(currenttime-pintimedown7); pinpwm7 = pinpwm7/t; } pintimedown7 = currenttime; pinstate7 = 1; } else if ((val==LOW) && (pinstate7==1)) { pintimeup7 = currenttime; pinstate7 = 0; } if (numberofchannels>7) { val = digitalRead(channel8pin); if ((val==HIGH) && (pinstate8==0)) {// start of high so record the time and move to next state if ((pintimedown8>0) && (pintimeup8>0)) { // we have both values, pwm is pintimeup1/(pintimeup1+pintimedown1) pinpwm8 = pintimeup8-pintimedown8; float t = (pintimeup8-pintimedown8)+(currenttime-pintimedown8); pinpwm8 = pinpwm8/t; } pintimedown8 = currenttime; pinstate8 = 1; } else if ((val==LOW) && (pinstate8==1)) { pintimeup8 = currenttime; pinstate8 = 0; } }// end of numberofchannels>7 }// end of numberofchannels>6 }// end of numberofchannels>5 }// end of numberofchannels>4 if (ppmstate==0) { if ((currenttime-pintimeup1)>radiolosstime) {// loss of radio signal ppmstate = 100; } } if (ppmstate==100) { if ((currenttime-pintimeup1)<radiolosstime) {// radio back! ppmstate = 0; } } if (ppmstate==0) { #ifndef ComplementaryAverage pinpwmppm1 = (pinpwm1-pwmbase)*pwmscale; // these values will be between 0.05 and 0.1 for normal RC receivers hence the *10 pinpwmppm2 = (pinpwm2-pwmbase)*pwmscale; // been done this way so it also copes with other PWM sources/frequencies pinpwmppm3 = (pinpwm3-pwmbase)*pwmscale; pinpwmppm4 = (pinpwm4-pwmbase)*pwmscale; pinpwmppm5 = (pinpwm5-pwmbase)*pwmscale; pinpwmppm6 = (pinpwm6-pwmbase)*pwmscale; pinpwmppm7 = (pinpwm7-pwmbase)*pwmscale; pinpwmppm8 = (pinpwm8-pwmbase)*pwmscale; #else pinpwmppm1 = ((pinpwmppm1*9)+((pinpwm1-pwmbase)*pwmscale))/10; // these values will be between 0.05 and 0.1 for normal RC receivers hence the *10 pinpwmppm2 = ((pinpwmppm2*9)+((pinpwm2-pwmbase)*pwmscale))/10; // been done this way so it also copes with other PWM sources/frequencies pinpwmppm3 = ((pinpwmppm3*9)+((pinpwm3-pwmbase)*pwmscale))/10; pinpwmppm4 = ((pinpwmppm4*9)+((pinpwm4-pwmbase)*pwmscale))/10; pinpwmppm5 = ((pinpwmppm5*9)+((pinpwm5-pwmbase)*pwmscale))/10; pinpwmppm6 = ((pinpwmppm6*9)+((pinpwm6-pwmbase)*pwmscale))/10; pinpwmppm7 = ((pinpwmppm7*9)+((pinpwm7-pwmbase)*pwmscale))/10; pinpwmppm8 = ((pinpwmppm8*9)+((pinpwm8-pwmbase)*pwmscale))/10; #endif //Serial.print(pinpwmppm1);Serial.print(" ");Serial.print(pinpwmppm2);Serial.print(" ");Serial.print(pinpwmppm3);Serial.print(" ");Serial.print(pinpwmppm4);Serial.print(" ");Serial.print(pinpwmppm5);Serial.print(" ");Serial.print(pinpwmppm6);Serial.println(" "); // end of pin1 should be currenttime+(tmp-ppmchannelinterval*4-ppmpulseinterval)*pinpwmppm1 pinppmtime = (long)(currenttime+ppmpulsespace*pinpwmppm1*channelscale); pinppmdowntime = (long)(ppmpulsespace*(1.0f-pinpwmppm1)*channelscale); digitalWrite(outputpin,HIGH); ppmstate=1; } else if (ppmstate==1) { if (currenttime>pinppmtime) { digitalWrite(outputpin,LOW); ppmstate = 2; pinppmtime+=ppmchannelinterval; } } else if (ppmstate==2) { if (currenttime>pinppmtime) { pinppmtime = (long)(currenttime+ppmpulsespace*pinpwmppm2*channelscale); pinppmdowntime += (long)(ppmpulsespace*(1.0f-pinpwmppm2)*channelscale); digitalWrite(outputpin,HIGH); ppmstate=3; } } else if (ppmstate==3) { if (currenttime>pinppmtime) { digitalWrite(outputpin,LOW); ppmstate = 4; pinppmtime+=ppmchannelinterval; } } else if (ppmstate==4) { if (currenttime>pinppmtime) { pinppmtime = (long)(currenttime+ppmpulsespace*pinpwmppm3*channelscale); pinppmdowntime += (long)(ppmpulsespace*(1.0f-pinpwmppm3)*channelscale); digitalWrite(outputpin,HIGH); ppmstate=5; } } else if (ppmstate==5) { if (currenttime>pinppmtime) { digitalWrite(outputpin,LOW); ppmstate = 6; pinppmtime+=ppmchannelinterval; } } else if (ppmstate==6) { if (currenttime>pinppmtime) { pinppmtime = (long)(currenttime+ppmpulsespace*pinpwmppm4*channelscale); pinppmdowntime += (long)(ppmpulsespace*(1.0f-pinpwmppm4)*channelscale); digitalWrite(outputpin,HIGH); ppmstate=7; } } else if (ppmstate==7) { if (currenttime>pinppmtime) { digitalWrite(outputpin,LOW); pinppmtime+=ppmchannelinterval; if (numberofchannels>4) ppmstate = 8; else ppmstate = 16; } } else if (ppmstate==8) { if (currenttime>pinppmtime) { pinppmtime = (long)(currenttime+ppmpulsespace*pinpwmppm5*channelscale); pinppmdowntime += (long)(ppmpulsespace*(1.0f-pinpwmppm5)*channelscale); digitalWrite(outputpin,HIGH); ppmstate=9; } } else if (ppmstate==9) { if (currenttime>pinppmtime) { digitalWrite(outputpin,LOW); if (numberofchannels>5) ppmstate = 10; else ppmstate = 16; pinppmtime+=ppmchannelinterval; } } else if (ppmstate==10) { if (currenttime>pinppmtime) { pinppmtime = (long)(currenttime+ppmpulsespace*pinpwmppm6*channelscale); pinppmdowntime += (long)(ppmpulsespace*(1.0f-pinpwmppm6)*channelscale); digitalWrite(outputpin,HIGH); ppmstate=11; } } else if (ppmstate==11) { if (currenttime>pinppmtime) { digitalWrite(outputpin,LOW); if (numberofchannels>6) ppmstate = 12; else ppmstate = 16; pinppmtime+=ppmchannelinterval; } } else if (ppmstate==12) { if (currenttime>pinppmtime) { pinppmtime = (long)(currenttime+ppmpulsespace*pinpwmppm7*channelscale); pinppmdowntime += (long)(ppmpulsespace*(1.0f-pinpwmppm7)*channelscale); digitalWrite(outputpin,HIGH); ppmstate=13; } } else if (ppmstate==13) { if (currenttime>pinppmtime) { digitalWrite(outputpin,LOW); if (numberofchannels>7) ppmstate = 14; else ppmstate = 16; pinppmtime+=ppmchannelinterval; } } else if (ppmstate==14) { if (currenttime>pinppmtime) { pinppmtime = (long)(currenttime+ppmpulsespace*pinpwmppm8*channelscale); pinppmdowntime += (long)(ppmpulsespace*(1.0f-pinpwmppm8)*channelscale); digitalWrite(outputpin,HIGH); ppmstate=15; } } else if (ppmstate==15) { if (currenttime>pinppmtime) { digitalWrite(outputpin,LOW); ppmstate = 16; pinppmtime+=ppmchannelinterval; } } else if (ppmstate==16) { if (currenttime>pinppmtime) { // now for a long high so the other side can sync up (just change this to LOW if it uses a LOW sync) digitalWrite(outputpin,HIGH); ppmstate = 17; pinppmtime = currenttime+ppmpulseinterval+pinppmdowntime; //pinppmdowntime is to flesh out the buffer so it maintains the correct frequency updates } } if (ppmstate==17) { if (currenttime>pinppmtime) { digitalWrite(outputpin,LOW); ppmstate=18; // loop around pinppmtime = currenttime+ppmchannelinterval; } } if (ppmstate==18) { if (currenttime>pinppmtime) { ppmstate=0; // loop around } } } } </plaintext>