Browse Source

Bit more cleanup.

Read Error 10 years ago
parent
commit
1464f737da
1 changed files with 133 additions and 138 deletions
  1. 133
    138
      frsky_arduino_rx_complete.ino

+ 133
- 138
frsky_arduino_rx_complete.ino View File

23
 #define SPIBB
23
 #define SPIBB
24
 //#define SPIHW
24
 //#define SPIHW
25
 #if defined SPIHW
25
 #if defined SPIHW
26
-#include <SPI.h>
26
+    #include <SPI.h>
27
 #endif
27
 #endif
28
 
28
 
29
 #define chanel_number 8  //set the number of chanels
29
 #define chanel_number 8  //set the number of chanels
30
 #define SEEK_CHANSKIP   13
30
 #define SEEK_CHANSKIP   13
31
 #define MAX_MISSING_PKT 20
31
 #define MAX_MISSING_PKT 20
32
-//*****************************************
33
 #define PPM_FrLen 22500
32
 #define PPM_FrLen 22500
34
 #define PPM_PulseLen 300
33
 #define PPM_PulseLen 300
35
 #define default_servo_value 1500
34
 #define default_servo_value 1500
37
 #define sigPin 10
36
 #define sigPin 10
38
 
37
 
39
 #if defined(SPIBB)
38
 #if defined(SPIBB)
40
-#define MO_pin 5 //D5
41
-#define MI_pin 6//D6
42
-#define SCLK_pin 4 //D4
43
-#define CS 2 //D2
44
-#define GDO_pin 3//D3  GDO0 pin
45
-//
46
-#define  SCK_on PORTD |= 0x10//D4
47
-#define  SCK_off PORTD &= 0xEF//D4
48
-
49
-#define  MO_on PORTD |= 0x20  //D5 
50
-#define  MO_off PORTD &= 0xDF //D5
51
-//
52
-#define  MI_1 (PIND & 0x40) == 0x40 //D6 input
53
-#define  MI_0 (PIND & 0x40) == 0x00 //D6
54
-//
55
-#define  CS_on PORTD |= 0x04 //D2
56
-#define  CS_off PORTD &= 0xFB //D2 
57
-//
58
-#define GDO_1 (PIND & 0x08) == 0x08 //D3 input
59
-#define GDO_0 (PIND & 0x08) == 0x00 //D3  
60
-//
39
+    #define MO_pin 5                    //D5
40
+    #define MI_pin 6                    //D6
41
+    #define SCLK_pin 4                  //D4
42
+    #define CS 2                        //D2
43
+    #define GDO_pin 3                   //D3  GDO0 pin
44
+    #define SCK_on PORTD |= 0x10        //D4
45
+    #define SCK_off PORTD &= 0xEF       //D4
46
+    #define MO_on PORTD |= 0x20         //D5 
47
+    #define MO_off PORTD &= 0xDF        //D5
48
+    #define MI_1 (PIND & 0x40) == 0x40  //D6 input
49
+    #define MI_0 (PIND & 0x40) == 0x00  //D6
50
+    #define CS_on PORTD |= 0x04         //D2
51
+    #define CS_off PORTD &= 0xFB        //D2 
52
+    #define GDO_1 (PIND & 0x08) == 0x08 //D3 input
53
+    #define GDO_0 (PIND & 0x08) == 0x00 //D3  
61
 #endif
54
 #endif
62
 
55
 
63
-#define bind_pin A0//C0 bind plug also servo8
64
-//
65
-#define Servo1_OUT 7 //Servo1(D7)
66
-#define Servo2_OUT 8 //Servo2(B0)
67
-#define Servo3_OUT 9 //Servo3(B1)
68
-#define Servo4_OUT 10 //Servo4(B2)//PPM pin
69
-#define Servo5_OUT 11 //Servo5(B3)
70
-#define Servo6_OUT 12 //Servo6(B4)
71
-#define Servo7_OUT 13 //Servo7(B5)
72
-#define Servo8_OUT A0 //Servo8(C0)
73
-//
56
+#define bind_pin A0     //C0 bind plug also servo8
57
+
58
+#define Servo1_OUT 7    //Servo1(D7)
59
+#define Servo2_OUT 8    //Servo2(B0)
60
+#define Servo3_OUT 9    //Servo3(B1)
61
+#define Servo4_OUT 10   //Servo4(B2)//PPM pin
62
+#define Servo5_OUT 11   //Servo5(B3)
63
+#define Servo6_OUT 12   //Servo6(B4)
64
+#define Servo7_OUT 13   //Servo7(B5)
65
+#define Servo8_OUT A0   //Servo8(C0)
74
 
