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