Subversion Repositories FlightCtrl

Rev

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

Rev 2095 Rev 2113
1
#ifndef _CONFIGURATION_H
1
#ifndef _CONFIGURATION_H
2
#define _CONFIGURATION_H
2
#define _CONFIGURATION_H
3
 
3
 
4
#include <inttypes.h>
4
#include <inttypes.h>
5
#include <avr/io.h>
5
#include <avr/io.h>
6
 
6
 
7
#define MAX_CHANNELS 10
7
#define MAX_CHANNELS 10
8
#define MAX_MOTORS 12
8
#define MAX_MOTORS 12
9
 
9
 
10
// bitmask for VersionInfo_t.HardwareError[0]
10
// bitmask for VersionInfo_t.HardwareError[0]
11
#define FC_ERROR0_GYRO_PITCH    0x01
11
#define FC_ERROR0_GYRO_PITCH    0x01
12
#define FC_ERROR0_GYRO_ROLL     0x02
12
#define FC_ERROR0_GYRO_ROLL     0x02
13
#define FC_ERROR0_GYRO_YAW              0x04
13
#define FC_ERROR0_GYRO_YAW              0x04
14
#define FC_ERROR0_ACC_X                 0x08
14
#define FC_ERROR0_ACC_X                 0x08
15
#define FC_ERROR0_ACC_Y                 0x10
15
#define FC_ERROR0_ACC_Y                 0x10
16
#define FC_ERROR0_ACC_Z                 0x20
16
#define FC_ERROR0_ACC_Z                 0x20
17
#define FC_ERROR0_PRESSURE              0x40
17
#define FC_ERROR0_PRESSURE              0x40
18
#define FC_ERROR1_RES0                  0x80
18
#define FC_ERROR1_RES0                  0x80
19
// bitmask for VersionInfo_t.HardwareError[1]
19
// bitmask for VersionInfo_t.HardwareError[1]
20
#define FC_ERROR1_I2C                   0x01
20
#define FC_ERROR1_I2C                   0x01
21
#define FC_ERROR1_BL_MISSING    0x02
21
#define FC_ERROR1_BL_MISSING    0x02
22
#define FC_ERROR1_SPI_RX                0x04
22
#define FC_ERROR1_SPI_RX                0x04
23
#define FC_ERROR1_PPM                   0x08
23
#define FC_ERROR1_PPM                   0x08
24
#define FC_ERROR1_MIXER                 0x10
24
#define FC_ERROR1_MIXER                 0x10
25
#define FC_ERROR1_RES1                  0x20
25
#define FC_ERROR1_RES1                  0x20
26
#define FC_ERROR1_RES2                  0x40
26
#define FC_ERROR1_RES2                  0x40
27
#define FC_ERROR1_RES3                  0x80
27
#define FC_ERROR1_RES3                  0x80
28
 
28
 
29
typedef struct {
29
typedef struct {
30
        uint8_t SWMajor;
30
        uint8_t SWMajor;
31
        uint8_t SWMinor;
31
        uint8_t SWMinor;
32
        uint8_t protoMajor;
32
        uint8_t protoMajor;
33
        uint8_t protoMinor;
33
        uint8_t protoMinor;
34
        uint8_t SWPatch;
34
        uint8_t SWPatch;
35
        uint8_t hardwareErrors[5];
35
        uint8_t hardwareErrors[5];
36
}__attribute__((packed)) VersionInfo_t;
36
}__attribute__((packed)) VersionInfo_t;
37
 
37
 
38
extern VersionInfo_t versionInfo;
38
extern VersionInfo_t versionInfo;
39
 
39
 
