TeensyReceiver_yam.h
Go to the documentation of this file.
00001 /*  PWM (Pulse Width Modulation) sampling done in hardware via pin interrupts and PIT timer.
00002     
00003     I am using one, out of 4 PIT timers build into the Teensy 3.0.
00004     
00005     Pins used for PWM signal capture are fully definable by the user.
00006     However, i do recommend avoiding FLEX timer enabled pins, (Teensy 3.0 pin numbering) 5, 6, 9, 10, 20, 21, 22, 23,
00007     as those are used for PWM signal generation (for Electronic Speed Controllers).
00008     
00009     Using the hardware timer for timing / counting the pulses gives us superior accuracy of ~21 nano seconds.
00010     
00011     This receiver code also utilizes a more advanced failsafe sequence.
00012     In case of receiver malfunction / signal cable damage, RX Failasefe will kicks in
00013     which will start auto-descent sequence.
00014     
00015 */
00016 /*
00017 #define RX_CHANNELS 8
00018 uint8_t PWM_PINS[RX_CHANNELS] = {2, 3, 4, 5, 6, 7, 8, 9};
00019 
00020 volatile uint16_t RX[RX_CHANNELS] = {1000, 1000, 1000, 1000, 1000, 1000, 1000, 1000};
00021 volatile uint32_t PWM_time[RX_CHANNELS] = {0, 0, 0, 0, 0, 0, 0, 0};
00022 */
00023 #define RX_CHANNELS 6
00024 uint8_t PWM_PINS[RX_CHANNELS] = {2,3,4,5,6,7};
00025 
00026 volatile uint16_t RX[RX_CHANNELS] = {1500,1500,1500,1500,1500,1500};
00027 volatile uint32_t PWM_time[RX_CHANNELS] = {0,0,0,0,0,0};
00028 
00029 
00030 volatile uint16_t RX_failsafeStatus=0;
00031 volatile int16_t RX_signalReceived = 10;
00032 
00033 bool failsafeEnabled = true;
00034 
00035 void readPWM(uint8_t channel) {
00036     uint32_t now = PIT_CVAL0; // Current counter value
00037     uint32_t delta = PWM_time[channel] - now; // Delta (calculated in reverse, because PIT is downcounting timer)
00038     
00039     // All of the number below are scaled to use with Teensy 3.0 running at 48Mhz
00040     if (delta < 100800 && delta > 43200) { // This is a valid pulse //(delta < 120000 && delta > 43200)
00041         RX[channel] = delta / 48;
00042         
00043         // Bring failsafe status flag for current channel down every time we accept a valid signal
00044         //RX_failsafeStatus &= ~(1 << channel);
00045      // if (( RX_signalReceived>0) && (RX[0]<2100)&&(RX[0]>900)&&(RX[1]<2100)&&(RX[1]>900)&&(RX[2]<2100)&&(RX[2]>900)&&(RX[3]<2100)&&(RX[3]>900)&&(RX[4]<2100)&&(RX[4]>900)&&(RX[5]<2100)&&(RX[5]>900)) { 
00046  if ( RX_signalReceived>0) {
00047 RX_signalReceived-=1;
00048 
00049 if (failsafeEnabled) {
00050 Serial.print(channel+1);
00051 Serial.print("   ");
00052 Serial.print(delta);
00053 Serial.print("   ");
00054 Serial.println(RX[channel]);
00055 }
00056 }
00057     } else { // Beginning of the pulse
00058         PWM_time[channel] = now;
00059     }
00060 }
00061 
00062 // ISRs
00063 void PWM_ISR_0() {
00064     readPWM(0);
00065 }
00066 void PWM_ISR_1() {
00067     readPWM(1);
00068 }
00069 void PWM_ISR_2() {
00070     readPWM(2);
00071 }
00072 void PWM_ISR_3() {
00073     readPWM(3);
00074 }
00075 void PWM_ISR_4() {
00076     readPWM(4);
00077 }
00078 void PWM_ISR_5() {
00079     readPWM(5);
00080 }
00081 void PWM_ISR_6() {
00082     readPWM(6);
00083 }
00084 void PWM_ISR_7() {
00085     readPWM(7);
00086 }
00087 
00088 void (*PWM_Handlers [])(void) = {
00089     PWM_ISR_0, 
00090     PWM_ISR_1, 
00091     PWM_ISR_2, 
00092     PWM_ISR_3, 
00093     PWM_ISR_4, 
00094     PWM_ISR_5, 
00095     PWM_ISR_6, 
00096     PWM_ISR_7
00097 };
00098 
00099 void initializeReceiver() {
00100     // initialize PIT timer (teensy running at 48000000)
00101          SIM_SCGC6 |=  SIM_SCGC6_PIT;
00102     PIT_MCR = 0x00;          // Turn on PIT
00103     PIT_LDVAL0 = 0xFFFFFFFF; // Load initial value of 4294967295
00104     PIT_TCTRL0 = 0x01;       // Start the counter
00105     for (uint8_t i = 0; i < RX_CHANNELS; i++) {
00106         pinMode(PWM_PINS[i], INPUT);
00107         attachInterrupt(PWM_PINS[i], PWM_Handlers[i], CHANGE);
00108     }
00109 }
00110 
00111 void RX_failSafe() {
00112 RX_signalReceived+=2;
00113 if (RX_signalReceived>500) RX_signalReceived=500;
00114 if (RX_signalReceived>=50) {
00115 //((RX[0]<900)||(RX[0]>2100)||(RX[1]<900)||(RX[1]>2100)||(RX[2]<900)||(RX[2]>2100)||(RX[3]<900)||(RX[3]>2100)||(RX[4]<900)||(RX[4]>2100)||(RX[5]<900)||(RX[5]>2100)) {
00116 
00117         failsafeEnabled = true;
00118 }
00119 else 
00120 {
00121         failsafeEnabled = false;
00122 }
00123 /*
00124     if (RX_failsafeStatus > 0) {
00125         RX_signalReceived++; // if this flag reaches 10, an auto-descent routine will be triggered.
00126     } else {
00127 
00128         // Raise the FLAGS
00129         RX_failsafeStatus |= (1 << RX_CHANNELS) - 1;
00130         
00131         // Reset the counter
00132         RX_signalReceived = 0;
00133     }
00134     
00135     if (RX_signalReceived > 10) {
00136 
00137         RX_signalReceived = 10; // don't let the variable overflow
00138         failsafeEnabled = true; // this ensures that failsafe will operate in attitude mode
00139         
00140      //TODO: FAILSAFE CODE
00141 
00142     } else {
00143         failsafeEnabled = false;
00144     }
00145 */
00146 }


ric_mc
Author(s): RoboTiCan
autogenerated on Thu Aug 27 2015 14:39:50