Rev 2142 | Only display areas with differences | Ignore whitespace | Details | Blame | Last modification | View Log | RSS feed
Rev 2142 | Rev 2143 | ||
---|---|---|---|
1 | #include <util/delay.h> |
1 | #include <util/delay.h> |
2 | #include <stddef.h> |
2 | #include <stddef.h> |
3 | #include <string.h> |
3 | #include <string.h> |
4 | #include "configuration.h" |
4 | #include "configuration.h" |
5 | #include "controlMixer.h" |
5 | #include "controlMixer.h" |
6 | #include "rc.h" |
6 | #include "rc.h" |
7 | #include "output.h" |
7 | #include "output.h" |
8 | #include "flight.h" |
8 | #include "flight.h" |
9 | 9 | ||
10 | int16_t variables[VARIABLE_COUNT]; |
10 | int16_t variables[VARIABLE_COUNT]; |
11 | ParamSet_t staticParams; |
11 | ParamSet_t staticParams; |
12 | ChannelMap_t channelMap; |
12 | ChannelMap_t channelMap; |
13 | RCTrim_t rcTrim; |
13 | RCTrim_t rcTrim; |
14 | IMUConfig_t IMUConfig; |
14 | IMUConfig_t IMUConfig; |
15 | volatile DynamicParams_t dynamicParams; |
15 | volatile DynamicParams_t dynamicParams; |
16 | 16 | ||
17 | VersionInfo_t versionInfo; |
17 | VersionInfo_t versionInfo; |
18 | 18 | ||
19 | FlightMode_t currentFlightMode = FLIGHT_MODE_MANUAL; |
19 | FlightMode_t currentFlightMode = FLIGHT_MODE_MANUAL; |
20 | // updated by considering airspeed.. |
20 | // updated by considering airspeed.. |
21 | volatile uint16_t isFlying = 0; |
21 | volatile uint16_t isFlying = 0; |
22 | 22 | ||
23 | const MMXLATION XLATIONS[] = { |
23 | const MMXLATION XLATIONS[] = { |
24 | {offsetof(ParamSet_t, externalControl), offsetof(DynamicParams_t, externalControl),0,255}, |
24 | {offsetof(ParamSet_t, externalControl), offsetof(DynamicParams_t, externalControl),0,255}, |
25 | 25 | ||
26 | {offsetof(ParamSet_t, gyroPID[0].P), offsetof(DynamicParams_t, gyroPID[0].P),0,255}, |
26 | {offsetof(ParamSet_t, gyroPID[0].P), offsetof(DynamicParams_t, gyroPID[0].P),0,255}, |
27 | {offsetof(ParamSet_t, gyroPID[0].I), offsetof(DynamicParams_t, gyroPID[0].I),0,255}, |
27 | {offsetof(ParamSet_t, gyroPID[0].I), offsetof(DynamicParams_t, gyroPID[0].I),0,255}, |
28 | {offsetof(ParamSet_t, gyroPID[0].D), offsetof(DynamicParams_t, gyroPID[0].D),0,255}, |
28 | {offsetof(ParamSet_t, gyroPID[0].D), offsetof(DynamicParams_t, gyroPID[0].D),0,255}, |
29 | 29 | ||
30 | {offsetof(ParamSet_t, gyroPID[1].P), offsetof(DynamicParams_t, gyroPID[1].P),0,255}, |
30 | {offsetof(ParamSet_t, gyroPID[1].P), offsetof(DynamicParams_t, gyroPID[1].P),0,255}, |
31 | {offsetof(ParamSet_t, gyroPID[1].I), offsetof(DynamicParams_t, gyroPID[1].I),0,255}, |
31 | {offsetof(ParamSet_t, gyroPID[1].I), offsetof(DynamicParams_t, gyroPID[1].I),0,255}, |
32 | {offsetof(ParamSet_t, gyroPID[1].D), offsetof(DynamicParams_t, gyroPID[1].D),0,255}, |
32 | {offsetof(ParamSet_t, gyroPID[1].D), offsetof(DynamicParams_t, gyroPID[1].D),0,255}, |
33 | 33 | ||
34 | {offsetof(ParamSet_t, gyroPID[2].P), offsetof(DynamicParams_t, gyroPID[2].P),0,255}, |
34 | {offsetof(ParamSet_t, gyroPID[2].P), offsetof(DynamicParams_t, gyroPID[2].P),0,255}, |
35 | {offsetof(ParamSet_t, gyroPID[2].I), offsetof(DynamicParams_t, gyroPID[2].I),0,255}, |
35 | {offsetof(ParamSet_t, gyroPID[2].I), offsetof(DynamicParams_t, gyroPID[2].I),0,255}, |
36 | {offsetof(ParamSet_t, gyroPID[2].D), offsetof(DynamicParams_t, gyroPID[2].D),0,255}, |
36 | {offsetof(ParamSet_t, gyroPID[2].D), offsetof(DynamicParams_t, gyroPID[2].D),0,255}, |
37 | 37 | ||
38 | {offsetof(ParamSet_t, outputFlash[0].timing), offsetof(DynamicParams_t, output0Timing),0,255}, |
38 | {offsetof(ParamSet_t, outputFlash[0].timing), offsetof(DynamicParams_t, output0Timing),0,255}, |
39 | {offsetof(ParamSet_t, outputFlash[1].timing), offsetof(DynamicParams_t, output1Timing),0,255}, |
39 | {offsetof(ParamSet_t, outputFlash[1].timing), offsetof(DynamicParams_t, output1Timing),0,255}, |
40 | }; |
40 | }; |
41 | 41 | ||
42 | uint8_t configuration_applyVariableToParam(uint8_t src, uint8_t min, uint8_t max) { |
42 | uint8_t configuration_applyVariableToParam(uint8_t src, uint8_t min, uint8_t max) { |
43 | uint8_t result; |
43 | uint8_t result; |
44 | if (src>=(256-VARIABLE_COUNT)) result = variables[src-(256-VARIABLE_COUNT)]; |
44 | if (src>=(256-VARIABLE_COUNT)) result = variables[src-(256-VARIABLE_COUNT)]; |
45 | else result = src; |
45 | else result = src; |
46 | if (result < min) result = min; |
46 | if (result < min) result = min; |
47 | else if (result > max) result = max; |
47 | else if (result > max) result = max; |
48 | return result; |
48 | return result; |
49 | } |
49 | } |
50 | 50 | ||
51 | void configuration_applyVariablesToParams(void) { |
51 | void configuration_applyVariablesToParams(void) { |
52 | uint8_t i, src; |
52 | uint8_t i, src; |
53 | uint8_t* pointerToTgt; |
53 | uint8_t* pointerToTgt; |
54 | 54 | ||
55 | for(i=0; i<sizeof(XLATIONS)/sizeof(MMXLATION); i++) { |
55 | for(i=0; i<sizeof(XLATIONS)/sizeof(MMXLATION); i++) { |
56 | src = *((uint8_t*)(&staticParams) + XLATIONS[i].sourceIdx); |
56 | src = *((uint8_t*)(&staticParams) + XLATIONS[i].sourceIdx); |
57 | pointerToTgt = (uint8_t*)(&dynamicParams) + XLATIONS[i].targetIdx; |
57 | pointerToTgt = (uint8_t*)(&dynamicParams) + XLATIONS[i].targetIdx; |
58 | *pointerToTgt = configuration_applyVariableToParam(src, XLATIONS[i].min, XLATIONS[i].max); |
58 | *pointerToTgt = configuration_applyVariableToParam(src, XLATIONS[i].min, XLATIONS[i].max); |
59 | } |
59 | } |
60 | 60 | ||
61 | // User parameters are always variable. |
61 | // User parameters are always variable. |
62 | for (i=0; i<sizeof(staticParams.userParams); i++) { |
62 | for (i=0; i<sizeof(staticParams.userParams); i++) { |
63 | src = *((uint8_t*)(&staticParams) + offsetof(ParamSet_t, userParams) + i); |
63 | src = *((uint8_t*)(&staticParams) + offsetof(ParamSet_t, userParams) + i); |
64 | pointerToTgt = (uint8_t*)(&dynamicParams) + offsetof(DynamicParams_t, userParams) + i; |
64 | pointerToTgt = (uint8_t*)(&dynamicParams) + offsetof(DynamicParams_t, userParams) + i; |
65 | *pointerToTgt = configuration_applyVariableToParam(src, 0, 255); |
65 | *pointerToTgt = configuration_applyVariableToParam(src, 0, 255); |
66 | } |
66 | } |
67 | } |
67 | } |
68 | 68 | ||
69 | void configuration_setFlightParameters(uint8_t newFlightMode) { |
69 | void configuration_setFlightParameters(uint8_t newFlightMode) { |
70 | currentFlightMode = newFlightMode; |
70 | currentFlightMode = newFlightMode; |
71 | flight_updateFlightParametersToFlightMode(); |
71 | flight_updateFlightParametersToFlightMode(); |
72 | } |
72 | } |
73 | 73 | ||
74 | // Called after a change in configuration parameters, as a hook for modules to take over changes. |
74 | // Called after a change in configuration parameters, as a hook for modules to take over changes. |
75 | void configuration_paramSetDidChange(void) { |
75 | void configuration_paramSetDidChange(void) { |
76 | // This should be OK to do here as long as we don't change parameters during emergency flight. We don't. |
76 | // This should be OK to do here as long as we don't change parameters during emergency flight. We don't. |
77 | configuration_setFlightParameters(currentFlightMode); |
77 | configuration_setFlightParameters(currentFlightMode); |
78 | // Immediately load changes to output, and also signal the paramset change. |
78 | // Immediately load changes to output, and also signal the paramset change. |
79 | output_init(); |
79 | output_init(); |
80 | } |
80 | } |
81 | 81 | ||
82 | void setOtherDefaults(void) { |
82 | void setOtherDefaults(void) { |
83 | // Control |
83 | // Control |
84 | staticParams.externalControl = 0; |
84 | staticParams.externalControl = 0; |
85 | staticParams.IFactor = 52; |
85 | staticParams.IFactor = 52; |
86 | 86 | ||
87 | staticParams.airspeedCorrection = 1; |
87 | staticParams.airspeedCorrection = 1; |
88 | staticParams.isFlyingThreshold = 10; |
88 | staticParams.isFlyingThreshold = 4; |
- | 89 | ||
- | 90 | staticParams.minFlashAirspeed = 5; |
|
- | 91 | staticParams.maxFlashAirspeed = 9; |
|
89 | 92 | ||
90 | // Servos |
93 | // Servos |
91 | staticParams.servoCount = 6; |
94 | staticParams.servoCount = 6; |
92 | staticParams.servos[CONTROL_ELEVATOR].reverse = 0; |
95 | staticParams.servos[CONTROL_ELEVATOR].reverse = 0; |
93 | staticParams.servos[CONTROL_AILERONS].reverse = 0; // 1 for extra. |
96 | staticParams.servos[CONTROL_AILERONS].reverse = 0; // 1 for extra. |
94 | staticParams.servos[CONTROL_RUDDER].reverse = 0; |
97 | staticParams.servos[CONTROL_RUDDER].reverse = 0; |
95 | 98 | ||
96 | for (uint8_t i=0; i<4; i++) { |
99 | for (uint8_t i=0; i<4; i++) { |
97 | staticParams.servos[i].minValue = 80; |
100 | staticParams.servos[i].minValue = 80; |
98 | staticParams.servos[i].maxValue = 80; |
101 | staticParams.servos[i].maxValue = 80; |
99 | } |
102 | } |
100 | 103 | ||
101 | // Battery warning and emergency flight |
104 | // Battery warning and emergency flight |
102 | staticParams.batteryWarningVoltage = 101; // 3.7 each for 3S |
105 | staticParams.batteryWarningVoltage = 101; // 3.7 each for 3S |
103 | 106 | ||
104 | for (uint8_t i=0; i<3; i++) { |
107 | for (uint8_t i=0; i<3; i++) { |
105 | staticParams.gyroPID[i].P = 40; |
108 | staticParams.gyroPID[i].P = 40; |
106 | staticParams.gyroPID[i].I = 20; |
109 | staticParams.gyroPID[i].I = 20; |
107 | staticParams.gyroPID[i].D = 20; |
110 | staticParams.gyroPID[i].D = 20; |
108 | staticParams.gyroPID[i].iMax = 30; // 60 for extra. |
111 | staticParams.gyroPID[i].iMax = 30; // 60 for extra. |
109 | } |
112 | } |
110 | 113 | ||
111 | staticParams.stickIElevator = 40; |
114 | staticParams.stickIElevator = 40; |
112 | staticParams.stickIAilerons = 60; |
115 | staticParams.stickIAilerons = 60; |
113 | staticParams.stickIRudder = 20; |
116 | staticParams.stickIRudder = 20; |
114 | 117 | ||
115 | // Outputs |
118 | // Outputs |
116 | staticParams.outputFlash[0].bitmask = 1; //0b01011111; |
119 | staticParams.outputFlash[0].bitmask = 1; //0b01011111; |
117 | staticParams.outputFlash[0].timing = 15; |
120 | staticParams.outputFlash[0].timing = 15; |
118 | staticParams.outputFlash[1].bitmask = 3; //0b11110011; |
121 | staticParams.outputFlash[1].bitmask = 3; //0b11110011; |
119 | staticParams.outputFlash[1].timing = 15; |
122 | staticParams.outputFlash[1].timing = 15; |
120 | 123 | ||
121 | staticParams.outputDebugMask = 0; |
124 | staticParams.outputDebugMask = 0; |
122 | staticParams.outputFlags = OUTPUTFLAGS_FLASH_0_AT_BEEP | OUTPUTFLAGS_FLASH_1_AT_BEEP | OUTPUTFLAGS_USE_ONBOARD_LEDS; |
125 | staticParams.outputFlags = OUTPUTFLAGS_FLASH_0_AT_BEEP | OUTPUTFLAGS_FLASH_1_AT_BEEP | OUTPUTFLAGS_USE_ONBOARD_LEDS; |
123 | } |
126 | } |
124 | 127 | ||
125 | /***************************************************/ |
128 | /***************************************************/ |
126 | /* Default Values for parameter set 1 */ |
129 | /* Default Values for parameter set 1 */ |
127 | /***************************************************/ |
130 | /***************************************************/ |
128 | void paramSet_default(uint8_t setnumber) { |
131 | void paramSet_default(uint8_t setnumber) { |
129 | setOtherDefaults(); |
132 | setOtherDefaults(); |
130 | 133 | ||
131 | for (uint8_t i=0; i<8; i++) { |
134 | for (uint8_t i=0; i<8; i++) { |
132 | staticParams.userParams[i] = i; |
135 | staticParams.userParams[i] = i; |
133 | } |
136 | } |
134 | 137 | ||
135 | staticParams.bitConfig = |
138 | staticParams.bitConfig = |
136 | CFG_GYRO_SATURATION_PREVENTION; |
139 | CFG_GYRO_SATURATION_PREVENTION; |
137 | 140 | ||
138 | memcpy(staticParams.name, "Default\0", 6); |
141 | memcpy(staticParams.name, "Default\0", 6); |
139 | } |
142 | } |
140 | 143 | ||
141 | void IMUConfig_default(void) { |
144 | void IMUConfig_default(void) { |
142 | IMUConfig.gyroPIDFilterConstant = 10; |
145 | IMUConfig.gyroPIDFilterConstant = 10; |
143 | IMUConfig.gyroDFilterConstant = 1; |
146 | IMUConfig.gyroDFilterConstant = 1; |
144 | IMUConfig.rateTolerance = 120; |
147 | IMUConfig.rateTolerance = 120; |
145 | IMUConfig.gyroDWindowLength = 8; |
148 | IMUConfig.gyroDWindowLength = 8; |
146 | IMUConfig.gyroQuadrant = 4; |
149 | IMUConfig.gyroQuadrant = 4; |
147 | IMUConfig.imuReversedFlags = 0; |
150 | IMUConfig.imuReversedFlags = 0; |
148 | } |
151 | } |
149 | 152 | ||
150 | /***************************************************/ |
153 | /***************************************************/ |
151 | /* Default Values for R/C Channels */ |
154 | /* Default Values for R/C Channels */ |
152 | /***************************************************/ |
155 | /***************************************************/ |
153 | void channelMap_default(void) { |
156 | void channelMap_default(void) { |
154 | channelMap.RCPolarity = 1; |
157 | channelMap.RCPolarity = 1; |
155 | channelMap.HWTrim = 175; |
158 | channelMap.HWTrim = 175; |
156 | channelMap.variableOffset = 131; |
159 | channelMap.variableOffset = 131; |
157 | channelMap.channels[CH_ELEVATOR] = 1; |
160 | channelMap.channels[CH_ELEVATOR] = 1; |
158 | channelMap.channels[CH_AILERONS] = 0; |
161 | channelMap.channels[CH_AILERONS] = 0; |
159 | channelMap.channels[CH_THROTTLE] = 2; |
162 | channelMap.channels[CH_THROTTLE] = 2; |
160 | channelMap.channels[CH_RUDDER] = 3; |
163 | channelMap.channels[CH_RUDDER] = 3; |
161 | channelMap.channels[CH_POTS + 0] = 4; |
164 | channelMap.channels[CH_POTS + 0] = 4; |
162 | channelMap.channels[CH_POTS + 1] = 5; |
165 | channelMap.channels[CH_POTS + 1] = 5; |
163 | channelMap.channels[CH_POTS + 2] = 6; |
166 | channelMap.channels[CH_POTS + 2] = 6; |
164 | channelMap.channels[CH_POTS + 3] = 7; |
167 | channelMap.channels[CH_POTS + 3] = 7; |
165 | } |
168 | } |
166 | 169 |