66
 
75
 #define Servo1_OUT_HIGH PORTD |= _BV(7) //Servo1(D7)
67
 #define Servo1_OUT_HIGH PORTD |= _BV(7) //Servo1(D7)
76
 #define Servo2_OUT_HIGH PORTB |= _BV(0) //Servo2(B0)
68
 #define Servo2_OUT_HIGH PORTB |= _BV(0) //Servo2(B0)
78
 #define Servo4_OUT_HIGH PORTB |= _BV(2) //Servo4(B2)
70
 #define Servo4_OUT_HIGH PORTB |= _BV(2) //Servo4(B2)
79
 #define Servo5_OUT_HIGH PORTB |= _BV(3) //Servo5(B3)
71
 #define Servo5_OUT_HIGH PORTB |= _BV(3) //Servo5(B3)
80
 #define Servo6_OUT_HIGH PORTB |= _BV(4) //Servo6(B4)
72
 #define Servo6_OUT_HIGH PORTB |= _BV(4) //Servo6(B4)
81
-#define Servo7_OUT_HIGH PORTB |= _BV(5)//Servo7(B5) 
73
+#define Servo7_OUT_HIGH PORTB |= _BV(5) //Servo7(B5) 
82
 #define Servo8_OUT_HIGH PORTC |= _BV(0) //Servo8(C0)
74
 #define Servo8_OUT_HIGH PORTC |= _BV(0) //Servo8(C0)
83
-//
84
 #define Servo_Ports_LOW PORTD &= 0x7F ; PORTB &= 0xc0; PORTC &=0xFE //all servos low
75
 #define Servo_Ports_LOW PORTD &= 0x7F ; PORTB &= 0xc0; PORTC &=0xFE //all servos low
85
-//
76
+
86
 #define LED_pin A3
77
 #define LED_pin A3
87
 #define LED_ON  PORTC |= _BV(3)
78
 #define LED_ON  PORTC |= _BV(3)
88
 #define LED_OFF  PORTC &= ~_BV(3)
79
 #define LED_OFF  PORTC &= ~_BV(3)
89
 #define NOP() __asm__ __volatile__("nop")
80
 #define NOP() __asm__ __volatile__("nop")
90
-//*******************************************
81
+        
91
 
82
 
92
 // Globals:
83
 // Globals:
93
 static uint8_t ccData[27];
84
 static uint8_t ccData[27];
112
 int count = 0;
103
 int count = 0;
113
 uint16_t c[8];
104
 uint16_t c[8];
114
 
105
 
115
-//
106
+
116
 void setup()
107
 void setup()