40
typedef struct {
40
typedef struct {
41
  // IMU
-
 
42
  /*PMM*/uint8_t gyroP;
41
  /*PMM*/uint8_t gyroP;
43
  /* P */uint8_t gyroI;
42
  /* P */uint8_t gyroI;
44
  /* P */uint8_t gyroD;
43
  /* P */uint8_t gyroD;
45
  /* P */uint8_t compassControlHeading;
44
  /* P */uint8_t compassControlHeading;
46
 
45
 
47
  // Control
46
  // Control
48
  /* P */uint8_t externalControl;
47
  /* P */uint8_t externalControl;
49
  /* P */uint8_t dynamicStability;
48
  /* P */uint8_t dynamicStability;
50
 
49
 
51
  // Height control
50
  // Height control
52
  /*PMM*/uint8_t heightP;
51
  /*PMM*/uint8_t heightP;
53
  /* P */uint8_t heightI;
52
  /* P */uint8_t heightI;
54
  /*PMM*/uint8_t heightD;
53
  /*PMM*/uint8_t heightD;
55
  /* P */uint8_t heightSetting;
54
  /* P */uint8_t heightSetting;
56
 
55
 
57
  uint8_t attitudeControl;
56
  uint8_t attitudeControl;
58
 
57
 
59
  // Output and servo
58
  // Output and servo
60
  /*PMM*/uint8_t output0Timing;
59
  /*PMM*/uint8_t output0Timing;
61
  /*PMM*/uint8_t output1Timing;
60
  /*PMM*/uint8_t output1Timing;
62
 
61
 
63
  uint8_t servoManualControl[2];
62
  uint8_t servoManualControl[2];
64
 
63
 
65
  // Correction
64
  // Correction
66
  uint8_t levelCorrection[2];
65
  uint8_t levelCorrection[2];
67
 
66
 
68
  // Simple direct navigation
67
  // Simple direct navigation
69
  uint8_t naviMode;
68
  uint8_t naviMode;
70
 
69
 
71
  /* P */uint8_t userParams[8];
70
  /* P */uint8_t userParams[8];
72
} DynamicParams_t;
71
} DynamicParams_t;
73
 
72
 
74
extern volatile DynamicParams_t dynamicParams;
73
extern volatile DynamicParams_t dynamicParams;
75
 
74
 
76
typedef struct {
75
typedef struct {
77
  uint8_t sourceIdx, targetIdx;
76
  uint8_t sourceIdx, targetIdx;
78
  uint8_t min, max;
77
  uint8_t min, max;
79
} MMXLATION;
78
} MMXLATION;
80
 
79
 
81
/*
80
/*
82
typedef struct {
81
typedef struct {
83
  uint8_t sourceIdx, targetIdx;
82
  uint8_t sourceIdx, targetIdx;
84
} XLATION;
83
} XLATION;
85
*/
84
*/
86
 
85
 
87
typedef struct {
86
typedef struct {
88
  uint8_t channels[MAX_CHANNELS];
87
  uint8_t channels[MAX_CHANNELS];
89
} channelMap_t;
88
} channelMap_t;
90
extern channelMap_t channelMap;
89
extern channelMap_t channelMap;
91
 
90
 
92
typedef struct {
91
typedef struct {
93
  char name[12];
92
  char name[12];
94
  int8_t motor[MAX_MOTORS][4];
93
  int8_t motor[MAX_MOTORS][4];
95
}__attribute__((packed)) mixerMatrix_t;
94
}__attribute__((packed)) mixerMatrix_t;
96
extern mixerMatrix_t mixerMatrix;
95
extern mixerMatrix_t mixerMatrix;
97
 
96
 
98
typedef struct {
97
typedef struct {
99
  int16_t offsets[3];
98
  int16_t offsets[3];
100
} sensorOffset_t;
99
} sensorOffset_t;
101
 
100
 
102
typedef struct {
101
typedef struct {
103
  uint8_t manualControl;
102
  uint8_t manualControl;
104
  uint8_t stabilizationFactor;
103
  uint8_t stabilizationFactor;
105
  uint8_t minValue;
104
  uint8_t minValue;
106
  uint8_t maxValue;
105
  uint8_t maxValue;
107
  uint8_t flags;
106
  uint8_t flags;
108
} servo_t;
107
} servo_t;
109
 
108
 
110
#define SERVO_STABILIZATION_REVERSE 1
109
#define SERVO_STABILIZATION_REVERSE 1
111
 
110
 
