Subversion Repositories FlightCtrl

Rev

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

Rev 2116 Rev 2118
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
  DDRD &= ~(1<<6);
30
  DDRD &= ~(1<<6);
31
  PORTD |= (1<<PORTD6);
31
  PORTD |= (1<<PORTD6);
32
 
32
 
33
  // 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)
34
  // set as output
34
  // set as output
35
  DDRD |= (1<<DDD5) | (1<<DDD4) | (1<<DDD3);
35
  DDRD |= (1<<DDD5) | (1<<DDD4) | (1<<DDD3);
36
  // low level
36
  // low level
37
  PORTD &= ~((1<<PORTD5) | (1<<PORTD4) | (1<<PORTD3));
37
  PORTD &= ~((1<<PORTD5) | (1<<PORTD4) | (1<<PORTD3));
38
 
38
 
39
  // PD3 can't be used if 2nd UART is activated
39
  // PD3 can't be used if 2nd UART is activated
40
  // because TXD1 is at that port
40
  // because TXD1 is at that port
41
  if (CPUType != ATMEGA644P) {
41
  if (CPUType != ATMEGA644P) {
42
    DDRD |= (1<<PORTD3);
42
    DDRD |= (1<<PORTD3);
43
    PORTD &= ~(1<<PORTD3);
43
    PORTD &= ~(1<<PORTD3);
44
  }
44
  }
45
 
45
 
46
  // Timer/Counter1 Control Register A, B, C
46
  // Timer/Counter1 Control Register A, B, C
47
 
47
 
48
  // Normal Mode (bits: WGM13=0, WGM12=0, WGM11=0, WGM10=0)
48
  // 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)
49
  // 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)
50
  // Set clock source to SYSCLK/64 (bit: CS12=0, CS11=1, CS10=1)
51
  // Enable input capture noise cancler (bit: ICNC1=1)
51
  // Enable input capture noise cancler (bit: ICNC1=1)
52
  // 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),
53
  // 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
54
  // The longest period is 0xFFFF / 312.5 kHz = 0.209712 s.
54
  // 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));
55
  TCCR1A &= ~((1 << COM1A1) | (1 << COM1A0) | (1 << COM1B1) | (1 << COM1B0) | (1 << WGM11) | (1 << WGM10));
56
  TCCR1B &= ~((1 << WGM13) | (1 << WGM12) | (1 << CS12));
56
  TCCR1B &= ~((1 << WGM13) | (1 << WGM12) | (1 << CS12));
57
  TCCR1B |= (1 << CS11) | (1 << ICES1) | (1 << ICNC1);
57
  TCCR1B |= (1 << CS11) | (1 << ICES1) | (1 << ICNC1);
58
  TCCR1C &= ~((1 << FOC1A) | (1 << FOC1B));
58
  TCCR1C &= ~((1 << FOC1A) | (1 << FOC1B));
59
 
59
 
60
  // Timer/Counter1 Interrupt Mask Register
60
  // Timer/Counter1 Interrupt Mask Register
61
  // Enable Input Capture Interrupt (bit: ICIE1=1)
61
  // Enable Input Capture Interrupt (bit: ICIE1=1)
62
  // 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)
63
  // Enable Overflow Interrupt (bit: TOIE1=0)
63
  // Enable Overflow Interrupt (bit: TOIE1=0)
64
  TIMSK1 &= ~((1<<OCIE1B) | (1<<OCIE1A) | (1<<TOIE1));
64
  TIMSK1 &= ~((1<<OCIE1B) | (1<<OCIE1A) | (1<<TOIE1));
65
  TIMSK1 |= (1<<ICIE1);
65
  TIMSK1 |= (1<<ICIE1);
66
 
66
 
67
  RCQuality = 0;
67
  RCQuality = 0;
68
 
68
 
69
  SREG = sreg;
69
  SREG = sreg;
70
}
70
}
71
 
71
 