117
 {
108
 {
118
 
109
 
119
-#if defined(SPIBB)
120
-    pinMode(MO_pin, OUTPUT);//SI
121
-    pinMode(MI_pin, INPUT);//SO
122
-    pinMode(SCLK_pin, OUTPUT);//SCLK
123
-    pinMode(CS, OUTPUT);//CS output
124
-    pinMode(GDO_pin, INPUT); //GDO0 pin
125
-    SCK_off;//start sck low
126
-    MO_off;//low
127
-#endif
128
-    //
110
+    #if defined(SPIBB)
111
+        pinMode(MO_pin, OUTPUT);    //SI
112
+        pinMode(MI_pin, INPUT);     //SO
113
+        pinMode(SCLK_pin, OUTPUT);  //SCLK
114
+        pinMode(CS, OUTPUT);        //CS output
115
+        pinMode(GDO_pin, INPUT);    //GDO0 pin
116
+        SCK_off;                    //start sck low
117
+        MO_off;                     //low
118
+    #endif
119
+    
129
     pinMode(LED_pin, OUTPUT);
120
     pinMode(LED_pin, OUTPUT);
130
     CS_on;
121
     CS_on;
131
-    //
132
-#if defined(SPIHW)
133
-    pinMode(CS, OUTPUT);
134
-    pinMode(GDO_pin, INPUT);
135
-    //
136
-    SPI.setClockDivider(SPI_CLOCK_DIV2);
137
-    SPI.setBitOrder( MSBFIRST);
138
-    SPI.begin();
139
-#endif
140
-    //
122
+
123
+    #if defined(SPIHW)
124
+        pinMode(CS, OUTPUT);
125
+        pinMode(GDO_pin, INPUT);
126
+        SPI.setClockDivider(SPI_CLOCK_DIV2);
127
+        SPI.setBitOrder( MSBFIRST);
128
+        SPI.begin();
129
+    #endif
130
+
141
     pinMode(Servo1_OUT, OUTPUT); //Servo1
131
     pinMode(Servo1_OUT, OUTPUT); //Servo1
142
     pinMode(Servo2_OUT, OUTPUT); //Servo2
132
     pinMode(Servo2_OUT, OUTPUT); //Servo2
143
     pinMode(Servo3_OUT, OUTPUT); //Servo3
133
     pinMode(Servo3_OUT, OUTPUT); //Servo3
147
     pinMode(Servo7_OUT, OUTPUT); //Servo7
137
     pinMode(Servo7_OUT, OUTPUT); //Servo7
148
     pinMode(Servo8_OUT, OUTPUT); //Servo8
138
     pinMode(Servo8_OUT, OUTPUT); //Servo8
149
     //Servo8_OUT_HIGH;//bindpin pullup
139
     //Servo8_OUT_HIGH;//bindpin pullup
150
-    //
151
-#if defined DEBUG
152
-    Serial.begin(115200);
153
-    int8_t i;
154
-    Serial.print("PartNum ");
155
-    i = cc2500_readReg(CC2500_30_PARTNUM + CC2500_READ_BURST);
156
-    Serial.println(i);
157
-    delay(10);
158
-    Serial.print("Version ");
159
-    i = cc2500_readReg(CC2500_31_VERSION + CC2500_READ_BURST);
160
-    Serial.println(i);
161
-#endif
162
-    //
163
-#if F_CPU == 16000000
164
-    scale = 2;
165
-#elif F_CPU == 8000000
166
-    scale = 1;
167
-#else
168
-#error // 8 or 16MHz only !
169
-#endif
170
-    //
171
-    initialize(1);//binding
140
+
141
+    #if defined DEBUG
142
+        Serial.begin(115200);
143
+        int8_t i;
144
+        Serial.print("PartNum ");
145
+        i = cc2500_readReg(CC2500_30_PARTNUM + CC2500_READ_BURST);
146
+        Serial.println(i);
147
+        delay(10);
148
+        Serial.print("Version ");
149
+        i = cc2500_readReg(CC2500_31_VERSION + CC2500_READ_BURST);
150
+        Serial.println(i);
151
+    #endif
152
+    
153
+    #if F_CPU == 16000000
154
+        scale = 2;
155
+    #elif F_CPU == 8000000
156
+        scale = 1;
157
+    #else
158
+        #error // 8 or 16MHz only !
159
+    #endif
160
+
161
+
162
+
163
+    initialize(1);                  //binding
172
     binding();
164
     binding();
173
-    pinMode(Servo8_OUT, OUTPUT); //Servo8.bind pin is set to output again.
174
-    initialize(0);//data
175
-    //
165
+    pinMode(Servo8_OUT, OUTPUT);    //Servo8.bind pin is set to output again.
166
+    initialize(0);                  //data
167
+    
176
     jumper1 = PPM_jumper(); // Check the possible jumper positions for changing the receiver mode.
168
     jumper1 = PPM_jumper(); // Check the possible jumper positions for changing the receiver mode.
177
-    //
169
+    
178
     if (jumper1 == 1) {
170
     if (jumper1 == 1) {
179
         //initiallize default ppm values
171
         //initiallize default ppm values
180
         for (int i = 0; i < chanel_number; i++) {
172
         for (int i = 0; i < chanel_number; i++) {
184
         digitalWrite(sigPin, !onState);  //set the PPM signal pin to the default state (off)
176
         digitalWrite(sigPin, !onState);  //set the PPM signal pin to the default state (off)
185
     }
177
     }
186
     config_timer();
178
     config_timer();
187
-    //
188
     channr = 0;
179
     channr = 0;
189
     cc2500_writeReg(CC2500_0A_CHANNR, hopData[channr]);//0A-hop
180
     cc2500_writeReg(CC2500_0A_CHANNR, hopData[channr]);//0A-hop
190
     cc2500_writeReg(CC2500_23_FSCAL3, 0x89); //23-89
181
     cc2500_writeReg(CC2500_23_FSCAL3, 0x89); //23-89
196
 void loop()
187
 void loop()
197
 {
188
 {
198
     unsigned long time = micros();
189
     unsigned long time = micros();
199
-#if defined(FAILSAFE)
200
-    if (missingPackets > 170) {
201
-        //**************************************
202
-        //noInterrupts();//
203
-        //digitalWrite(sigPin, LOW);
204
-        //Servo_Ports_LOW;
205
-        //**********************************************
206
-        missingPackets = 0;
207
-        int i;
208
-        for (i = 0; i < 8; i++) {
209
-            Servo_data[i] = 1500;
210
-            ppm[i] = 1500;
211
-            if (i == 2) {
212
-                Servo_data[2] = 1000; //THROTLE ON CHN3 here it can be changed Throttle on other channel
213
-                ppm[2] = 1000;
190
+
191
+    #if defined(FAILSAFE)
192
+        if (missingPackets > 170) {
193
+            //**************************************
194
+            //noInterrupts();//
195
+            //digitalWrite(sigPin, LOW);
196
+            //Servo_Ports_LOW;
197
+            //**********************************************
198
+            missingPackets = 0;
199
+            int i;
200
+            for (i = 0; i < 8; i++) {
201
+                Servo_data[i] = 1500;
202
+                ppm[i] = 1500;
203
+                if (i == 2) {
204
+                    Servo_data[2] = 1000; //THROTLE ON CHN3 here it can be changed Throttle on other channel
205
+                    ppm[2] = 1000;
206
+                }
214
             }
207
             }
215
         }
208
         }
216
-    }
217
-#endif
209
+    #endif
210
+
218
     while (1) {
211
     while (1) {
219
         if ((micros() - time) > 9000) {
212
         if ((micros() - time) > 9000) {
220
             missingPackets++;
213
             missingPackets++;
278
             }
271
             }
279
             ppm[i] = Servo_data[i];
272
             ppm[i] = Servo_data[i];
280
         }
273
         }
281
-#if defined(DEBUG5)
282
-        //Serial.println(rssi);
283
-#endif
284
-#if defined(DEBUG0)
285
-        for (int i = 0; i < 8; i++) {
286
-            Serial.print(" ");
287
-            Serial.print(Servo_data[i]);
288
-            Serial.print(" ");
289
-        }
290
-        Serial.println(" ");
291
-#endif
274
+        #if defined(DEBUG5)
275
+                //Serial.println(rssi);
276
+        #endif
277
+        #if defined(DEBUG0)
278
+                for (int i = 0; i < 8; i++) {
279
+                    Serial.print(" ");
280
+                    Serial.print(Servo_data[i]);
281
+                    Serial.print(" ");
282
+                }
283
+                Serial.println(" ");
284
+        #endif
292
     }
285
     }
293
-    //
286
+
294
     cc2500_strobe(CC2500_SRX);
287
     cc2500_strobe(CC2500_SRX);
295
     if (debug == true) {
288
     if (debug == true) {
296
         debug = false;
289
         debug = false;
297
-#if defined(DEBUG2)
298
-        Serial.println(ccData[3], HEX);
299
-#endif
290
+        #if defined(DEBUG2)
291
+                Serial.println(ccData[3], HEX);
292
+        #endif
300
     }
293
     }
301
 }
294
 }
302
 
295
 
338
     cc2500_writeReg(CC2500_03_FIFOTHR,  0x0F);  // reg 0x03:
331
     cc2500_writeReg(CC2500_03_FIFOTHR,  0x0F);  // reg 0x03:
339
     cc2500_writeReg(CC2500_09_ADDR, bind ? 0x03 : txid[0]);
332
     cc2500_writeReg(CC2500_09_ADDR, bind ? 0x03 : txid[0]);
340
     cc2500_strobe(CC2500_SIDLE);    // Go to idle...
333
     cc2500_strobe(CC2500_SIDLE);    // Go to idle...
341
-
342
     cc2500_writeReg(CC2500_07_PKTCTRL1, 0x0D);  // reg 0x07 hack: Append status, filter by address, auto-flush on bad crc, PQT=0
334
     cc2500_writeReg(CC2500_07_PKTCTRL1, 0x0D);  // reg 0x07 hack: Append status, filter by address, auto-flush on bad crc, PQT=0
343
     //cc2500_writeReg(CC2500_0C_FSCTRL0, 0);    // Frequency offset...
335
     //cc2500_writeReg(CC2500_0C_FSCTRL0, 0);    // Frequency offset...
344
     cc2500_writeReg(CC2500_0C_FSCTRL0, bind ? 0x00 : count); // Frequency offset hack
336
     cc2500_writeReg(CC2500_0C_FSCTRL0, bind ? 0x00 : count); // Frequency offset hack
376
         }
368
         }