112
typedef struct {
111
typedef struct {
113
  uint8_t bitmask;
112
  uint8_t bitmask;
114
  uint8_t timing;
113
  uint8_t timing;
115
} output_flash_t;
114
} output_flash_t;
116
 
115
 
117
typedef struct {
116
typedef struct {
118
  uint8_t gyroQuadrant;
117
  uint8_t gyroQuadrant;
119
  uint8_t accQuadrant;
118
  uint8_t accQuadrant;
120
  uint8_t imuReversedFlags;
119
  uint8_t imuReversedFlags;
121
 
120
 
122
  uint8_t gyroPIDFilterConstant;
121
  uint8_t gyroPIDFilterConstant;
123
  uint8_t gyroDWindowLength;
122
  uint8_t gyroDWindowLength;
124
  uint8_t gyroDFilterConstant;
123
  uint8_t gyroDFilterConstant;
125
  uint8_t accFilterConstant;
124
  uint8_t accFilterConstant;
126
 
125
 
127
  uint8_t zerothOrderCorrection;
126
  uint8_t zerothOrderCorrection;
128
  uint8_t rateTolerance;
127
  uint8_t rateTolerance;
129
 
128
 
130
  uint8_t gyroActivityDamping;
129
  uint8_t gyroActivityDamping;
131
  uint8_t driftCompDivider; // 1/k  (Koppel_ACC_Wirkung)
130
  uint8_t driftCompDivider; // 1/k  (Koppel_ACC_Wirkung)
132
  uint8_t driftCompLimit;   // limit for gyrodrift compensation
131
  uint8_t driftCompLimit;   // limit for gyrodrift compensation
133
} IMUConfig_t;
132
} IMUConfig_t;
134
 
133
 
135
extern IMUConfig_t IMUConfig;
134
extern IMUConfig_t IMUConfig;
136
 
135
 
