Subversion Repositories FlightCtrl

Rev

Rev 2099 | Rev 2103 | Go to most recent revision | Only display areas with differences | Ignore whitespace | Details | Blame | Last modification | View Log | RSS feed

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