Rev 2110 | Rev 2116 | Go to most recent revision | Only display areas with differences | Ignore whitespace | Details | Blame | Last modification | View Log | RSS feed
Rev 2110 | Rev 2115 | ||
---|---|---|---|
1 | #include <stdlib.h> |
1 | #include <stdlib.h> |
2 | #include <avr/io.h> |
2 | #include <avr/io.h> |
3 | #include <avr/interrupt.h> |
3 | #include <avr/interrupt.h> |
4 | 4 | ||
5 | #include "rc.h" |
5 | #include "rc.h" |
6 | #include "controlMixer.h" |
6 | #include "controlMixer.h" |
7 | #include "configuration.h" |
7 | #include "configuration.h" |
8 | #include "commands.h" |
8 | #include "commands.h" |
9 | #include "output.h" |
9 | #include "output.h" |
10 | 10 | ||
11 | // The channel array is 0-based! |
11 | // The channel array is 0-based! |
12 | volatile int16_t PPM_in[MAX_CHANNELS]; |
12 | volatile int16_t PPM_in[MAX_CHANNELS]; |
13 | volatile uint8_t RCQuality; |
13 | volatile uint8_t RCQuality; |
14 | 14 | ||
15 | uint8_t lastRCCommand = COMMAND_NONE; |
15 | uint8_t lastRCCommand = COMMAND_NONE; |
16 | uint8_t lastFlightMode = FLIGHT_MODE_NONE; |
16 | uint8_t lastFlightMode = FLIGHT_MODE_NONE; |
17 | 17 | ||
18 | #define TIME(s) ((int16_t)(((long)F_CPU/(long)8000)*(float)s)) |
18 | #define TIME(s) ((int16_t)(((long)F_CPU/(long)8000)*(float)s)) |
19 | 19 | ||
20 | /*************************************************************** |
20 | /*************************************************************** |
21 | * 16bit timer 1 is used to decode the PPM-Signal |
21 | * 16bit timer 1 is used to decode the PPM-Signal |
22 | ***************************************************************/ |
22 | ***************************************************************/ |
23 | void RC_Init(void) { |
23 | void RC_Init(void) { |
24 | uint8_t sreg = SREG; |
24 | uint8_t sreg = SREG; |
25 | 25 | ||
26 | // disable all interrupts before reconfiguration |
26 | // disable all interrupts before reconfiguration |
27 | cli(); |
27 | cli(); |
28 | 28 | ||
29 | // PPM-signal is connected to the Input Capture Pin (PD6) of timer 1 |
29 | // PPM-signal is connected to the Input Capture Pin (PD6) of timer 1 |
30 | DDRB &= ~(1<<0); |
30 | DDRB &= ~(1<<0); |
31 | PORTB |= (1<<PORTB0); |
31 | PORTB |= (1<<PORTB0); |
32 | 32 | ||
33 | // Timer/Counter1 Control Register A, B, C |
33 | // Timer/Counter1 Control Register A, B, C |
34 | // Normal Mode (bits: WGM13=0, WGM12=0, WGM11=0, WGM10=0) |
34 | // Normal Mode (bits: WGM13=0, WGM12=0, WGM11=0, WGM10=0) |
35 | // Compare output pin A & B is disabled (bits: COM1A1=0, COM1A0=0, COM1B1=0, COM1B0=0) |
35 | // Compare output pin A & B is disabled (bits: COM1A1=0, COM1A0=0, COM1B1=0, COM1B0=0) |
36 | // Set clock source to SYSCLK/64 (bit: CS12=0, CS11=1, CS10=1) |
36 | // Set clock source to SYSCLK/64 (bit: CS12=0, CS11=1, CS10=1) |
37 | // Enable input capture noise cancler (bit: ICNC1=1) |
37 | // Enable input capture noise cancler (bit: ICNC1=1) |
38 | // Trigger on positive edge of the input capture pin (bit: ICES1=1), |
38 | // Trigger on positive edge of the input capture pin (bit: ICES1=1), |
39 | // Therefore the counter incremets at a clock of 20 MHz/64 = 312.5 kHz or 3.2�s |
39 | // Therefore the counter incremets at a clock of 20 MHz/64 = 312.5 kHz or 3.2�s |
40 | // The longest period is 0xFFFF / 312.5 kHz = 0.209712 s. |
40 | // The longest period is 0xFFFF / 312.5 kHz = 0.209712 s. |
41 | TCCR1A &= ~((1 << COM1A1) | (1 << COM1A0) | (1 << COM1B1) | (1 << COM1B0) | (1 << WGM11) | (1 << WGM10)); |
41 | TCCR1A &= ~((1 << COM1A1) | (1 << COM1A0) | (1 << COM1B1) | (1 << COM1B0) | (1 << WGM11) | (1 << WGM10)); |
42 | TCCR1B &= ~((1 << WGM13) | (1 << WGM12) | (1 << CS12)); |
42 | TCCR1B &= ~((1 << WGM13) | (1 << WGM12) | (1 << CS12)); |
43 | TCCR1B |= (1 << CS11) | (1 << ICES1) | (1 << ICNC1); |
43 | TCCR1B |= (1 << CS11) | (1 << ICES1) | (1 << ICNC1); |
44 | TCCR1C &= ~((1 << FOC1A) | (1 << FOC1B)); |
44 | TCCR1C &= ~((1 << FOC1A) | (1 << FOC1B)); |
45 | 45 | ||
46 | // Timer/Counter1 Interrupt Mask Register |
46 | // Timer/Counter1 Interrupt Mask Register |
47 | // Enable Input Capture Interrupt (bit: ICIE1=1) |
47 | // Enable Input Capture Interrupt (bit: ICIE1=1) |
48 | // Disable Output Compare A & B Match Interrupts (bit: OCIE1B=0, OICIE1A=0) |
48 | // Disable Output Compare A & B Match Interrupts (bit: OCIE1B=0, OICIE1A=0) |
49 | // Enable Overflow Interrupt (bit: TOIE1=0) |
49 | // Enable Overflow Interrupt (bit: TOIE1=0) |
50 | TIMSK1 &= ~((1<<OCIE1B) | (1<<OCIE1A) | (1<<TOIE1)); |
50 | TIMSK1 &= ~((1<<OCIE1B) | (1<<OCIE1A) | (1<<TOIE1)); |
51 | TIMSK1 |= (1<<ICIE1); |
51 | TIMSK1 |= (1<<ICIE1); |
52 | 52 | ||
53 | RCQuality = 0; |
53 | RCQuality = 0; |
54 | 54 | ||
55 | SREG = sreg; |
55 | SREG = sreg; |
56 | } |
56 | } |
57 | 57 | ||
58 | /********************************************************************/ |
58 | /********************************************************************/ |
59 | /* Every time a positive edge is detected at PD6 */ |
59 | /* Every time a positive edge is detected at PD6 */ |
60 | /********************************************************************/ |
60 | /********************************************************************/ |
61 | /* t-Frame |
61 | /* t-Frame |
62 | <-----------------------------------------------------------------------> |
62 | <-----------------------------------------------------------------------> |
63 | ____ ______ _____ ________ ______ sync gap ____ |
63 | ____ ______ _____ ________ ______ sync gap ____ |
64 | | | | | | | | | | | | |
64 | | | | | | | | | | | | |
65 | | | | | | | | | | | | |
65 | | | | | | | | | | | | |
66 | ___| |_| |_| |_| |_.............| |________________| |
66 | ___| |_| |_| |_| |_.............| |________________| |
67 | <-----><-------><------><----------- <------> <--- |
67 | <-----><-------><------><----------- <------> <--- |
68 | t0 t1 t2 t4 tn t0 |
68 | t0 t1 t2 t4 tn t0 |
69 | 69 | ||
70 | The PPM-Frame length is 22.5 ms. |
70 | The PPM-Frame length is 22.5 ms. |
71 | Channel high pulse width range is 0.7 ms to 1.7 ms completed by an 0.3 ms low pulse. |
71 | Channel high pulse width range is 0.7 ms to 1.7 ms completed by an 0.3 ms low pulse. |
72 | The mininimum time delay of two events coding a channel is ( 0.7 + 0.3) ms = 1 ms. |
72 | The mininimum time delay of two events coding a channel is ( 0.7 + 0.3) ms = 1 ms. |
73 | The maximum time delay of two events coding a channel is ( 1.7 + 0.3) ms = 2 ms. |
73 | The maximum time delay of two events coding a channel is ( 1.7 + 0.3) ms = 2 ms. |
74 | The minimum duration of all channels at minimum value is 8 * 1 ms = 8 ms. |
74 | The minimum duration of all channels at minimum value is 8 * 1 ms = 8 ms. |
75 | The maximum duration of all channels at maximum value is 8 * 2 ms = 16 ms. |
75 | The maximum duration of all channels at maximum value is 8 * 2 ms = 16 ms. |
76 | The remaining time of (22.5 - 8 ms) ms = 14.5 ms to (22.5 - 16 ms) ms = 6.5 ms is |
76 | The remaining time of (22.5 - 8 ms) ms = 14.5 ms to (22.5 - 16 ms) ms = 6.5 ms is |
77 | the syncronization gap. |
77 | the syncronization gap. |
78 | */ |
78 | */ |
79 | ISR(TIMER1_CAPT_vect) { // typical rate of 1 ms to 2 ms |
79 | ISR(TIMER1_CAPT_vect) { // typical rate of 1 ms to 2 ms |
80 | int16_t signal, tmp; |
80 | int16_t signal, tmp; |
81 | static int16_t index; |
81 | static int16_t index; |
82 | static uint16_t oldICR1 = 0; |
82 | static uint16_t oldICR1 = 0; |
83 | 83 | ||
84 | // 16bit Input Capture Register ICR1 contains the timer value TCNT1 |
84 | // 16bit Input Capture Register ICR1 contains the timer value TCNT1 |
85 | // at the time the edge was detected |
85 | // at the time the edge was detected |
86 | 86 | ||
87 | // calculate the time delay to the previous event time which is stored in oldICR1 |
87 | // calculate the time delay to the previous event time which is stored in oldICR1 |
88 | // calculatiing the difference of the two uint16_t and converting the result to an int16_t |
88 | // calculatiing the difference of the two uint16_t and converting the result to an int16_t |
89 | // implicit handles a timer overflow 65535 -> 0 the right way. |
89 | // implicit handles a timer overflow 65535 -> 0 the right way. |
90 | signal = (uint16_t) ICR1 - oldICR1; |
90 | signal = (uint16_t) ICR1 - oldICR1; |
91 | oldICR1 = ICR1; |
91 | oldICR1 = ICR1; |
92 | 92 | ||
93 | //sync gap? (3.5 ms < signal < 25.6 ms) |
93 | //sync gap? (3.5 ms < signal < 25.6 ms) |
94 | if (signal > TIME(3.5)) { |
94 | if (signal > TIME(3.5)) { |
95 | index = 0; |
95 | index = 0; |
96 | } else { // within the PPM frame |
96 | } else { // within the PPM frame |
97 | if (index < MAX_CHANNELS) { // PPM24 supports 12 channels |
97 | if (index < MAX_CHANNELS) { // PPM24 supports 12 channels |
98 | // check for valid signal length (0.8 ms < signal < 2.2 ms) |
98 | // check for valid signal length (0.8 ms < signal < 2.2 ms) |
99 | if ((signal >= TIME(0.8)) && (signal < TIME(2.2))) { |
99 | if ((signal >= TIME(0.8)) && (signal < TIME(2.2))) { |
100 | // shift signal to zero symmetric range -154 to 159 |
100 | // shift signal to zero symmetric range -154 to 159 |
101 | //signal -= 3750; // theoretical value |
101 | //signal -= 3750; // theoretical value |
102 | signal -= (TIME(1.5) + RC_TRIM); // best value with my Futaba in zero trim. |
102 | signal -= (TIME(1.5) + RC_TRIM); // best value with my Futaba in zero trim. |
103 | // check for stable signal |
103 | // check for stable signal |
104 | if (abs(signal - PPM_in[index]) < TIME(0.05)) { |
104 | if (abs(signal - PPM_in[index]) < TIME(0.05)) { |
105 | if (RCQuality < 200) |
105 | if (RCQuality < 200) |
106 | RCQuality += 10; |
106 | RCQuality += 10; |
107 | else |
107 | else |
108 | RCQuality = 200; |
108 | RCQuality = 200; |
109 | } |
109 | } |
110 | // If signal is the same as before +/- 1, just keep it there. Naah lets get rid of this slimy sticy stuff. |
110 | // If signal is the same as before +/- 1, just keep it there. Naah lets get rid of this slimy sticy stuff. |
111 | // if (signal >= PPM_in[index] - 1 && signal <= PPM_in[index] + 1) { |
111 | // if (signal >= PPM_in[index] - 1 && signal <= PPM_in[index] + 1) { |
112 | // In addition, if the signal is very close to 0, just set it to 0. |
112 | // In addition, if the signal is very close to 0, just set it to 0. |
113 | if (signal >= -1 && signal <= 1) { |
113 | if (signal >= -1 && signal <= 1) { |
114 | tmp = 0; |
114 | tmp = 0; |
115 | //} else { |
115 | //} else { |
116 | // tmp = PPM_in[index]; |
116 | // tmp = PPM_in[index]; |
117 | // } |
117 | // } |
118 | } else |
118 | } else |
119 | tmp = signal; |
119 | tmp = signal; |
120 | PPM_in[index] = tmp; // update channel value |
120 | PPM_in[index] = tmp; // update channel value |
121 | } |
121 | } |
122 | index++; // next channel |
122 | index++; // next channel |
123 | // demux sum signal for channels 5 to 7 to J3, J4, J5 |
123 | // demux sum signal for channels 5 to 7 to J3, J4, J5 |
124 | // TODO: General configurability of this R/C channel forwarding. Or remove it completely - the |
124 | // TODO: General configurability of this R/C channel forwarding. Or remove it completely - the |
125 | // channels are usually available at the receiver anyway. |
125 | // channels are usually available at the receiver anyway. |
126 | // if(index == 5) J3HIGH; else J3LOW; |
126 | // if(index == 5) J3HIGH; else J3LOW; |
127 | // if(index == 6) J4HIGH; else J4LOW; |
127 | // if(index == 6) J4HIGH; else J4LOW; |
128 | // if(CPUType != ATMEGA644P) // not used as TXD1 |
128 | // if(CPUType != ATMEGA644P) // not used as TXD1 |
129 | // { |
129 | // { |
130 | // if(index == 7) J5HIGH; else J5LOW; |
130 | // if(index == 7) J5HIGH; else J5LOW; |
131 | // } |
131 | // } |
132 | } |
132 | } |
133 | } |
133 | } |
134 | } |
134 | } |
135 | 135 | ||
136 | #define RCChannel(dimension) PPM_in[channelMap.channels[dimension]] |
136 | #define RCChannel(dimension) PPM_in[channelMap.channels[dimension]] |
137 | #define COMMAND_CHANNEL_VERTICAL CH_THROTTLE |
137 | #define COMMAND_CHANNEL_VERTICAL CH_THROTTLE |
138 | #define COMMAND_CHANNEL_HORIZONTAL CH_YAW |
138 | #define COMMAND_CHANNEL_HORIZONTAL CH_YAW |
139 | 139 | ||
140 | uint8_t getControlModeSwitch(void) { |
140 | uint8_t getControlModeSwitch(void) { |
141 | int16_t channel = RCChannel(CH_MODESWITCH); |
141 | int16_t channel = RCChannel(CH_MODESWITCH); |
142 | uint8_t flightMode = channel < -TIME(0.17) ? FLIGHT_MODE_MANUAL : (channel > TIME(0.17) ? FLIGHT_MODE_ANGLES : FLIGHT_MODE_RATE); |
142 | uint8_t flightMode = channel < -TIME(0.17) ? FLIGHT_MODE_MANUAL : (channel > TIME(0.17) ? FLIGHT_MODE_ANGLES : FLIGHT_MODE_RATE); |
143 | return flightMode; |
143 | return flightMode; |
144 | } |
144 | } |
145 | 145 | ||
146 | // Gyro calibration is performed as.... well mode switch with no throttle and no airspeed would be nice. |
146 | // Gyro calibration is performed as.... well mode switch with no throttle and no airspeed would be nice. |
147 | // Maybe simply: Very very low throttle. |
147 | // Maybe simply: Very very low throttle. |
148 | // Throttle xlow for COMMAND_TIMER: GYROCAL (once). |
148 | // Throttle xlow for COMMAND_TIMER: GYROCAL (once). |
149 | // mode switched: CHMOD |
149 | // mode switched: CHMOD |
150 | 150 | ||
151 | uint8_t RC_getCommand(void) { |
151 | uint8_t RC_getCommand(void) { |
152 | uint8_t flightMode = getControlModeSwitch(); |
152 | uint8_t flightMode = getControlModeSwitch(); |
153 | 153 | ||
154 | if (lastFlightMode != flightMode) { |
154 | if (lastFlightMode != flightMode) { |
155 | lastFlightMode = flightMode; |
155 | lastFlightMode = flightMode; |
156 | lastRCCommand = COMMAND_CHMOD; |
156 | lastRCCommand = COMMAND_CHMOD; |
157 | return lastRCCommand; |
157 | return lastRCCommand; |
158 | } |
158 | } |
159 | 159 | ||
160 | int16_t channel = RCChannel(CH_THROTTLE); |
160 | int16_t channel = RCChannel(CH_THROTTLE); |
161 | 161 | ||
162 | if (channel <= -TIME(0.55)) { |
162 | if (channel <= -TIME(0.55)) { |
163 | lastRCCommand = COMMAND_GYROCAL; |
163 | lastRCCommand = COMMAND_GYROCAL; |
164 | debugOut.analog[17] = 1; |
164 | debugOut.analog[17] = 1; |
165 | } else { |
165 | } else { |
166 | lastRCCommand = COMMAND_NONE; |
166 | lastRCCommand = COMMAND_NONE; |
167 | debugOut.analog[17] = 0; |
167 | debugOut.analog[17] = 0; |
168 | } |
168 | } |
169 | return lastRCCommand; |
169 | return lastRCCommand; |
170 | } |
170 | } |
171 | 171 | ||
172 | uint8_t RC_getArgument(void) { |
172 | uint8_t RC_getArgument(void) { |
173 | return lastFlightMode; |
173 | return lastFlightMode; |
174 | } |
174 | } |
175 | 175 | ||
176 | /* |
176 | /* |
177 | * Get Pitch, Roll, Throttle, Yaw values |
177 | * Get Pitch, Roll, Throttle, Yaw values |
178 | */ |
178 | */ |
179 | void RC_periodicTaskAndPRYT(int16_t* PRYT) { |
179 | void RC_periodicTaskAndPRYT(int16_t* PRYT) { |
180 | if (RCQuality) { |
180 | if (RCQuality) { |
181 | RCQuality--; |
181 | RCQuality--; |
182 | 182 | ||
183 | debugOut.analog[20] = RCChannel(CH_ELEVATOR); |
183 | debugOut.analog[20] = RCChannel(CH_ELEVATOR); |
184 | debugOut.analog[21] = RCChannel(CH_AILERONS); |
184 | debugOut.analog[21] = RCChannel(CH_AILERONS); |
185 | debugOut.analog[22] = RCChannel(CH_RUDDER); |
185 | debugOut.analog[22] = RCChannel(CH_RUDDER); |
186 | debugOut.analog[23] = RCChannel(CH_THROTTLE); |
186 | debugOut.analog[23] = RCChannel(CH_THROTTLE); |
187 | 187 | ||
188 | PRYT[CONTROL_ELEVATOR] = RCChannel(CH_ELEVATOR) / RC_SCALING; |
188 | PRYT[CONTROL_ELEVATOR] = RCChannel(CH_ELEVATOR) / RC_SCALING; |
189 | PRYT[CONTROL_AILERONS] = RCChannel(CH_AILERONS) / RC_SCALING; |
189 | PRYT[CONTROL_AILERONS] = RCChannel(CH_AILERONS) / RC_SCALING; |
190 | PRYT[CONTROL_RUDDER] = RCChannel(CH_RUDDER) / RC_SCALING; |
190 | PRYT[CONTROL_RUDDER] = RCChannel(CH_RUDDER) / RC_SCALING; |
191 | PRYT[CONTROL_THROTTLE] = RCChannel(CH_THROTTLE) / RC_SCALING; |
191 | PRYT[CONTROL_THROTTLE] = RCChannel(CH_THROTTLE) / RC_SCALING; |
192 | } // if RCQuality is no good, we just do nothing. |
192 | } // if RCQuality is no good, we just do nothing. |
193 | } |
193 | } |
194 | 194 | ||
195 | /* |
195 | /* |
196 | * Get other channel value |
196 | * Get other channel value |
197 | */ |
197 | */ |
198 | int16_t RC_getVariable(uint8_t varNum) { |
198 | int16_t RC_getVariable(uint8_t varNum) { |
199 | if (varNum < 4) |
199 | if (varNum < 4) |
200 | // 0th variable is 5th channel (1-based) etc. |
200 | // 0th variable is 5th channel (1-based) etc. |
201 | return (RCChannel(varNum + CH_POTS) >> 2) + VARIABLE_OFFSET; |
201 | return (RCChannel(varNum + CH_POTS) >> 2) + VARIABLE_OFFSET; |
202 | /* |
202 | /* |
203 | * Let's just say: |
203 | * Let's just say: |
204 | * The RC variable i is hardwired to channel i, i>=4 |
204 | * The RC variable i is hardwired to channel i, i>=4 |
205 | */ |
205 | */ |
206 | return (PPM_in[varNum] >> 2) + VARIABLE_OFFSET; |
206 | return (PPM_in[varNum] >> 2) + VARIABLE_OFFSET; |
207 | } |
207 | } |
208 | 208 | ||
209 | uint8_t RC_getSignalQuality(void) { |
209 | uint8_t RC_getSignalQuality(void) { |
210 | if (RCQuality >= 160) |
210 | if (RCQuality >= 160) |
211 | return SIGNAL_GOOD; |
211 | return SIGNAL_GOOD; |
212 | if (RCQuality >= 140) |
212 | if (RCQuality >= 140) |
213 | return SIGNAL_OK; |
213 | return SIGNAL_OK; |
214 | if (RCQuality >= 120) |
214 | if (RCQuality >= 120) |
215 | return SIGNAL_BAD; |
215 | return SIGNAL_BAD; |
216 | return SIGNAL_LOST; |
216 | return SIGNAL_LOST; |
217 | } |
217 | } |
218 | - | ||
219 | /* |
- | |
220 | * To should fired only when the right stick is in the center position. |
- | |
221 | * This will cause the value of pitch and roll stick to be adjusted |
- | |
222 | * to zero (not just to near zero, as per the assumption in rc.c |
- | |
223 | * about the rc signal. I had values about 50..70 with a Futaba |
- | |
224 | * R617 receiver.) This calibration is not strictly necessary, but |
- | |
225 | * for control logic that depends on the exact (non)center position |
- | |
226 | * of a stick, it may be useful. |
- | |
227 | */ |
218 | |
228 | void RC_calibrate(void) { |
219 | void RC_calibrate(void) { |
229 | // Do nothing. |
220 | // Do nothing. |
230 | } |
221 | } |
- | 222 | ||
- | 223 | int16_t RC_getZeroThrottle() { |
|
- | 224 | return TIME (-0.5); |
|
- | 225 | } |
|
231 | 226 |