137
// values above 250 representing poti1 to poti4
136
// values above 250 representing poti1 to poti4
138
typedef struct {
137
typedef struct {
139
  // Global bitflags
138
  // Global bitflags
140
  uint8_t bitConfig;  // see upper defines for bitcoding
139
  uint8_t bitConfig;  // see upper defines for bitcoding
141
 
140
 
142
  // uint8_t axisCoupling1; // Value: 0-250  Faktor, mit dem Yaw die Achsen Roll und Nick koppelt (NickRollMitkopplung)
141
  // uint8_t axisCoupling1; // Value: 0-250  Faktor, mit dem Yaw die Achsen Roll und Nick koppelt (NickRollMitkopplung)
143
  // uint8_t axisCoupling2; // Value: 0-250  Faktor, mit dem Nick und Roll verkoppelt werden
142
  // uint8_t axisCoupling2; // Value: 0-250  Faktor, mit dem Nick und Roll verkoppelt werden
144
  // uint8_t axisCouplingYawCorrection;// Value: 0-250  Faktor, mit dem Nick und Roll verkoppelt werden
143
  // uint8_t axisCouplingYawCorrection;// Value: 0-250  Faktor, mit dem Nick und Roll verkoppelt werden
145
 
144
 
146
  uint8_t levelCorrection[2];
145
  uint8_t levelCorrection[2];
147
 
146
 
148
  // Control
147
  // Control
149
  uint8_t gyroP;
148
  uint8_t gyroP;
150
  uint8_t gyroI;
149
  uint8_t gyroI;
151
  uint8_t gyroD;
150
  uint8_t gyroD;
152
 
151
 
153
  uint8_t attitudeControl;
152
  uint8_t attitudeControl;
154
 
153
 
155
  uint8_t stickP;
154
  uint8_t stickP;
156
  uint8_t stickD;
155
  uint8_t stickD;
157
  uint8_t stickYawP;
156
  uint8_t stickYawP;
158
  uint8_t stickThrottleD;
157
  uint8_t stickThrottleD;
159
 
158
 
160
  uint8_t minThrottle;
159
  uint8_t minThrottle;
161
  uint8_t maxThrottle;
160
  uint8_t maxThrottle;
162
 
161
 
163
  uint8_t externalControl; // for serial Control
162
  uint8_t externalControl; // for serial Control
164
  uint8_t motorSmoothing;
163
  uint8_t motorSmoothing;
165
  uint8_t dynamicStability; // PID limit for Attitude controller
164
  uint8_t dynamicStability; // PID limit for Attitude controller
166
 
165
 
167
  uint8_t IFactor;
166
  uint8_t IFactor;
168
  uint8_t yawIFactor;
167
  uint8_t yawIFactor;
169
 
168
 
170
  uint8_t compassMode;      // bitflag thing.
169
  uint8_t compassMode;      // bitflag thing.
171
  uint8_t compassYawCorrection;
170
  uint8_t compassYawCorrection;
172
  uint8_t compassBendingReturnSpeed;
171
  uint8_t compassBendingReturnSpeed;
173
  uint8_t compassP;
172
  uint8_t compassP;
174
 
173
 
175
  uint8_t batteryVoltageWarning;
174
  uint8_t batteryVoltageWarning;
176
  uint8_t emergencyThrottle;
175
  uint8_t emergencyThrottle;
177
  uint8_t emergencyFlightDuration;
176
  uint8_t emergencyFlightDuration;
178
 
177
 
179
  // Height Control
178
  // Height Control
180
  uint8_t airpressureFilterConstant;
179
  uint8_t airpressureFilterConstant;
181
  uint8_t airpressureWindowLength; // 0 means: Use filter.
180
  uint8_t airpressureWindowLength; // 0 means: Use filter.
182
  uint8_t airpressureDWindowLength; // values 1..5 are legal.
181
  uint8_t airpressureDWindowLength; // values 1..5 are legal.
183
  uint8_t airpressureAccZCorrection;
182
  uint8_t airpressureAccZCorrection;
184
 
183
 
185
  uint8_t heightP;
184
  uint8_t heightP;
186
  uint8_t heightI;
185
  uint8_t heightI;
187
  uint8_t heightD;
186
  uint8_t heightD;
188
 
187
 
189
  uint8_t heightSetting;
188
  uint8_t heightSetting;
190
  uint8_t heightControlMaxIntegralIn;
189
  uint8_t heightControlMaxIntegralIn;
191
  uint8_t heightControlMaxIntegralOut;
190
  uint8_t heightControlMaxIntegralOut;
192
  uint8_t heightControlMaxThrottleChange;
191
  uint8_t heightControlMaxThrottleChange;
193
 
192
 
194
  uint8_t heightControlTestOscPeriod;
193
  uint8_t heightControlTestOscPeriod;
195
  uint8_t heightControlTestOscAmplitude;
194
  uint8_t heightControlTestOscAmplitude;
196
 
195
 
197
  // Servos
196
  // Servos
198
  uint8_t servoCount;
197
  uint8_t servoCount;
199
  uint8_t servoManualMaxSpeed;
198
  uint8_t servoManualMaxSpeed;
200
  servo_t servoConfigurations[2]; // [PITCH, ROLL]
199
  servo_t servoConfigurations[2]; // [PITCH, ROLL]
201
 
200
 
202
  // Outputs
201
  // Outputs
203
  output_flash_t outputFlash[2];
202
  output_flash_t outputFlash[2];
204
  uint8_t outputDebugMask;
203
  uint8_t outputDebugMask;
205
  uint8_t outputFlags;
204
  uint8_t outputFlags;
206
 
205
 
207
 // Shared for both modes of navigation
206
 // Shared for both modes of navigation
208
  uint8_t naviMode;
207
  uint8_t naviMode;
209
  uint8_t naviStickThreshold;
208
  uint8_t naviStickThreshold;
210
  uint8_t naviStickLimit;
209
  uint8_t naviStickLimit;
211
  uint8_t GPSMininumSatellites;
210
  uint8_t GPSMininumSatellites;
212
  uint8_t naviP;
211
  uint8_t naviP;
213
  uint8_t naviI;
212
  uint8_t naviI;
214
  uint8_t naviD;
213
  uint8_t naviD;
215
 
214
 
216
  uint8_t naviTestOscPeriod;
215
  uint8_t naviTestOscPeriod;
217
  uint8_t naviTestOscAmplitude;
216
  uint8_t naviTestOscAmplitude;
218
 
217
 
219
  // User params
218
  // User params
220
  uint8_t userParams[8];
219
  uint8_t userParams[8];
221
 
220
 
222
  // Name
221
  // Name
223
  char name[12];
222
  char name[12];
224
} ParamSet_t;
223
} ParamSet_t;
225
 
