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