Go to the documentation of this file.00001
00002
00003
00004
00005
00006
00007
00008
00009
00010
00011
00012
00013
00014
00015
00016
00017
00018
00019
00020
00021
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;
00037 uint32_t delta = PWM_time[channel] - now;
00038
00039
00040 if (delta < 100800 && delta > 43200) {
00041 RX[channel] = delta / 48;
00042
00043
00044
00045
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 {
00058 PWM_time[channel] = now;
00059 }
00060 }
00061
00062
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
00101 SIM_SCGC6 |= SIM_SCGC6_PIT;
00102 PIT_MCR = 0x00;
00103 PIT_LDVAL0 = 0xFFFFFFFF;
00104 PIT_TCTRL0 = 0x01;
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
00116
00117 failsafeEnabled = true;
00118 }
00119 else
00120 {
00121 failsafeEnabled = false;
00122 }
00123
00124
00125
00126
00127
00128
00129
00130
00131
00132
00133
00134
00135
00136
00137
00138
00139
00140
00141
00142
00143
00144
00145
00146 }