377
     }
369
     }
378
 
370
 
379
-#if defined(DEBUG)
380
-    Serial.print(txid[0], HEX);
381
-    Serial.println(txid[1], HEX);
382
-#endif
371
+    #if defined(DEBUG)
372
+        Serial.print(txid[0], HEX);
373
+        Serial.println(txid[1], HEX);
374
+    #endif
375
+
383
     for (uint8_t bindIdx = 0x05; bindIdx <= 120; bindIdx += 5) {
376
     for (uint8_t bindIdx = 0x05; bindIdx <= 120; bindIdx += 5) {
384
         while (1) {
377
         while (1) {
385
             if (GDO_1) {
378
             if (GDO_1) {
406
                 }
399
                 }
407
             }
400
             }
408
         }
401
         }
409
-#if defined(DEBUG)
410
-        Serial.println(bindIdx / 5);
411
-#endif
402
+        #if defined(DEBUG)
403
+                Serial.println(bindIdx / 5);
404
+        #endif
412
         if (eol) break; // End of list found, stop!
405
         if (eol) break; // End of list found, stop!
413
     }
406
     }
414
-#if defined(DEBUG)
415
-    for (uint8_t jumpIdx = 0; jumpIdx < (listLength); jumpIdx++) {
416
-        Serial.print(" ");
417
-        Serial.print(hopData[jumpIdx], HEX);
418
-        Serial.print(" ");
419
-    }
420
-    Serial.println(" ");
421
-#endif
407
+
408
+    #if defined(DEBUG)
409
+        for (uint8_t jumpIdx = 0; jumpIdx < (listLength); jumpIdx++) {
410
+            Serial.print(" ");
411
+            Serial.print(hopData[jumpIdx], HEX);
412
+            Serial.print(" ");
413
+        }
414
+        Serial.println(" ");
415
+    #endif
416
+
422
     Store_bind();
