Rev 1166 | Rev 1171 | Go to most recent revision | Only display areas with differences | Ignore whitespace | Details | Blame | Last modification | View Log | RSS feed
Rev 1166 | Rev 1167 | ||
---|---|---|---|
1 | /*####################################################################################### |
1 | /*####################################################################################### |
2 | Decodieren eines RC Summen Signals |
2 | Decodieren eines RC Summen Signals |
3 | #######################################################################################*/ |
3 | #######################################################################################*/ |
4 | // ++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++ |
4 | // ++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++ |
5 | // + Copyright (c) 04.2007 Holger Buss |
5 | // + Copyright (c) 04.2007 Holger Buss |
6 | // + only for non-profit use |
6 | // + only for non-profit use |
7 | // + www.MikroKopter.com |
7 | // + www.MikroKopter.com |
8 | // + see the File "License.txt" for further Informations |
8 | // + see the File "License.txt" for further Informations |
9 | // ++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++ |
9 | // ++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++ |
10 | 10 | ||
11 | #include "rc.h" |
11 | #include "rc.h" |
12 | #include "main.h" |
12 | #include "main.h" |
13 | 13 | ||
14 | volatile int PPM_in[11]; |
14 | volatile int PPM_in[11]; |
15 | volatile int PPM_diff[11]; // das diffenzierte Stick-Signal |
15 | volatile int PPM_diff[11]; // das diffenzierte Stick-Signal |
16 | volatile unsigned char NewPpmData = 1; |
16 | volatile unsigned char NewPpmData = 1; |
17 | 17 | ||
18 | //############################################################################ |
18 | //############################################################################ |
19 | //zum decodieren des PPM-Signals wird Timer1 mit seiner Input |
19 | //zum decodieren des PPM-Signals wird Timer1 mit seiner Input |
20 | //Capture Funktion benutzt: |
20 | //Capture Funktion benutzt: |
21 | void rc_sum_init (void) |
21 | void rc_sum_init (void) |
22 | //############################################################################ |
22 | //############################################################################ |
23 | { |
23 | { |
24 | TCCR1B=(1<<CS11)|(1<<CS10)|(1<<ICES1)|(1<<ICNC1);//|(1 << WGM12); //timer1 prescale 64 |
24 | TCCR1B=(1<<CS11)|(1<<CS10)|(1<<ICES1)|(1<<ICNC1);//|(1 << WGM12); //timer1 prescale 64 |
25 | - | ||
26 | // PWM |
- | |
27 | //TCCR1A = (1 << COM1B1) | (1 << WGM11) | (1 << WGM10); |
- | |
28 | //TCCR1B |= (1 << WGM12); |
- | |
29 | //OCR1B = 55; |
- | |
30 | - | ||
31 | TIMSK1 |= _BV(ICIE1); |
25 | TIMSK1 |= _BV(ICIE1); |
32 | AdNeutralGier = 0; |
26 | AdNeutralGier = 0; |
33 | AdNeutralRoll = 0; |
27 | AdNeutralRoll = 0; |
34 | AdNeutralNick = 0; |
28 | AdNeutralNick = 0; |
35 | return; |
29 | return; |
36 | } |
30 | } |
37 | 31 | ||
38 | //############################################################################ |
32 | //############################################################################ |
39 | //Diese Routine startet und inizialisiert den Timer für RC |
33 | //Diese Routine startet und inizialisiert den Timer für RC |
40 | SIGNAL(SIG_INPUT_CAPTURE1) |
34 | SIGNAL(SIG_INPUT_CAPTURE1) |
41 | //############################################################################ |
35 | //############################################################################ |
42 | 36 | ||
43 | { |
37 | { |
44 | static unsigned int AltICR=0; |
38 | static unsigned int AltICR=0; |
45 | signed int signal = 0,tmp; |
39 | signed int signal = 0,tmp; |
46 | static int index; |
40 | static int index; |
47 | 41 | ||
48 | signal = (unsigned int) ICR1 - AltICR; |
42 | signal = (unsigned int) ICR1 - AltICR; |
49 | AltICR = ICR1; |
43 | AltICR = ICR1; |
50 | //Syncronisationspause? |
44 | //Syncronisationspause? |
51 | // if((signal > (int) Parameter_UserParam2 * 10) && (signal < 8000)) |
- | |
52 | if((signal > 1100) && (signal < 8000)) |
45 | if((signal > 1100) && (signal < 8000)) |
53 | { |
46 | { |
54 | if(index >= 4) NewPpmData = 0; // Null bedeutet: Neue Daten |
47 | if(index >= 4) NewPpmData = 0; // Null bedeutet: Neue Daten |
55 | index = 1; |
48 | index = 1; |
56 | } |
49 | } |
57 | else |
50 | else |
58 | { |
51 | { |
59 | if(index < 10) |
52 | if(index < 10) |
60 | { |
53 | { |
61 | if((signal > 250) && (signal < 687)) |
54 | if((signal > 250) && (signal < 687)) |
62 | { |
55 | { |
63 | signal -= 466; |
56 | signal -= 466; |
64 | // Stabiles Signal |
57 | // Stabiles Signal |
65 | if(abs(signal - PPM_in[index]) < 6) { if(SenderOkay < 200) SenderOkay += 10;} |
58 | if(abs(signal - PPM_in[index]) < 6) { if(SenderOkay < 200) SenderOkay += 10;} |
66 | // tmp = (7 * (PPM_in[index]) + signal) / 8; |
- | |
67 | tmp = (3 * (PPM_in[index]) + signal) / 4; |
59 | tmp = (3 * (PPM_in[index]) + signal) / 4; |
68 | if(tmp > signal+1) tmp--; else |
60 | if(tmp > signal+1) tmp--; else |
69 | if(tmp < signal-1) tmp++; |
61 | if(tmp < signal-1) tmp++; |
70 | if(SenderOkay >= 195) PPM_diff[index] = ((tmp - PPM_in[index]) / 3) * 3; |
62 | if(SenderOkay >= 195) PPM_diff[index] = ((tmp - PPM_in[index]) / 3) * 3; |
71 | else PPM_diff[index] = 0; |
63 | else PPM_diff[index] = 0; |
72 | PPM_in[index] = tmp; |
64 | PPM_in[index] = tmp; |
73 | } |
65 | } |
74 | index++; |
66 | index++; |
75 | /* |
- | |
76 | if(index == 5) J3High; else J3Low; // Servosignal an J3 anlegen |
67 | if(index == 5) J3High; else J3Low; // Servosignal an J3 anlegen |
77 | if(index == 6) J4High; else J4Low; // Servosignal an J4 anlegen |
68 | if(index == 6) J4High; else J4Low; // Servosignal an J4 anlegen |
78 | if(index == 7) J5High; else J5Low; // Servosignal an J5 anlegen |
69 | if(index == 7) J5High; else J5Low; // Servosignal an J5 anlegen |
79 | */ |
- | |
80 | } |
70 | } |
81 | } |
71 | } |
82 | } |
72 | } |
83 | 73 | ||
84 | 74 | ||
85 | 75 | ||
86 | 76 | ||
87 | 77 | ||
88 | 78 |