72
/********************************************************************/
72
/********************************************************************/
73
/*         Every time a positive edge is detected at PD6            */
73
/*         Every time a positive edge is detected at PD6            */
74
/********************************************************************/
74
/********************************************************************/
75
/*                               t-Frame
75
/*                               t-Frame
76
    <----------------------------------------------------------------------->
76
    <----------------------------------------------------------------------->
77
     ____   ______   _____   ________                ______    sync gap      ____
77
     ____   ______   _____   ________                ______    sync gap      ____
78
    |    | |      | |     | |        |              |      |                |
78
    |    | |      | |     | |        |              |      |                |
79
    |    | |      | |     | |        |              |      |                |
79
    |    | |      | |     | |        |              |      |                |
80
 ___|    |_|      |_|     |_|        |_.............|      |________________|
80
 ___|    |_|      |_|     |_|        |_.............|      |________________|
81
    <-----><-------><------><-----------            <------>                <---
81
    <-----><-------><------><-----------            <------>                <---
82
 t0       t1      t2       t4                     tn                     t0
82
 t0       t1      t2       t4                     tn                     t0
83
 
83
 
84
 The PPM-Frame length is 22.5 ms.
84
 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.
85
 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.
86
 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.
87
 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.
88
 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.
89
 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
90
 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.
91
 the syncronization gap.
92
 */
92
 */
93
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
94
  int16_t signal, tmp;
94
  int16_t signal, tmp;
95
  static int16_t index;
95
  static int16_t index;
96
  static uint16_t oldICR1 = 0;
96
  static uint16_t oldICR1 = 0;
97
 
97
 
98
  // 16bit Input Capture Register ICR1 contains the timer value TCNT1
98
  // 16bit Input Capture Register ICR1 contains the timer value TCNT1
99
  // at the time the edge was detected
99
  // at the time the edge was detected
100
 
100
 
101
  // 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
102
  // 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
103
  // implicit handles a timer overflow 65535 -> 0 the right way.
103
  // implicit handles a timer overflow 65535 -> 0 the right way.
104
  signal = (uint16_t) ICR1 - oldICR1;
104
  signal = (uint16_t) ICR1 - oldICR1;
105
  oldICR1 = ICR1;
105
  oldICR1 = ICR1;
106
 
106
 
107
  //sync gap? (3.5 ms < signal < 25.6 ms)
107
  //sync gap? (3.5 ms < signal < 25.6 ms)
108
  if (signal > TIME(3.5)) {
108
  if (signal > TIME(3.5)) {
109
    index = 0;
109
    index = 0;
110
  } else { // within the PPM frame
110
  } else { // within the PPM frame
111
    if (index < MAX_CHANNELS) { // PPM24 supports 12 channels
111
    if (index < MAX_CHANNELS) { // PPM24 supports 12 channels
112
      // check for valid signal length (0.8 ms < signal < 2.2 ms)
112
      // check for valid signal length (0.8 ms < signal < 2.2 ms)
113
      if ((signal >= TIME(0.8)) && (signal < TIME(2.2))) {
113
      if ((signal >= TIME(0.8)) && (signal < TIME(2.2))) {
114
        // shift signal to zero symmetric range  -154 to 159
114
        // shift signal to zero symmetric range  -154 to 159
115
        //signal -= 3750; // theoretical value
115
        //signal -= 3750; // theoretical value
116
        signal -= (TIME(1.5) - 128 + channelMap.trim); // best value with my Futaba in zero trim.
116
        signal -= (TIME(1.5) - 128 + channelMap.trim); // best value with my Futaba in zero trim.
117
        // check for stable signal
117
        // check for stable signal
118
        if (abs(signal - PPM_in[index]) < TIME(0.05)) {
118
        if (abs(signal - PPM_in[index]) < TIME(0.05)) {
119
          if (RCQuality < 200)
119
          if (RCQuality < 200)
120
            RCQuality += 10;
120
            RCQuality += 10;
121
          else
121
          else
122
            RCQuality = 200;
122
            RCQuality = 200;
123
        }
123
        }
124
        // 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.
125
        // if (signal >= PPM_in[index] - 1 && signal <= PPM_in[index] + 1) {
125
        // 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.
126
          // In addition, if the signal is very close to 0, just set it to 0.
127
        if (signal >= -1 && signal <= 1) {
127
        if (signal >= -1 && signal <= 1) {
128
          tmp = 0;
128
          tmp = 0;
129
        //} else {
129
        //} else {
130
        //  tmp = PPM_in[index];
130
        //  tmp = PPM_in[index];
131
        //  }
131
        //  }
132
        } else
132
        } else
133
          tmp = signal;
133
          tmp = signal;
134
        PPM_in[index] = tmp; // update channel value
134
        PPM_in[index] = tmp; // update channel value
135
      }
135
      }
136
      index++; // next channel
136
      index++; // next channel
137
      // 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
138
      // 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
139
      // channels are usually available at the receiver anyway.
139
      // channels are usually available at the receiver anyway.
140
      // if(index == 5) J3HIGH; else J3LOW;
140
      // if(index == 5) J3HIGH; else J3LOW;
141
      // if(index == 6) J4HIGH; else J4LOW;
141
      // if(index == 6) J4HIGH; else J4LOW;
142
      // if(CPUType != ATMEGA644P) // not used as TXD1
142
      // if(CPUType != ATMEGA644P) // not used as TXD1
143
      //  {
143
      //  {
144
      //    if(index == 7) J5HIGH; else J5LOW;
144
      //    if(index == 7) J5HIGH; else J5LOW;
145
      //  }
145
      //  }
146
    }
146
    }
147
  }
147
  }
