TeensyReceiver.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;
00031 volatile uint8_t RX_signalReceived = 0;
00032 
00033 volatile int oks=0;
00034 
00035 bool failsafeEnabled = false;
00036 
00037 void readPWM(uint8_t channel) {
00038     uint32_t now = PIT_CVAL0; // Current counter value
00039     uint32_t delta = PWM_time[channel] - now; // Delta (calculated in reverse, because PIT is downcounting timer)
00040     
00041     // All of the number below are scaled to use with Teensy 3.0 running at 48Mhz
00042     if (delta < 120000 && delta > 43200) { // This is a valid pulse
00043         RX[channel] = delta / 48;
00044         
00045         // Bring failsafe status flag for current channel down every time we accept a valid signal
00046         RX_failsafeStatus &= ~(1 << channel);
00047     } else { // Beginning of the pulse
00048         PWM_time[channel] = now;
00049     }
00050 }
00051 
00052 // ISRs
00053 void PWM_ISR_0() {
00054     readPWM(0);
00055 }
00056 void PWM_ISR_1() {
00057     readPWM(1);
00058 }
00059 void PWM_ISR_2() {
00060     readPWM(2);
00061 }
00062 void PWM_ISR_3() {
00063     readPWM(3);
00064 }
00065 void PWM_ISR_4() {
00066     readPWM(4);
00067 }
00068 void PWM_ISR_5() {
00069     readPWM(5);
00070 }
00071 void PWM_ISR_6() {
00072     readPWM(6);
00073 }
00074 void PWM_ISR_7() {
00075     readPWM(7);
00076 }
00077 
00078 void (*PWM_Handlers [])(void) = {
00079     PWM_ISR_0, 
00080     PWM_ISR_1, 
00081     PWM_ISR_2, 
00082     PWM_ISR_3, 
00083     PWM_ISR_4, 
00084     PWM_ISR_5, 
00085     PWM_ISR_6, 
00086     PWM_ISR_7
00087 };
00088 
00089 void initializeReceiver() {
00090     // initialize PIT timer (teensy running at 48000000)
00091          SIM_SCGC6 |=  SIM_SCGC6_PIT;
00092     PIT_MCR = 0x00;          // Turn on PIT
00093     PIT_LDVAL0 = 0xFFFFFFFF; // Load initial value of 4294967295
00094     PIT_TCTRL0 = 0x01;       // Start the counter
00095     for (uint8_t i = 0; i < RX_CHANNELS; i++) {
00096         pinMode(PWM_PINS[i], INPUT);
00097         attachInterrupt(PWM_PINS[i], PWM_Handlers[i], CHANGE);
00098     }
00099 }
00100 
00101 void RX_failSafe() {
00102     if (RX_failsafeStatus > 0) {
00103         RX_signalReceived++; // if this flag reaches 10, an auto-descent routine will be triggered.
00104     } else {
00105         // Raise the FLAGS
00106         RX_failsafeStatus |= (1 << RX_CHANNELS) - 1;
00107         
00108         // Reset the counter
00109         RX_signalReceived = 0;
00110     }
00111     
00112     if (RX_signalReceived > 10) {
00113         RX_signalReceived = 10; // don't let the variable overflow
00114 
00115 failsafeEnabled = true; // this ensures that failsafe will operate in attitude mode
00116 oks=0;
00117         
00118      //TODO: FAILSAFE CODE
00119 
00120     } else {
00121         oks+=1;
00122         if (oks>=100) {
00123                 failsafeEnabled = false;
00124                 oks=100;
00125         }
00126     }
00127 }


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