224
 
226
extern ParamSet_t staticParams;
225
extern ParamSet_t staticParams;
227
 
226
 
228
// MKFlags
227
// MKFlags
229
#define MKFLAG_MOTOR_RUN        (1<<0)
228
#define MKFLAG_MOTOR_RUN        (1<<0)
230
//#define MKFLAG_FLY            (1<<1)
229
//#define MKFLAG_FLY            (1<<1)
231
#define MKFLAG_CALIBRATE        (1<<2)
230
#define MKFLAG_CALIBRATE        (1<<2)
232
#define MKFLAG_START            (1<<3)
231
#define MKFLAG_START            (1<<3)
233
#define MKFLAG_EMERGENCY_FLIGHT (1<<4)
232
#define MKFLAG_EMERGENCY_FLIGHT (1<<4)
234
#define MKFLAG_LOWBAT           (1<<5)
233
#define MKFLAG_LOWBAT           (1<<5)
235
#define MKFLAG_RESERVE2         (1<<6)
234
#define MKFLAG_RESERVE2         (1<<6)
236
#define MKFLAG_RESERVE3         (1<<7)
235
#define MKFLAG_RESERVE3         (1<<7)
237
 
236
 
238
// bit mask for staticParams.bitConfig
237
// bit mask for staticParams.bitConfig
239
#define CFG_SIMPLE_HEIGHT_CONTROL               (1<<0)
238
#define CFG_SIMPLE_HEIGHT_CONTROL               (1<<0)
240
#define CFG_SIMPLE_HC_HOLD_SWITCH       (1<<1)
239
#define CFG_SIMPLE_HC_HOLD_SWITCH       (1<<1)
241
#define CFG_HEADING_HOLD                        (1<<2)
240
#define CFG_HEADING_HOLD                        (1<<2)
242
#define CFG_COMPASS_ENABLED             (1<<3)
241
#define CFG_COMPASS_ENABLED             (1<<3)
243
#define CFG_UNUSED                              (1<<4)
242
#define CFG_UNUSED                              (1<<4)
244
#define CFG_NAVI_ENABLED                        (1<<5)
243
#define CFG_NAVI_ENABLED                        (1<<5)
245
#define CFG_AXIS_COUPLING_ENABLED       (1<<6)
244
#define CFG_AXIS_COUPLING_ENABLED       (1<<6)
246
#define CFG_GYRO_SATURATION_PREVENTION  (1<<7)
245
#define CFG_GYRO_SATURATION_PREVENTION  (1<<7)
247
 
246
 
248
#define IMU_REVERSE_GYRO_PR                             (1<<0)
247
#define IMU_REVERSE_GYRO_PR                             (1<<0)
249
#define IMU_REVERSE_GYRO_YAW                    (1<<1)
248
#define IMU_REVERSE_GYRO_YAW                    (1<<1)
250
#define IMU_REVERSE_ACC_XY                              (1<<2)
249
#define IMU_REVERSE_ACC_XY                              (1<<2)
251
#define IMU_REVERSE_ACC_Z                               (1<<3)
250
#define IMU_REVERSE_ACC_Z                               (1<<3)
252
 
251
 
253
#define ATMEGA644       0
252
#define ATMEGA644       0
254
#define ATMEGA644P      1
253
#define ATMEGA644P      1
255
#define SYSCLK F_CPU
254
#define SYSCLK F_CPU
256
 
255
 