148
}
148
}
149
 
149
 
150
#define RCChannel(dimension) PPM_in[channelMap.channels[dimension]]
150
#define RCChannel(dimension) PPM_in[channelMap.channels[dimension]]
151
#define COMMAND_CHANNEL_VERTICAL CH_THROTTLE
151
#define COMMAND_CHANNEL_VERTICAL CH_THROTTLE
152
#define COMMAND_CHANNEL_HORIZONTAL CH_YAW
152
#define COMMAND_CHANNEL_HORIZONTAL CH_YAW
153
 
153
 
154
uint8_t getControlModeSwitch(void) {
154
uint8_t getControlModeSwitch(void) {
155
        int16_t channel = RCChannel(CH_MODESWITCH);
155
        int16_t channel = RCChannel(CH_MODESWITCH);
156
        uint8_t flightMode = channel < -TIME(0.17) ? FLIGHT_MODE_MANUAL : (channel > TIME(0.17) ? FLIGHT_MODE_ANGLES : FLIGHT_MODE_RATE);
156
        uint8_t flightMode = channel < -TIME(0.17) ? FLIGHT_MODE_MANUAL : (channel > TIME(0.17) ? FLIGHT_MODE_ANGLES : FLIGHT_MODE_RATE);
157
        return flightMode;
157
        return flightMode;
158
}
158
}
159
 
159
 
160
// Gyro calibration is performed as.... well mode switch with no throttle and no airspeed would be nice.
160
// Gyro calibration is performed as.... well mode switch with no throttle and no airspeed would be nice.
161
// Maybe simply: Very very low throttle.
161
// Maybe simply: Very very low throttle.
162
// Throttle xlow for COMMAND_TIMER: GYROCAL (once).
162
// Throttle xlow for COMMAND_TIMER: GYROCAL (once).
163
// mode switched: CHMOD
163
// mode switched: CHMOD
164
 
164
 
165
uint8_t RC_getCommand(void) {
165
uint8_t RC_getCommand(void) {
166
        uint8_t flightMode = getControlModeSwitch();
166
        uint8_t flightMode = getControlModeSwitch();
167
 
167
 
168
        if (lastFlightMode != flightMode) {
168
        if (lastFlightMode != flightMode) {
169
                lastFlightMode = flightMode;
169
                lastFlightMode = flightMode;
170
                lastRCCommand = COMMAND_CHMOD;
170
                lastRCCommand = COMMAND_CHMOD;
171
                return lastRCCommand;
171
                return lastRCCommand;
172
        }
172
        }
173
 
173
 
174
        int16_t channel = RCChannel(CH_THROTTLE);
174
        int16_t channel = RCChannel(CH_THROTTLE);
175
 
175
 
176
        if (channel <= -TIME(0.55)) {
176
        if (channel <= -TIME(0.55)) {
177
          lastRCCommand = COMMAND_GYROCAL;
177
          lastRCCommand = COMMAND_GYROCAL;
178
        } else {
178
        } else {
179
          lastRCCommand = COMMAND_NONE;
179
          lastRCCommand = COMMAND_NONE;
180
        }
180
        }
181
        return lastRCCommand;
181
        return lastRCCommand;
182
}
182
}
183
 
183
 
184
uint8_t RC_getArgument(void) {
184
uint8_t RC_getArgument(void) {
185
        return lastFlightMode;
185
        return lastFlightMode;
186
}
186
}
187
 