417
     Store_bind();
423
     cc2500_strobe(CC2500_SIDLE);    // Back to idle
418
     cc2500_strobe(CC2500_SIDLE);    // Back to idle
424
 }
419
 }
430
         pinMode(Servo5_OUT, OUTPUT);
425
         pinMode(Servo5_OUT, OUTPUT);
431
         Servo_Ports_LOW;
426
         Servo_Ports_LOW;
432
         //code for servo.
427
         //code for servo.
433
-        cur_chan_numb++;//next servo
428
+        cur_chan_numb++; //next servo
434
         if (cur_chan_numb < chanel_number) {
429
         if (cur_chan_numb < chanel_number) {
435
             total_servo_time += Servo_data[cur_chan_numb] * scale;
430
             total_servo_time += Servo_data[cur_chan_numb] * scale;
436
             OCR1A = Servo_data[cur_chan_numb] * scale;
431
             OCR1A = Servo_data[cur_chan_numb] * scale;
580
             }
575
             }
581
         }
576
         }
582
     }
577
     }
583
-#if defined(DEBUG1)
584
-    Serial.println(count, HEX);
585
-#endif
578
+    #if defined(DEBUG1)
579
+        Serial.println(count, HEX);
580
+    #endif
586
 }
581
 }
587
 
582
 
588
 
583
 

Loading…
Cancel
Save