257
// Not really a part of configuration, but LEDs and HW s test are the same.
256
// Not really a part of configuration, but LEDs and HW s test are the same.
258
#define RED_OFF   {if((boardRelease == 10) || (boardRelease == 20)) PORTB &=~(1<<PORTB0); else  PORTB |= (1<<PORTB0);}
257
#define RED_OFF   {if((boardRelease == 10) || (boardRelease == 20)) PORTB &=~(1<<PORTB0); else  PORTB |= (1<<PORTB0);}
259
#define RED_ON    {if((boardRelease == 10) || (boardRelease == 20)) PORTB |= (1<<PORTB0); else  PORTB &=~(1<<PORTB0);}
258
#define RED_ON    {if((boardRelease == 10) || (boardRelease == 20)) PORTB |= (1<<PORTB0); else  PORTB &=~(1<<PORTB0);}
260
#define RED_FLASH PORTB ^= (1<<PORTB0)
259
#define RED_FLASH PORTB ^= (1<<PORTB0)
261
#define GRN_OFF   {if(boardRelease  < 12) PORTB &=~(1<<PORTB1); else PORTB |= (1<<PORTB1);}
260
#define GRN_OFF   {if(boardRelease  < 12) PORTB &=~(1<<PORTB1); else PORTB |= (1<<PORTB1);}
262
#define GRN_ON    {if(boardRelease  < 12) PORTB |= (1<<PORTB1); else PORTB &=~(1<<PORTB1);}
261
#define GRN_ON    {if(boardRelease  < 12) PORTB |= (1<<PORTB1); else PORTB &=~(1<<PORTB1);}
263
#define GRN_FLASH PORTB ^= (1<<PORTB1)
262
#define GRN_FLASH PORTB ^= (1<<PORTB1)
264
 
263
 
265
// Mixer table
264
// Mixer table
266
#define MIX_THROTTLE    0
265
#define MIX_THROTTLE    0
267
#define MIX_PITCH       1
266
#define MIX_PITCH       1
268
#define MIX_ROLL        2
267
#define MIX_ROLL        2
269
#define MIX_YAW         3
268
#define MIX_YAW         3
270
 
269
 
271
#define VARIABLE_COUNT 8
270
#define VARIABLE_COUNT 8
272
 
271
 
273
extern volatile uint8_t MKFlags;
272
extern volatile uint8_t MKFlags;
274
extern uint8_t requiredMotors;
273
extern uint8_t requiredMotors;
275
extern int16_t variables[VARIABLE_COUNT]; // The "Poti"s.
274
extern int16_t variables[VARIABLE_COUNT]; // The "Poti"s.
276
extern uint8_t boardRelease;
275
extern uint8_t boardRelease;
277
extern uint8_t CPUType;
276
extern uint8_t CPUType;
278
 
277
 
279
extern volatile uint8_t MKFlags;
278
extern volatile uint8_t MKFlags;
280
extern uint16_t isFlying;
279
extern uint16_t isFlying;
281
 
280
 
282
void IMUConfig_default(void);
281
void IMUConfig_default(void);
283
void channelMap_default(void);
282
void channelMap_default(void);
284
void paramSet_default(uint8_t setnumber);
283
void paramSet_default(uint8_t setnumber);
285
void mixerMatrix_default(void);
284
void mixerMatrix_default(void);
286
 
285
 
287
void configuration_setNormalFlightParameters(void);
286
void configuration_setNormalFlightParameters(void);
288
void configuration_setFailsafeFlightParameters(void);
287
void configuration_setFailsafeFlightParameters(void);
289
void configuration_applyVariablesToParams(void);
288
void configuration_applyVariablesToParams(void);
290
 
289
 
291
void setCPUType(void);
290
void setCPUType(void);
292
void setBoardRelease(void);
291
void setBoardRelease(void);
293
 
292
 
294
// Called after a change in configuration parameters, as a hook for modules to take over changes.
293
// Called after a change in configuration parameters, as a hook for modules to take over changes.
295
void configuration_paramSetDidChange(void);
294
void configuration_paramSetDidChange(void);
296
#endif // _CONFIGURATION_H
295
#endif // _CONFIGURATION_H
297
 
296