187
 
188
/*
188
/*
189
 * Get Pitch, Roll, Throttle, Yaw values
189
 * Get Pitch, Roll, Throttle, Yaw values
190
 */
190
 */
191
void RC_periodicTaskAndPRYT(int16_t* PRYT) {
191
void RC_periodicTaskAndPRYT(int16_t* PRYT) {
192
  if (RCQuality) {
192
  if (RCQuality) {
193
    RCQuality--;
193
    RCQuality--;
194
 
194
 
195
    debugOut.analog[20] = RCChannel(CH_ELEVATOR);
195
    debugOut.analog[20] = RCChannel(CH_ELEVATOR);
196
    debugOut.analog[21] = RCChannel(CH_AILERONS);
196
    debugOut.analog[21] = RCChannel(CH_AILERONS);
197
    debugOut.analog[22] = RCChannel(CH_RUDDER);
197
    debugOut.analog[22] = RCChannel(CH_RUDDER);
198
    debugOut.analog[23] = RCChannel(CH_THROTTLE);
198
    debugOut.analog[23] = RCChannel(CH_THROTTLE);
199
 
199
 
200
    PRYT[CONTROL_ELEVATOR]   = RCChannel(CH_ELEVATOR) / RC_SCALING;
200
    PRYT[CONTROL_ELEVATOR]   = RCChannel(CH_ELEVATOR);
201
    PRYT[CONTROL_AILERONS]   = RCChannel(CH_AILERONS) / RC_SCALING;
201
    PRYT[CONTROL_AILERONS]   = RCChannel(CH_AILERONS);
202
    PRYT[CONTROL_RUDDER]     = RCChannel(CH_RUDDER)   / RC_SCALING;
202
    PRYT[CONTROL_RUDDER]     = RCChannel(CH_RUDDER);
203
    PRYT[CONTROL_THROTTLE]   = RCChannel(CH_THROTTLE) / RC_SCALING;
203
    PRYT[CONTROL_THROTTLE]   = RCChannel(CH_THROTTLE);
204
  } // if RCQuality is no good, we just do nothing.
204
  } // if RCQuality is no good, we just do nothing.
205
}
205
}
206
 
206
 
207
/*
207
/*
208
 * Get other channel value
208
 * Get other channel value
209
 */
209
 */
210
int16_t RC_getVariable(uint8_t varNum) {
210
int16_t RC_getVariable(uint8_t varNum) {
211
  if (varNum < 4)
211
  if (varNum < 4)
212
    // 0th variable is 5th channel (1-based) etc.
212
    // 0th variable is 5th channel (1-based) etc.
213
    return (RCChannel(varNum + CH_POTS) >> 3) + channelMap.variableOffset;
213
    return (RCChannel(varNum + CH_POTS) >> 3) + channelMap.variableOffset;
214
  /*
214
  /*
215
   * Let's just say:
215
   * Let's just say:
216
   * The RC variable i is hardwired to channel i, i>=4
216
   * The RC variable i is hardwired to channel i, i>=4
217
   */
217
   */
218
  return (PPM_in[varNum] >> 3) + channelMap.variableOffset;
218
  return (PPM_in[varNum] >> 3) + channelMap.variableOffset;
219
}
219
}
220
 
220
 
221
uint8_t RC_getSignalQuality(void) {
221
uint8_t RC_getSignalQuality(void) {
222
  if (RCQuality >= 160)
222
  if (RCQuality >= 160)
223
    return SIGNAL_GOOD;
223
    return SIGNAL_GOOD;
224
  if (RCQuality >= 140)
224
  if (RCQuality >= 140)
225
    return SIGNAL_OK;
225
    return SIGNAL_OK;
226
  if (RCQuality >= 120)
226
  if (RCQuality >= 120)
227
    return SIGNAL_BAD;
227
    return SIGNAL_BAD;
228
  return SIGNAL_LOST;
228
  return SIGNAL_LOST;
229
}
229
}
230
 
230
 
231
void RC_calibrate(void) {
231
void RC_calibrate(void) {
232
  // Do nothing.
232
  // Do nothing.
233
}
233
}
234
 
234
 
235
int16_t RC_getZeroThrottle() {
235
int16_t RC_getZeroThrottle() {
236
        return TIME (-0.5);
236
        return TIME (-0.5);
237
}
237
}
238
 
238