Rev 2015 | Rev 2018 | Go to most recent revision | Only display areas with differences | Ignore whitespace | Details | Blame | Last modification | View Log | RSS feed
Rev 2015 | Rev 2017 | ||
---|---|---|---|
1 | // ++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++ |
1 | // ++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++ |
2 | // + Copyright (c) 04.2007 Holger Buss |
2 | // + Copyright (c) 04.2007 Holger Buss |
3 | // + Nur für den privaten Gebrauch |
3 | // + Nur für den privaten Gebrauch |
4 | // + www.MikroKopter.com |
4 | // + www.MikroKopter.com |
5 | // ++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++ |
5 | // ++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++ |
6 | // + Es gilt für das gesamte Projekt (Hardware, Software, Binärfiles, Sourcecode und Dokumentation), |
6 | // + Es gilt für das gesamte Projekt (Hardware, Software, Binärfiles, Sourcecode und Dokumentation), |
7 | // + dass eine Nutzung (auch auszugsweise) nur f�r den privaten und nicht-kommerziellen Gebrauch zulässig ist. |
7 | // + dass eine Nutzung (auch auszugsweise) nur für den privaten und nicht-kommerziellen Gebrauch zulässig ist. |
8 | // + Sollten direkte oder indirekte kommerzielle Absichten verfolgt werden, ist mit uns (info@mikrokopter.de) Kontakt |
8 | // + Sollten direkte oder indirekte kommerzielle Absichten verfolgt werden, ist mit uns (info@mikrokopter.de) Kontakt |
9 | // + bzgl. der Nutzungsbedingungen aufzunehmen. |
9 | // + bzgl. der Nutzungsbedingungen aufzunehmen. |
10 | // + Eine kommerzielle Nutzung ist z.B.Verkauf von MikroKoptern, Bestückung und Verkauf von Platinen oder Bausätzen, |
10 | // + Eine kommerzielle Nutzung ist z.B.Verkauf von MikroKoptern, Bestückung und Verkauf von Platinen oder Bausätzen, |
11 | // + Verkauf von Luftbildaufnahmen, usw. |
11 | // + Verkauf von Luftbildaufnahmen, usw. |
12 | // ++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++ |
12 | // ++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++ |
13 | // + Werden Teile des Quellcodes (mit oder ohne Modifikation) weiterverwendet oder veröffentlicht, |
13 | // + Werden Teile des Quellcodes (mit oder ohne Modifikation) weiterverwendet oder veröffentlicht, |
14 | // + unterliegen sie auch diesen Nutzungsbedingungen und diese Nutzungsbedingungen incl. Copyright müssen dann beiliegen |
14 | // + unterliegen sie auch diesen Nutzungsbedingungen und diese Nutzungsbedingungen incl. Copyright müssen dann beiliegen |
15 | // ++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++ |
15 | // ++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++ |
16 | // + Sollte die Software (auch auszugesweise) oder sonstige Informationen des MikroKopter-Projekts |
16 | // + Sollte die Software (auch auszugesweise) oder sonstige Informationen des MikroKopter-Projekts |
17 | // + auf anderen Webseiten oder Medien veröffentlicht werden, muss unsere Webseite "http://www.mikrokopter.de" |
17 | // + auf anderen Webseiten oder Medien veröffentlicht werden, muss unsere Webseite "http://www.mikrokopter.de" |
18 | // + eindeutig als Ursprung verlinkt und genannt werden |
18 | // + eindeutig als Ursprung verlinkt und genannt werden |
19 | // ++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++ |
19 | // ++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++ |
20 | // + Keine Gewähr auf Fehlerfreiheit, Vollständigkeit oder Funktion |
20 | // + Keine Gewähr auf Fehlerfreiheit, Vollständigkeit oder Funktion |
21 | // + Benutzung auf eigene Gefahr |
21 | // + Benutzung auf eigene Gefahr |
22 | // + Wir übernehmen keinerlei Haftung für direkte oder indirekte Personen- oder Sachschäden |
22 | // + Wir übernehmen keinerlei Haftung für direkte oder indirekte Personen- oder Sachschäden |
23 | // ++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++ |
23 | // ++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++ |
24 | // + Die Portierung der Software (oder Teile davon) auf andere Systeme (ausser der Hardware von www.mikrokopter.de) ist nur |
24 | // + Die Portierung der Software (oder Teile davon) auf andere Systeme (ausser der Hardware von www.mikrokopter.de) ist nur |
25 | // + mit unserer Zustimmung zulässig |
25 | // + mit unserer Zustimmung zulässig |
26 | // ++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++ |
26 | // ++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++ |
27 | // + Die Funktion printf_P() unterliegt ihrer eigenen Lizenz und ist hiervon nicht betroffen |
27 | // + Die Funktion printf_P() unterliegt ihrer eigenen Lizenz und ist hiervon nicht betroffen |
28 | // ++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++ |
28 | // ++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++ |
29 | // + Redistributions of source code (with or without modifications) must retain the above copyright notice, |
29 | // + Redistributions of source code (with or without modifications) must retain the above copyright notice, |
30 | // + this list of conditions and the following disclaimer. |
30 | // + this list of conditions and the following disclaimer. |
31 | // + * Neither the name of the copyright holders nor the names of contributors may be used to endorse or promote products derived |
31 | // + * Neither the name of the copyright holders nor the names of contributors may be used to endorse or promote products derived |
32 | // + from this software without specific prior written permission. |
32 | // + from this software without specific prior written permission. |
33 | // + * The use of this project (hardware, software, binary files, sources and documentation) is only permittet |
33 | // + * The use of this project (hardware, software, binary files, sources and documentation) is only permittet |
34 | // + for non-commercial use (directly or indirectly) |
34 | // + for non-commercial use (directly or indirectly) |
35 | // + Commercial use (for example: selling of MikroKopters, selling of PCBs, assembly, ...) is only permitted |
35 | // + Commercial use (for example: selling of MikroKopters, selling of PCBs, assembly, ...) is only permitted |
36 | // + with our written permission |
36 | // + with our written permission |
37 | // + * If sources or documentations are redistributet on other webpages, out webpage (http://www.MikroKopter.de) must be |
37 | // + * If sources or documentations are redistributet on other webpages, out webpage (http://www.MikroKopter.de) must be |
38 | // + clearly linked as origin |
38 | // + clearly linked as origin |
39 | // + * porting to systems other than hardware from www.mikrokopter.de is not allowed |
39 | // + * porting to systems other than hardware from www.mikrokopter.de is not allowed |
40 | // + THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" |
40 | // + THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" |
41 | // + AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE |
41 | // + AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE |
42 | // + IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE |
42 | // + IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE |
43 | // + ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE |
43 | // + ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE |
44 | // + LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR |
44 | // + LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR |
45 | // + CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF |
45 | // + CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF |
46 | // + SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS |
46 | // + SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS |
47 | // + INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN |
47 | // + INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN |
48 | // + CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) |
48 | // + CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) |
49 | // + ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE |
49 | // + ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE |
50 | // + POSSIBILITY OF SUCH DAMAGE. |
50 | // + POSSIBILITY OF SUCH DAMAGE. |
51 | // ++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++ |
51 | // ++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++ |
52 | #include <avr/io.h> |
52 | #include <avr/io.h> |
53 | #include <avr/interrupt.h> |
53 | #include <avr/interrupt.h> |
54 | #include <avr/pgmspace.h> |
54 | #include <avr/pgmspace.h> |
55 | 55 | ||
56 | #include "analog.h" |
56 | #include "analog.h" |
57 | #include "attitude.h" |
57 | #include "attitude.h" |
58 | #include "sensors.h" |
58 | #include "sensors.h" |
59 | #include "printf_P.h" |
59 | #include "printf_P.h" |
60 | 60 | ||
61 | // for Delay functions |
61 | // for Delay functions |
62 | #include "timer0.h" |
62 | #include "timer0.h" |
63 | 63 | ||
64 | // For debugOut |
64 | // For debugOut |
65 | #include "uart0.h" |
65 | #include "uart0.h" |
66 | 66 | ||
67 | // For reading and writing acc. meter offsets. |
67 | // For reading and writing acc. meter offsets. |
68 | #include "eeprom.h" |
68 | #include "eeprom.h" |
69 | 69 | ||
70 | // For debugOut.digital |
70 | // For debugOut.digital |
71 | #include "output.h" |
71 | #include "output.h" |
72 | 72 | ||
73 | // set ADC enable & ADC Start Conversion & ADC Interrupt Enable bit |
73 | // set ADC enable & ADC Start Conversion & ADC Interrupt Enable bit |
74 | #define startADC() (ADCSRA |= (1<<ADEN)|(1<<ADSC)|(1<<ADIE)) |
74 | #define startADC() (ADCSRA |= (1<<ADEN)|(1<<ADSC)|(1<<ADIE)) |
75 | 75 | ||
76 | const char* recal = ", recalibration needed."; |
76 | const char* recal = ", recalibration needed."; |
77 | 77 | ||
78 | /* |
78 | /* |
79 | * For each A/D conversion cycle, each analog channel is sampled a number of times |
79 | * For each A/D conversion cycle, each analog channel is sampled a number of times |
80 | * (see array channelsForStates), and the results for each channel are summed. |
80 | * (see array channelsForStates), and the results for each channel are summed. |
81 | * Here are those for the gyros and the acc. meters. They are not zero-offset. |
81 | * Here are those for the gyros and the acc. meters. They are not zero-offset. |
82 | * They are exported in the analog.h file - but please do not use them! The only |
82 | * They are exported in the analog.h file - but please do not use them! The only |
83 | * reason for the export is that the ENC-03_FC1.3 modules needs them for calibrating |
83 | * reason for the export is that the ENC-03_FC1.3 modules needs them for calibrating |
84 | * the offsets with the DAC. |
84 | * the offsets with the DAC. |
85 | */ |
85 | */ |
86 | volatile uint16_t sensorInputs[8]; |
86 | volatile uint16_t sensorInputs[8]; |
87 | int16_t acc[3]; |
87 | int16_t acc[3]; |
88 | int16_t filteredAcc[3] = { 0,0,0 }; |
88 | int16_t filteredAcc[3] = { 0,0,0 }; |
89 | 89 | ||
90 | /* |
90 | /* |
91 | * These 4 exported variables are zero-offset. The "PID" ones are used |
91 | * These 4 exported variables are zero-offset. The "PID" ones are used |
92 | * in the attitude control as rotation rates. The "ATT" ones are for |
92 | * in the attitude control as rotation rates. The "ATT" ones are for |
93 | * integration to angles. |
93 | * integration to angles. |
94 | */ |
94 | */ |
95 | int16_t gyro_PID[2]; |
95 | int16_t gyro_PID[2]; |
96 | int16_t gyro_ATT[2]; |
96 | int16_t gyro_ATT[2]; |
97 | int16_t gyroD[2]; |
97 | int16_t gyroD[2]; |
98 | int16_t yawGyro; |
98 | int16_t yawGyro; |
99 | 99 | ||
100 | /* |
100 | /* |
101 | * Offset values. These are the raw gyro and acc. meter sums when the copter is |
101 | * Offset values. These are the raw gyro and acc. meter sums when the copter is |
102 | * standing still. They are used for adjusting the gyro and acc. meter values |
102 | * standing still. They are used for adjusting the gyro and acc. meter values |
103 | * to be centered on zero. |
103 | * to be centered on zero. |
104 | */ |
104 | */ |
105 | 105 | ||
106 | sensorOffset_t gyroOffset; |
106 | sensorOffset_t gyroOffset; |
107 | sensorOffset_t accOffset; |
107 | sensorOffset_t accOffset; |
108 | sensorOffset_t gyroAmplifierOffset; |
108 | sensorOffset_t gyroAmplifierOffset; |
109 | 109 | ||
110 | /* |
110 | /* |
111 | * In the MK coordinate system, nose-down is positive and left-roll is positive. |
111 | * In the MK coordinate system, nose-down is positive and left-roll is positive. |
112 | * If a sensor is used in an orientation where one but not both of the axes has |
112 | * If a sensor is used in an orientation where one but not both of the axes has |
113 | * an opposite sign, PR_ORIENTATION_REVERSED is set to 1 (true). |
113 | * an opposite sign, PR_ORIENTATION_REVERSED is set to 1 (true). |
114 | * Transform: |
114 | * Transform: |
115 | * pitch <- pp*pitch + pr*roll |
115 | * pitch <- pp*pitch + pr*roll |
116 | * roll <- rp*pitch + rr*roll |
116 | * roll <- rp*pitch + rr*roll |
117 | * Not reversed, GYRO_QUADRANT: |
117 | * Not reversed, GYRO_QUADRANT: |
118 | * 0: pp=1, pr=0, rp=0, rr=1 // 0 degrees |
118 | * 0: pp=1, pr=0, rp=0, rr=1 // 0 degrees |
119 | * 1: pp=1, pr=-1,rp=1, rr=1 // +45 degrees |
119 | * 1: pp=1, pr=-1,rp=1, rr=1 // +45 degrees |
120 | * 2: pp=0, pr=-1,rp=1, rr=0 // +90 degrees |
120 | * 2: pp=0, pr=-1,rp=1, rr=0 // +90 degrees |
121 | * 3: pp=-1,pr=-1,rp=1, rr=1 // +135 degrees |
121 | * 3: pp=-1,pr=-1,rp=1, rr=1 // +135 degrees |
122 | * 4: pp=-1,pr=0, rp=0, rr=-1 // +180 degrees |
122 | * 4: pp=-1,pr=0, rp=0, rr=-1 // +180 degrees |
123 | * 5: pp=-1,pr=1, rp=-1,rr=-1 // +225 degrees |
123 | * 5: pp=-1,pr=1, rp=-1,rr=-1 // +225 degrees |
124 | * 6: pp=0, pr=1, rp=-1,rr=0 // +270 degrees |
124 | * 6: pp=0, pr=1, rp=-1,rr=0 // +270 degrees |
125 | * 7: pp=1, pr=1, rp=-1,rr=1 // +315 degrees |
125 | * 7: pp=1, pr=1, rp=-1,rr=1 // +315 degrees |
126 | * Reversed, GYRO_QUADRANT: |
126 | * Reversed, GYRO_QUADRANT: |
127 | * 0: pp=-1,pr=0, rp=0, rr=1 // 0 degrees with pitch reversed |
127 | * 0: pp=-1,pr=0, rp=0, rr=1 // 0 degrees with pitch reversed |
128 | * 1: pp=-1,pr=-1,rp=-1,rr=1 // +45 degrees with pitch reversed |
128 | * 1: pp=-1,pr=-1,rp=-1,rr=1 // +45 degrees with pitch reversed |
129 | * 2: pp=0, pr=-1,rp=-1,rr=0 // +90 degrees with pitch reversed |
129 | * 2: pp=0, pr=-1,rp=-1,rr=0 // +90 degrees with pitch reversed |
130 | * 3: pp=1, pr=-1,rp=-1,rr=1 // +135 degrees with pitch reversed |
130 | * 3: pp=1, pr=-1,rp=-1,rr=1 // +135 degrees with pitch reversed |
131 | * 4: pp=1, pr=0, rp=0, rr=-1 // +180 degrees with pitch reversed |
131 | * 4: pp=1, pr=0, rp=0, rr=-1 // +180 degrees with pitch reversed |
132 | * 5: pp=1, pr=1, rp=1, rr=-1 // +225 degrees with pitch reversed |
132 | * 5: pp=1, pr=1, rp=1, rr=-1 // +225 degrees with pitch reversed |
133 | * 6: pp=0, pr=1, rp=1, rr=0 // +270 degrees with pitch reversed |
133 | * 6: pp=0, pr=1, rp=1, rr=0 // +270 degrees with pitch reversed |
134 | * 7: pp=-1,pr=1, rp=1, rr=1 // +315 degrees with pitch reversed |
134 | * 7: pp=-1,pr=1, rp=1, rr=1 // +315 degrees with pitch reversed |
135 | */ |
135 | */ |
- | 136 | ||
- | 137 | void rotate(int16_t* result, uint8_t quadrant, uint8_t reverse) {} |
|
- | 138 | ||
136 | 139 | /* |
|
137 | void rotate(int16_t* result, uint8_t quadrant, uint8_t reverse) { |
140 | void rotate(int16_t* result, uint8_t quadrant, uint8_t reverse) { |
138 | static const int8_t rotationTab[] = {1,1,0,-1,-1,-1,0,1}; |
141 | static const int8_t rotationTab[] = {1,1,0,-1,-1,-1,0,1}; |
139 | // Pitch to Pitch part |
142 | // Pitch to Pitch part |
140 | int8_t xx = (reverse & 1) ? rotationTab[(quadrant+4)%8] : rotationTab[quadrant]; |
143 | int8_t xx = (reverse & 1) ? rotationTab[(quadrant+4)%8] : rotationTab[quadrant]; |
141 | // Roll to Pitch part |
144 | // Roll to Pitch part |
142 | int8_t xy = rotationTab[(quadrant+2)%8]; |
145 | int8_t xy = rotationTab[(quadrant+2)%8]; |
143 | // Pitch to Roll part |
146 | // Pitch to Roll part |
144 | int8_t yx = reverse ? rotationTab[(quadrant+2)%8] : rotationTab[(quadrant+6)%8]; |
147 | int8_t yx = reverse ? rotationTab[(quadrant+2)%8] : rotationTab[(quadrant+6)%8]; |
145 | // Roll to Roll part |
148 | // Roll to Roll part |
146 | int8_t yy = rotationTab[quadrant]; |
149 | int8_t yy = rotationTab[quadrant]; |
147 | 150 | ||
148 | int16_t xIn = result[0]; |
151 | int16_t xIn = result[0]; |
149 | result[0] = xx*result[0] + xy*result[1]; |
152 | result[0] = xx*result[0] + xy*result[1]; |
150 | result[1] = yx*xIn + yy*result[1]; |
153 | result[1] = yx*xIn + yy*result[1]; |
151 | 154 | |
|
152 | if (quadrant & 1) { |
155 | if (quadrant & 1) { |
153 | // A rotation was used above, where the factors were too large by sqrt(2). |
156 | // A rotation was used above, where the factors were too large by sqrt(2). |
154 | // So, we multiply by 2^n/sqt(2) and right shift n bits, as to divide by sqrt(2). |
157 | // So, we multiply by 2^n/sqt(2) and right shift n bits, as to divide by sqrt(2). |
155 | // A suitable value for n: Sample is 11 bits. After transformation it is the sum |
158 | // A suitable value for n: Sample is 11 bits. After transformation it is the sum |
156 | // of 2 11 bit numbers, so 12 bits. We have 4 bits left... |
159 | // of 2 11 bit numbers, so 12 bits. We have 4 bits left... |
157 | result[0] = (result[0]*11) >> 4; |
160 | result[0] = (result[0]*11) >> 4; |
158 | result[1] = (result[1]*11) >> 4; |
161 | result[1] = (result[1]*11) >> 4; |
159 | } |
162 | } |
160 | } |
163 | } |
161 | 164 | */ |
|
162 | /* |
165 | /* |
163 | * Air pressure |
166 | * Air pressure |
164 | */ |
167 | */ |
165 | volatile uint8_t rangewidth = 105; |
168 | volatile uint8_t rangewidth = 105; |
166 | 169 | ||
167 | // Direct from sensor, irrespective of range. |
170 | // Direct from sensor, irrespective of range. |
168 | // volatile uint16_t rawAirPressure; |
171 | // volatile uint16_t rawAirPressure; |
169 | 172 | ||
170 | // Value of 2 samples, with range. |
173 | // Value of 2 samples, with range. |
171 | uint16_t simpleAirPressure; |
174 | uint16_t simpleAirPressure; |
172 | 175 | ||
173 | // Value of AIRPRESSURE_SUMMATION_FACTOR samples, with range, filtered. |
176 | // Value of AIRPRESSURE_SUMMATION_FACTOR samples, with range, filtered. |
174 | int32_t filteredAirPressure; |
177 | int32_t filteredAirPressure; |
175 | 178 | ||
176 | // Partial sum of AIRPRESSURE_SUMMATION_FACTOR samples. |
179 | // Partial sum of AIRPRESSURE_SUMMATION_FACTOR samples. |
177 | int32_t airPressureSum; |
180 | int32_t airPressureSum; |
178 | 181 | ||
179 | // The number of samples summed into airPressureSum so far. |
182 | // The number of samples summed into airPressureSum so far. |
180 | uint8_t pressureMeasurementCount; |
183 | uint8_t pressureMeasurementCount; |
181 | 184 | ||
182 | /* |
185 | /* |
183 | * Battery voltage, in units of: 1k/11k / 3V * 1024 = 31.03 per volt. |
186 | * Battery voltage, in units of: 1k/11k / 3V * 1024 = 31.03 per volt. |
184 | * That is divided by 3 below, for a final 10.34 per volt. |
187 | * That is divided by 3 below, for a final 10.34 per volt. |
185 | * So the initial value of 100 is for 9.7 volts. |
188 | * So the initial value of 100 is for 9.7 volts. |
186 | */ |
189 | */ |
187 | int16_t UBat = 100; |
190 | int16_t UBat = 100; |
188 | 191 | ||
189 | /* |
192 | /* |
190 | * Control and status. |
193 | * Control and status. |
191 | */ |
194 | */ |
192 | volatile uint16_t ADCycleCount = 0; |
195 | volatile uint16_t ADCycleCount = 0; |
193 | volatile uint8_t analogDataReady = 1; |
196 | volatile uint8_t analogDataReady = 1; |
194 | 197 | ||
195 | /* |
198 | /* |
196 | * Experiment: Measuring vibration-induced sensor noise. |
199 | * Experiment: Measuring vibration-induced sensor noise. |
197 | */ |
200 | */ |
198 | uint16_t gyroNoisePeak[3]; |
201 | uint16_t gyroNoisePeak[3]; |
199 | uint16_t accNoisePeak[3]; |
202 | uint16_t accNoisePeak[3]; |
200 | 203 | ||
201 | volatile uint8_t adState; |
204 | volatile uint8_t adState; |
202 | volatile uint8_t adChannel; |
205 | volatile uint8_t adChannel; |
203 | 206 | ||
204 | // ADC channels |
207 | // ADC channels |
205 | #define AD_GYRO_YAW 0 |
208 | #define AD_GYRO_YAW 0 |
206 | #define AD_GYRO_ROLL 1 |
209 | #define AD_GYRO_ROLL 1 |
207 | #define AD_GYRO_PITCH 2 |
210 | #define AD_GYRO_PITCH 2 |
208 | #define AD_AIRPRESSURE 3 |
211 | #define AD_AIRPRESSURE 3 |
209 | #define AD_UBAT 4 |
212 | #define AD_UBAT 4 |
210 | #define AD_ACC_Z 5 |
213 | #define AD_ACC_Z 5 |
211 | #define AD_ACC_ROLL 6 |
214 | #define AD_ACC_ROLL 6 |
212 | #define AD_ACC_PITCH 7 |
215 | #define AD_ACC_PITCH 7 |
213 | 216 | ||
214 | /* |
217 | /* |
215 | * Table of AD converter inputs for each state. |
218 | * Table of AD converter inputs for each state. |
216 | * The number of samples summed for each channel is equal to |
219 | * The number of samples summed for each channel is equal to |
217 | * the number of times the channel appears in the array. |
220 | * the number of times the channel appears in the array. |
218 | * The max. number of samples that can be taken in 2 ms is: |
221 | * The max. number of samples that can be taken in 2 ms is: |
219 | * 20e6 / 128 / 13 / (1/2e-3) = 24. Since the main control |
222 | * 20e6 / 128 / 13 / (1/2e-3) = 24. Since the main control |
220 | * loop needs a little time between reading AD values and |
223 | * loop needs a little time between reading AD values and |
221 | * re-enabling ADC, the real limit is (how much?) lower. |
224 | * re-enabling ADC, the real limit is (how much?) lower. |
222 | * The acc. sensor is sampled even if not used - or installed |
225 | * The acc. sensor is sampled even if not used - or installed |
223 | * at all. The cost is not significant. |
226 | * at all. The cost is not significant. |
224 | */ |
227 | */ |
225 | 228 | ||
226 | const uint8_t channelsForStates[] PROGMEM = { |
229 | const uint8_t channelsForStates[] PROGMEM = { |
227 | AD_GYRO_PITCH, AD_GYRO_ROLL, AD_GYRO_YAW, |
230 | AD_GYRO_PITCH, AD_GYRO_ROLL, AD_GYRO_YAW, |
228 | AD_ACC_PITCH, AD_ACC_ROLL, AD_AIRPRESSURE, |
231 | AD_ACC_PITCH, AD_ACC_ROLL, AD_AIRPRESSURE, |
229 | 232 | ||
230 | AD_GYRO_PITCH, AD_GYRO_ROLL, AD_ACC_Z, // at 8, measure Z acc. |
233 | AD_GYRO_PITCH, AD_GYRO_ROLL, AD_ACC_Z, // at 8, measure Z acc. |
231 | AD_GYRO_PITCH, AD_GYRO_ROLL, AD_GYRO_YAW, // at 11, finish yaw gyro |
234 | AD_GYRO_PITCH, AD_GYRO_ROLL, AD_GYRO_YAW, // at 11, finish yaw gyro |
232 | 235 | ||
233 | AD_ACC_PITCH, // at 12, finish pitch axis acc. |
236 | AD_ACC_PITCH, // at 12, finish pitch axis acc. |
234 | AD_ACC_ROLL, // at 13, finish roll axis acc. |
237 | AD_ACC_ROLL, // at 13, finish roll axis acc. |
235 | AD_AIRPRESSURE, // at 14, finish air pressure. |
238 | AD_AIRPRESSURE, // at 14, finish air pressure. |
236 | 239 | ||
237 | AD_GYRO_PITCH, // at 15, finish pitch gyro |
240 | AD_GYRO_PITCH, // at 15, finish pitch gyro |
238 | AD_GYRO_ROLL, // at 16, finish roll gyro |
241 | AD_GYRO_ROLL, // at 16, finish roll gyro |
239 | AD_UBAT // at 17, measure battery. |
242 | AD_UBAT // at 17, measure battery. |
240 | }; |
243 | }; |
241 | 244 | ||
242 | // Feature removed. Could be reintroduced later - but should work for all gyro types then. |
245 | // Feature removed. Could be reintroduced later - but should work for all gyro types then. |
243 | // uint8_t GyroDefectPitch = 0, GyroDefectRoll = 0, GyroDefectYaw = 0; |
246 | // uint8_t GyroDefectPitch = 0, GyroDefectRoll = 0, GyroDefectYaw = 0; |
244 | 247 | ||
245 | void analog_init(void) { |
248 | void analog_init(void) { |
246 | uint8_t sreg = SREG; |
249 | uint8_t sreg = SREG; |
247 | // disable all interrupts before reconfiguration |
250 | // disable all interrupts before reconfiguration |
248 | cli(); |
251 | cli(); |
249 | 252 | ||
250 | //ADC0 ... ADC7 is connected to PortA pin 0 ... 7 |
253 | //ADC0 ... ADC7 is connected to PortA pin 0 ... 7 |
251 | DDRA = 0x00; |
254 | DDRA = 0x00; |
252 | PORTA = 0x00; |
255 | PORTA = 0x00; |
253 | // Digital Input Disable Register 0 |
256 | // Digital Input Disable Register 0 |
254 | // Disable digital input buffer for analog adc_channel pins |
257 | // Disable digital input buffer for analog adc_channel pins |
255 | DIDR0 = 0xFF; |
258 | DIDR0 = 0xFF; |
256 | // external reference, adjust data to the right |
259 | // external reference, adjust data to the right |
257 | ADMUX &= ~((1<<REFS1)|(1<<REFS0)|(1<<ADLAR)); |
260 | ADMUX &= ~((1<<REFS1)|(1<<REFS0)|(1<<ADLAR)); |
258 | // set muxer to ADC adc_channel 0 (0 to 7 is a valid choice) |
261 | // set muxer to ADC adc_channel 0 (0 to 7 is a valid choice) |
259 | ADMUX = (ADMUX & 0xE0); |
262 | ADMUX = (ADMUX & 0xE0); |
260 | //Set ADC Control and Status Register A |
263 | //Set ADC Control and Status Register A |
261 | //Auto Trigger Enable, Prescaler Select Bits to Division Factor 128, i.e. ADC clock = SYSCKL/128 = 156.25 kHz |
264 | //Auto Trigger Enable, Prescaler Select Bits to Division Factor 128, i.e. ADC clock = SYSCKL/128 = 156.25 kHz |
262 | ADCSRA = (1<<ADPS2)|(1<<ADPS1)|(1<<ADPS0); |
265 | ADCSRA = (1<<ADPS2)|(1<<ADPS1)|(1<<ADPS0); |
263 | //Set ADC Control and Status Register B |
266 | //Set ADC Control and Status Register B |
264 | //Trigger Source to Free Running Mode |
267 | //Trigger Source to Free Running Mode |
265 | ADCSRB &= ~((1<<ADTS2)|(1<<ADTS1)|(1<<ADTS0)); |
268 | ADCSRB &= ~((1<<ADTS2)|(1<<ADTS1)|(1<<ADTS0)); |
266 | 269 | ||
267 | startAnalogConversionCycle(); |
270 | startAnalogConversionCycle(); |
268 | 271 | ||
269 | // restore global interrupt flags |
272 | // restore global interrupt flags |
270 | SREG = sreg; |
273 | SREG = sreg; |
271 | } |
274 | } |
272 | 275 | ||
273 | uint16_t rawGyroValue(uint8_t axis) { |
276 | uint16_t rawGyroValue(uint8_t axis) { |
274 | return sensorInputs[AD_GYRO_PITCH-axis]; |
277 | return sensorInputs[AD_GYRO_PITCH-axis]; |
275 | } |
278 | } |
276 | 279 | ||
277 | uint16_t rawAccValue(uint8_t axis) { |
280 | uint16_t rawAccValue(uint8_t axis) { |
278 | return sensorInputs[AD_ACC_PITCH-axis]; |
281 | return sensorInputs[AD_ACC_PITCH-axis]; |
279 | } |
282 | } |
280 | 283 | ||
281 | void measureNoise(const int16_t sensor, |
284 | void measureNoise(const int16_t sensor, |
282 | volatile uint16_t* const noiseMeasurement, const uint8_t damping) { |
285 | volatile uint16_t* const noiseMeasurement, const uint8_t damping) { |
283 | if (sensor > (int16_t) (*noiseMeasurement)) { |
286 | if (sensor > (int16_t) (*noiseMeasurement)) { |
284 | *noiseMeasurement = sensor; |
287 | *noiseMeasurement = sensor; |
285 | } else if (-sensor > (int16_t) (*noiseMeasurement)) { |
288 | } else if (-sensor > (int16_t) (*noiseMeasurement)) { |
286 | *noiseMeasurement = -sensor; |
289 | *noiseMeasurement = -sensor; |
287 | } else if (*noiseMeasurement > damping) { |
290 | } else if (*noiseMeasurement > damping) { |
288 | *noiseMeasurement -= damping; |
291 | *noiseMeasurement -= damping; |
289 | } else { |
292 | } else { |
290 | *noiseMeasurement = 0; |
293 | *noiseMeasurement = 0; |
291 | } |
294 | } |
292 | } |
295 | } |
293 | 296 | ||
294 | /* |
297 | /* |
295 | * Min.: 0 |
298 | * Min.: 0 |
296 | * Max: About 106 * 240 + 2047 = 27487; it is OK with just a 16 bit type. |
299 | * Max: About 106 * 240 + 2047 = 27487; it is OK with just a 16 bit type. |
297 | */ |
300 | */ |
298 | uint16_t getSimplePressure(int advalue) { |
301 | uint16_t getSimplePressure(int advalue) { |
299 | return (uint16_t) OCR0A * (uint16_t) rangewidth + advalue; |
302 | return (uint16_t) OCR0A * (uint16_t) rangewidth + advalue; |
300 | } |
303 | } |
301 | 304 | ||
302 | void startAnalogConversionCycle(void) { |
305 | void startAnalogConversionCycle(void) { |
303 | analogDataReady = 0; |
306 | analogDataReady = 0; |
- | 307 | ||
304 | // Stop the sampling. Cycle is over. |
308 | // Stop the sampling. Cycle is over. |
305 | for (uint8_t i = 0; i < 8; i++) { |
309 | for (uint8_t i = 0; i < 8; i++) { |
306 | sensorInputs[i] = 0; |
310 | sensorInputs[i] = 0; |
307 | } |
311 | } |
308 | adState = 0; |
312 | adState = 0; |
309 | adChannel = AD_GYRO_PITCH; |
313 | adChannel = AD_GYRO_PITCH; |
310 | ADMUX = (ADMUX & 0xE0) | adChannel; |
314 | ADMUX = (ADMUX & 0xE0) | adChannel; |
311 | startADC(); |
315 | startADC(); |
312 | } |
316 | } |
313 | 317 | ||
314 | /***************************************************** |
318 | /***************************************************** |
315 | * Interrupt Service Routine for ADC |
319 | * Interrupt Service Routine for ADC |
316 | * Runs at 312.5 kHz or 3.2 �s. When all states are |
320 | * Runs at 312.5 kHz or 3.2 �s. When all states are |
317 | * processed further conversions are stopped. |
321 | * processed further conversions are stopped. |
318 | *****************************************************/ |
322 | *****************************************************/ |
319 | ISR(ADC_vect) { |
323 | ISR(ADC_vect) { |
320 | sensorInputs[adChannel] += ADC; |
324 | sensorInputs[adChannel] += ADC; |
321 | // set up for next state. |
325 | // set up for next state. |
322 | adState++; |
326 | adState++; |
323 | if (adState < sizeof(channelsForStates)) { |
327 | if (adState < sizeof(channelsForStates)) { |
324 | adChannel = pgm_read_byte(&channelsForStates[adState]); |
328 | adChannel = pgm_read_byte(&channelsForStates[adState]); |
325 | // set adc muxer to next adChannel |
329 | // set adc muxer to next adChannel |
326 | ADMUX = (ADMUX & 0xE0) | adChannel; |
330 | ADMUX = (ADMUX & 0xE0) | adChannel; |
327 | // after full cycle stop further interrupts |
331 | // after full cycle stop further interrupts |
328 | startADC(); |
332 | startADC(); |
329 | } else { |
333 | } else { |
330 | ADCycleCount++; |
334 | ADCycleCount++; |
331 | analogDataReady = 1; |
335 | analogDataReady = 1; |
332 | // do not restart ADC converter. |
336 | // do not restart ADC converter. |
333 | } |
337 | } |
334 | } |
338 | } |
335 | 339 | ||
336 | void analog_updateGyros(void) { |
340 | void analog_updateGyros(void) { |
337 | // for various filters... |
341 | // for various filters... |
338 | int16_t tempOffsetGyro[2], tempGyro; |
342 | int16_t tempOffsetGyro[2], tempGyro; |
339 | 343 | ||
340 | debugOut.digital[0] &= ~DEBUG_SENSORLIMIT; |
344 | debugOut.digital[0] &= ~DEBUG_SENSORLIMIT; |
341 | for (uint8_t axis=0; axis<2; axis++) { |
345 | for (uint8_t axis=0; axis<2; axis++) { |
342 | tempGyro = rawGyroValue(axis); |
346 | tempGyro = rawGyroValue(axis); |
343 | - | ||
344 | /* |
347 | /* |
345 | * Process the gyro data for the PID controller. |
348 | * Process the gyro data for the PID controller. |
346 | */ |
349 | */ |
347 | // 1) Extrapolate: Near the ends of the range, we boost the input significantly. This simulates a |
350 | // 1) Extrapolate: Near the ends of the range, we boost the input significantly. This simulates a |
348 | // gyro with a wider range, and helps counter saturation at full control. |
351 | // gyro with a wider range, and helps counter saturation at full control. |
349 | 352 | ||
350 | if (staticParams.bitConfig & CFG_GYRO_SATURATION_PREVENTION) { |
353 | if (staticParams.bitConfig & CFG_GYRO_SATURATION_PREVENTION) { |
351 | if (tempGyro < SENSOR_MIN_PITCHROLL) { |
354 | if (tempGyro < SENSOR_MIN_PITCHROLL) { |
352 | debugOut.digital[0] |= DEBUG_SENSORLIMIT; |
355 | debugOut.digital[0] |= DEBUG_SENSORLIMIT; |
353 | tempGyro = tempGyro * EXTRAPOLATION_SLOPE - EXTRAPOLATION_LIMIT; |
356 | tempGyro = tempGyro * EXTRAPOLATION_SLOPE - EXTRAPOLATION_LIMIT; |
354 | } else if (tempGyro > SENSOR_MAX_PITCHROLL) { |
357 | } else if (tempGyro > SENSOR_MAX_PITCHROLL) { |
355 | debugOut.digital[0] |= DEBUG_SENSORLIMIT; |
358 | debugOut.digital[0] |= DEBUG_SENSORLIMIT; |
356 | tempGyro = (tempGyro - SENSOR_MAX_PITCHROLL) * EXTRAPOLATION_SLOPE + SENSOR_MAX_PITCHROLL; |
359 | tempGyro = (tempGyro - SENSOR_MAX_PITCHROLL) * EXTRAPOLATION_SLOPE + SENSOR_MAX_PITCHROLL; |
357 | } |
360 | } |
358 | } |
361 | } |
359 | 362 | ||
360 | // 2) Apply sign and offset, scale before filtering. |
363 | // 2) Apply sign and offset, scale before filtering. |
361 | tempOffsetGyro[axis] = (tempGyro - gyroOffset.offsets[axis]) * GYRO_FACTOR_PITCHROLL; |
364 | tempOffsetGyro[axis] = (tempGyro - gyroOffset.offsets[axis]) * GYRO_FACTOR_PITCHROLL; |
362 | } |
365 | } |
363 | 366 | ||
364 | // 2.1: Transform axes. |
367 | // 2.1: Transform axes. |
365 | rotate(tempOffsetGyro, staticParams.gyroQuadrant, staticParams.imuReversedFlags & 1); |
368 | rotate(tempOffsetGyro, staticParams.gyroQuadrant, staticParams.imuReversedFlags & 1); |
366 | 369 | ||
367 | for (uint8_t axis=0; axis<2; axis++) { |
370 | for (uint8_t axis=0; axis<2; axis++) { |
368 | // 3) Filter. |
371 | // 3) Filter. |
369 | tempOffsetGyro[axis] = (gyro_PID[axis] * (staticParams.gyroPIDFilterConstant - 1) + tempOffsetGyro[axis]) / staticParams.gyroPIDFilterConstant; |
372 | tempOffsetGyro[axis] = (gyro_PID[axis] * (staticParams.gyroPIDFilterConstant - 1) + tempOffsetGyro[axis]) / staticParams.gyroPIDFilterConstant; |
370 | 373 | ||
371 | // 4) Measure noise. |
374 | // 4) Measure noise. |
372 | measureNoise(tempOffsetGyro[axis], &gyroNoisePeak[axis], GYRO_NOISE_MEASUREMENT_DAMPING); |
375 | measureNoise(tempOffsetGyro[axis], &gyroNoisePeak[axis], GYRO_NOISE_MEASUREMENT_DAMPING); |
373 | 376 | ||
374 | // 5) Differential measurement. |
377 | // 5) Differential measurement. |
375 | gyroD[axis] = (gyroD[axis] * (staticParams.gyroDFilterConstant - 1) + (tempOffsetGyro[axis] - gyro_PID[axis])) / staticParams.gyroDFilterConstant; |
378 | gyroD[axis] = (gyroD[axis] * (staticParams.gyroDFilterConstant - 1) + (tempOffsetGyro[axis] - gyro_PID[axis])) / staticParams.gyroDFilterConstant; |
376 | 379 | ||
377 | // 6) Done. |
380 | // 6) Done. |
378 | gyro_PID[axis] = tempOffsetGyro[axis]; |
381 | gyro_PID[axis] = tempOffsetGyro[axis]; |
379 | 382 | ||
380 | // Prepare tempOffsetGyro for next calculation below... |
383 | // Prepare tempOffsetGyro for next calculation below... |
381 | tempOffsetGyro[axis] = (rawGyroValue(axis) - gyroOffset.offsets[axis]) * GYRO_FACTOR_PITCHROLL; |
384 | tempOffsetGyro[axis] = (rawGyroValue(axis) - gyroOffset.offsets[axis]) * GYRO_FACTOR_PITCHROLL; |
382 | } |
385 | } |
383 | 386 | ||
384 | /* |
387 | /* |
385 | * Now process the data for attitude angles. |
388 | * Now process the data for attitude angles. |
386 | */ |
389 | */ |
387 | rotate(tempOffsetGyro, staticParams.gyroQuadrant, staticParams.imuReversedFlags & 1); |
390 | rotate(tempOffsetGyro, staticParams.gyroQuadrant, staticParams.imuReversedFlags & 1); |
- | 391 | ||
- | 392 | gyro_ATT[PITCH] = tempOffsetGyro[PITCH]; |
|
- | 393 | gyro_ATT[ROLL] = tempOffsetGyro[ROLL]; |
|
- | 394 | ||
- | 395 | debugOut.analog[22 + 0] = gyro_PID[0]; |
|
- | 396 | debugOut.analog[22 + 1] = gyro_PID[1]; |
|
- | 397 | ||
- | 398 | debugOut.analog[24 + 0] = gyro_ATT[0]; |
|
- | 399 | debugOut.analog[24 + 1] = gyro_ATT[1]; |
|
388 | 400 | ||
389 | // 2) Filter. This should really be quite unnecessary. The integration should gobble up any noise anyway and the values are not used for anything else. |
401 | // 2) Filter. This should really be quite unnecessary. The integration should gobble up any noise anyway and the values are not used for anything else. |
390 | // gyro_ATT[PITCH] = (gyro_ATT[PITCH] * (staticParams.attitudeGyroFilter - 1) + tempOffsetGyro[PITCH]) / staticParams.attitudeGyroFilter; |
402 | // gyro_ATT[PITCH] = (gyro_ATT[PITCH] * (staticParams.attitudeGyroFilter - 1) + tempOffsetGyro[PITCH]) / staticParams.attitudeGyroFilter; |
391 | // gyro_ATT[ROLL] = (gyro_ATT[ROLL] * (staticParams.attitudeGyroFilter - 1) + tempOffsetGyro[ROLL]) / staticParams.attitudeGyroFilter; |
403 | // gyro_ATT[ROLL] = (gyro_ATT[ROLL] * (staticParams.attitudeGyroFilter - 1) + tempOffsetGyro[ROLL]) / staticParams.attitudeGyroFilter; |
392 | 404 | ||
393 | // Yaw gyro. |
405 | // Yaw gyro. |
394 | if (staticParams.imuReversedFlags & 2) |
406 | if (staticParams.imuReversedFlags & 2) |
395 | yawGyro = gyroOffset.offsets[YAW] - sensorInputs[AD_GYRO_YAW]; |
407 | yawGyro = gyroOffset.offsets[YAW] - sensorInputs[AD_GYRO_YAW]; |
396 | else |
408 | else |
397 | yawGyro = sensorInputs[AD_GYRO_YAW] - gyroOffset.offsets[YAW]; |
409 | yawGyro = sensorInputs[AD_GYRO_YAW] - gyroOffset.offsets[YAW]; |
398 | } |
410 | } |
399 | 411 | ||
400 | void analog_updateAccelerometers(void) { |
412 | void analog_updateAccelerometers(void) { |
401 | // Pitch and roll axis accelerations. |
413 | // Pitch and roll axis accelerations. |
402 | for (uint8_t axis=0; axis<2; axis++) { |
414 | for (uint8_t axis=0; axis<2; axis++) { |
403 | acc[axis] = rawAccValue(axis) - accOffset.offsets[axis]; |
415 | acc[axis] = rawAccValue(axis) - accOffset.offsets[axis]; |
404 | } |
416 | } |
405 | 417 | ||
406 | rotate(acc, staticParams.accQuadrant, staticParams.imuReversedFlags & 4); |
418 | rotate(acc, staticParams.accQuadrant, staticParams.imuReversedFlags & 4); |
407 | 419 | ||
408 | for(uint8_t axis=0; axis<3; axis++) { |
420 | for(uint8_t axis=0; axis<3; axis++) { |
409 | filteredAcc[axis] = (filteredAcc[axis] * (staticParams.accFilterConstant - 1) + acc[axis]) / staticParams.accFilterConstant; |
421 | filteredAcc[axis] = (filteredAcc[axis] * (staticParams.accFilterConstant - 1) + acc[axis]) / staticParams.accFilterConstant; |
410 | measureNoise(acc[axis], &accNoisePeak[axis], 1); |
422 | measureNoise(acc[axis], &accNoisePeak[axis], 1); |
411 | } |
423 | } |
412 | 424 | ||
413 | // Z acc. |
425 | // Z acc. |
414 | if (staticParams.imuReversedFlags & 8) |
426 | if (staticParams.imuReversedFlags & 8) |
415 | acc[Z] = accOffset.offsets[Z] - sensorInputs[AD_ACC_Z]; |
427 | acc[Z] = accOffset.offsets[Z] - sensorInputs[AD_ACC_Z]; |
416 | else |
428 | else |
417 | acc[Z] = sensorInputs[AD_ACC_Z] - accOffset.offsets[Z]; |
429 | acc[Z] = sensorInputs[AD_ACC_Z] - accOffset.offsets[Z]; |
418 | } |
430 | } |
419 | 431 | ||
420 | void analog_updateAirPressure(void) { |
432 | void analog_updateAirPressure(void) { |
421 | static uint16_t pressureAutorangingWait = 25; |
433 | static uint16_t pressureAutorangingWait = 25; |
422 | uint16_t rawAirPressure; |
434 | uint16_t rawAirPressure; |
423 | int16_t newrange; |
435 | int16_t newrange; |
424 | // air pressure |
436 | // air pressure |
425 | if (pressureAutorangingWait) { |
437 | if (pressureAutorangingWait) { |
426 | //A range switch was done recently. Wait for steadying. |
438 | //A range switch was done recently. Wait for steadying. |
427 | pressureAutorangingWait--; |
439 | pressureAutorangingWait--; |
428 | debugOut.analog[27] = (uint16_t) OCR0A; |
440 | debugOut.analog[27] = (uint16_t) OCR0A; |
429 | debugOut.analog[31] = simpleAirPressure; |
441 | debugOut.analog[31] = simpleAirPressure; |
430 | } else { |
442 | } else { |
431 | rawAirPressure = sensorInputs[AD_AIRPRESSURE]; |
443 | rawAirPressure = sensorInputs[AD_AIRPRESSURE]; |
432 | if (rawAirPressure < MIN_RAWPRESSURE) { |
444 | if (rawAirPressure < MIN_RAWPRESSURE) { |
433 | // value is too low, so decrease voltage on the op amp minus input, making the value higher. |
445 | // value is too low, so decrease voltage on the op amp minus input, making the value higher. |
434 | newrange = OCR0A - (MAX_RAWPRESSURE - MIN_RAWPRESSURE) / (rangewidth * 4); // 4; // (MAX_RAWPRESSURE - rawAirPressure) / (rangewidth * 2) + 1; |
446 | newrange = OCR0A - (MAX_RAWPRESSURE - MIN_RAWPRESSURE) / (rangewidth * 4); // 4; // (MAX_RAWPRESSURE - rawAirPressure) / (rangewidth * 2) + 1; |
435 | if (newrange > MIN_RANGES_EXTRAPOLATION) { |
447 | if (newrange > MIN_RANGES_EXTRAPOLATION) { |
436 | pressureAutorangingWait = (OCR0A - newrange) * AUTORANGE_WAIT_FACTOR; // = OCRA0 - OCRA0 + |
448 | pressureAutorangingWait = (OCR0A - newrange) * AUTORANGE_WAIT_FACTOR; // = OCRA0 - OCRA0 + |
437 | OCR0A = newrange; |
449 | OCR0A = newrange; |
438 | } else { |
450 | } else { |
439 | if (OCR0A) { |
451 | if (OCR0A) { |
440 | OCR0A--; |
452 | OCR0A--; |
441 | pressureAutorangingWait = AUTORANGE_WAIT_FACTOR; |
453 | pressureAutorangingWait = AUTORANGE_WAIT_FACTOR; |
442 | } |
454 | } |
443 | } |
455 | } |
444 | } else if (rawAirPressure > MAX_RAWPRESSURE) { |
456 | } else if (rawAirPressure > MAX_RAWPRESSURE) { |
445 | // value is too high, so increase voltage on the op amp minus input, making the value lower. |
457 | // value is too high, so increase voltage on the op amp minus input, making the value lower. |
446 | // If near the end, make a limited increase |
458 | // If near the end, make a limited increase |
447 | newrange = OCR0A + (MAX_RAWPRESSURE - MIN_RAWPRESSURE) / (rangewidth * 4); // 4; // (rawAirPressure - MIN_RAWPRESSURE) / (rangewidth * 2) - 1; |
459 | newrange = OCR0A + (MAX_RAWPRESSURE - MIN_RAWPRESSURE) / (rangewidth * 4); // 4; // (rawAirPressure - MIN_RAWPRESSURE) / (rangewidth * 2) - 1; |
448 | if (newrange < MAX_RANGES_EXTRAPOLATION) { |
460 | if (newrange < MAX_RANGES_EXTRAPOLATION) { |
449 | pressureAutorangingWait = (newrange - OCR0A) * AUTORANGE_WAIT_FACTOR; |
461 | pressureAutorangingWait = (newrange - OCR0A) * AUTORANGE_WAIT_FACTOR; |
450 | OCR0A = newrange; |
462 | OCR0A = newrange; |
451 | } else { |
463 | } else { |
452 | if (OCR0A < 254) { |
464 | if (OCR0A < 254) { |
453 | OCR0A++; |
465 | OCR0A++; |
454 | pressureAutorangingWait = AUTORANGE_WAIT_FACTOR; |
466 | pressureAutorangingWait = AUTORANGE_WAIT_FACTOR; |
455 | } |
467 | } |
456 | } |
468 | } |
457 | } |
469 | } |
458 | 470 | ||
459 | // Even if the sample is off-range, use it. |
471 | // Even if the sample is off-range, use it. |
460 | simpleAirPressure = getSimplePressure(rawAirPressure); |
472 | simpleAirPressure = getSimplePressure(rawAirPressure); |
461 | debugOut.analog[27] = (uint16_t) OCR0A; |
473 | debugOut.analog[27] = (uint16_t) OCR0A; |
462 | debugOut.analog[31] = simpleAirPressure; |
474 | debugOut.analog[31] = simpleAirPressure; |
463 | 475 | ||
464 | if (simpleAirPressure < MIN_RANGES_EXTRAPOLATION * rangewidth) { |
476 | if (simpleAirPressure < MIN_RANGES_EXTRAPOLATION * rangewidth) { |
465 | // Danger: pressure near lower end of range. If the measurement saturates, the |
477 | // Danger: pressure near lower end of range. If the measurement saturates, the |
466 | // copter may climb uncontrolledly... Simulate a drastic reduction in pressure. |
478 | // copter may climb uncontrolledly... Simulate a drastic reduction in pressure. |
467 | debugOut.digital[1] |= DEBUG_SENSORLIMIT; |
479 | debugOut.digital[1] |= DEBUG_SENSORLIMIT; |
468 | airPressureSum += (int16_t) MIN_RANGES_EXTRAPOLATION * rangewidth |
480 | airPressureSum += (int16_t) MIN_RANGES_EXTRAPOLATION * rangewidth |
469 | + (simpleAirPressure - (int16_t) MIN_RANGES_EXTRAPOLATION |
481 | + (simpleAirPressure - (int16_t) MIN_RANGES_EXTRAPOLATION |
470 | * rangewidth) * PRESSURE_EXTRAPOLATION_COEFF; |
482 | * rangewidth) * PRESSURE_EXTRAPOLATION_COEFF; |
471 | } else if (simpleAirPressure > MAX_RANGES_EXTRAPOLATION * rangewidth) { |
483 | } else if (simpleAirPressure > MAX_RANGES_EXTRAPOLATION * rangewidth) { |
472 | // Danger: pressure near upper end of range. If the measurement saturates, the |
484 | // Danger: pressure near upper end of range. If the measurement saturates, the |
473 | // copter may descend uncontrolledly... Simulate a drastic increase in pressure. |
485 | // copter may descend uncontrolledly... Simulate a drastic increase in pressure. |
474 | debugOut.digital[1] |= DEBUG_SENSORLIMIT; |
486 | debugOut.digital[1] |= DEBUG_SENSORLIMIT; |
475 | airPressureSum += (int16_t) MAX_RANGES_EXTRAPOLATION * rangewidth |
487 | airPressureSum += (int16_t) MAX_RANGES_EXTRAPOLATION * rangewidth |
476 | + (simpleAirPressure - (int16_t) MAX_RANGES_EXTRAPOLATION |
488 | + (simpleAirPressure - (int16_t) MAX_RANGES_EXTRAPOLATION |
477 | * rangewidth) * PRESSURE_EXTRAPOLATION_COEFF; |
489 | * rangewidth) * PRESSURE_EXTRAPOLATION_COEFF; |
478 | } else { |
490 | } else { |
479 | // normal case. |
491 | // normal case. |
480 | // If AIRPRESSURE_SUMMATION_FACTOR is an odd number we only want to add half the double sample. |
492 | // If AIRPRESSURE_SUMMATION_FACTOR is an odd number we only want to add half the double sample. |
481 | // The 2 cases above (end of range) are ignored for this. |
493 | // The 2 cases above (end of range) are ignored for this. |
482 | debugOut.digital[1] &= ~DEBUG_SENSORLIMIT; |
494 | debugOut.digital[1] &= ~DEBUG_SENSORLIMIT; |
483 | if (pressureMeasurementCount == AIRPRESSURE_SUMMATION_FACTOR - 1) |
495 | if (pressureMeasurementCount == AIRPRESSURE_SUMMATION_FACTOR - 1) |
484 | airPressureSum += simpleAirPressure / 2; |
496 | airPressureSum += simpleAirPressure / 2; |
485 | else |
497 | else |
486 | airPressureSum += simpleAirPressure; |
498 | airPressureSum += simpleAirPressure; |
487 | } |
499 | } |
488 | 500 | ||
489 | // 2 samples were added. |
501 | // 2 samples were added. |
490 | pressureMeasurementCount += 2; |
502 | pressureMeasurementCount += 2; |
491 | if (pressureMeasurementCount >= AIRPRESSURE_SUMMATION_FACTOR) { |
503 | if (pressureMeasurementCount >= AIRPRESSURE_SUMMATION_FACTOR) { |
492 | filteredAirPressure = (filteredAirPressure * (AIRPRESSURE_FILTER - 1) |
504 | filteredAirPressure = (filteredAirPressure * (AIRPRESSURE_FILTER - 1) |
493 | + airPressureSum + AIRPRESSURE_FILTER / 2) / AIRPRESSURE_FILTER; |
505 | + airPressureSum + AIRPRESSURE_FILTER / 2) / AIRPRESSURE_FILTER; |
494 | pressureMeasurementCount = airPressureSum = 0; |
506 | pressureMeasurementCount = airPressureSum = 0; |
495 | } |
507 | } |
496 | } |
508 | } |
497 | } |
509 | } |
498 | 510 | ||
499 | void analog_updateBatteryVoltage(void) { |
511 | void analog_updateBatteryVoltage(void) { |
500 | // Battery. The measured value is: (V * 1k/11k)/3v * 1024 = 31.03 counts per volt (max. measurable is 33v). |
512 | // Battery. The measured value is: (V * 1k/11k)/3v * 1024 = 31.03 counts per volt (max. measurable is 33v). |
501 | // This is divided by 3 --> 10.34 counts per volt. |
513 | // This is divided by 3 --> 10.34 counts per volt. |
502 | UBat = (3 * UBat + sensorInputs[AD_UBAT] / 3) / 4; |
514 | UBat = (3 * UBat + sensorInputs[AD_UBAT] / 3) / 4; |
503 | debugOut.analog[11] = UBat; |
515 | debugOut.analog[11] = UBat; |
504 | debugOut.analog[21] = sensorInputs[AD_UBAT]; |
516 | debugOut.analog[21] = sensorInputs[AD_UBAT]; |
505 | } |
517 | } |
506 | 518 | ||
507 | void analog_update(void) { |
519 | void analog_update(void) { |
508 | analog_updateGyros(); |
520 | analog_updateGyros(); |
509 | analog_updateAccelerometers(); |
521 | analog_updateAccelerometers(); |
510 | analog_updateAirPressure(); |
522 | analog_updateAirPressure(); |
511 | analog_updateBatteryVoltage(); |
523 | analog_updateBatteryVoltage(); |
512 | } |
524 | } |
513 | 525 | ||
514 | void analog_setNeutral() { |
526 | void analog_setNeutral() { |
515 | if (gyroAmplifierOffset_readFromEEProm()) { |
527 | if (gyroAmplifierOffset_readFromEEProm()) { |
516 | printf("gyro amp invalid%s",recal); |
528 | printf("gyro amp invalid%s",recal); |
517 | gyro_loadAmplifierOffsets(1); |
529 | gyro_loadAmplifierOffsets(1); |
518 | } else |
530 | } else |
519 | gyro_loadAmplifierOffsets(0); |
531 | gyro_loadAmplifierOffsets(0); |
520 | 532 | ||
521 | if (gyroOffset_readFromEEProm()) { |
533 | if (gyroOffset_readFromEEProm()) { |
522 | printf("gyro offsets invalid%s",recal); |
534 | printf("gyro offsets invalid%s",recal); |
523 | gyroOffset.offsets[PITCH] = gyroOffset.offsets[ROLL] = 512 * GYRO_SUMMATION_FACTOR_PITCHROLL; |
535 | gyroOffset.offsets[PITCH] = gyroOffset.offsets[ROLL] = 512 * GYRO_SUMMATION_FACTOR_PITCHROLL; |
524 | gyroOffset.offsets[YAW] = 512 * GYRO_SUMMATION_FACTOR_YAW; |
536 | gyroOffset.offsets[YAW] = 512 * GYRO_SUMMATION_FACTOR_YAW; |
525 | } |
537 | } |
526 | 538 | ||
527 | if (accOffset_readFromEEProm()) { |
539 | if (accOffset_readFromEEProm()) { |
528 | printf("acc. meter offsets invalid%s",recal); |
540 | printf("acc. meter offsets invalid%s",recal); |
529 | accOffset.offsets[PITCH] = accOffset.offsets[ROLL] = 512 * ACC_SUMMATION_FACTOR_PITCHROLL; |
541 | accOffset.offsets[PITCH] = accOffset.offsets[ROLL] = 512 * ACC_SUMMATION_FACTOR_PITCHROLL; |
530 | accOffset.offsets[Z] = 717 * ACC_SUMMATION_FACTOR_Z; |
542 | accOffset.offsets[Z] = 717 * ACC_SUMMATION_FACTOR_Z; |
531 | } |
543 | } |
532 | 544 | ||
533 | // Noise is relative to offset. So, reset noise measurements when changing offsets. |
545 | // Noise is relative to offset. So, reset noise measurements when changing offsets. |
534 | gyroNoisePeak[PITCH] = gyroNoisePeak[ROLL] = 0; |
546 | gyroNoisePeak[PITCH] = gyroNoisePeak[ROLL] = 0; |
535 | accNoisePeak[PITCH] = accNoisePeak[ROLL] = 0; |
547 | accNoisePeak[PITCH] = accNoisePeak[ROLL] = 0; |
536 | 548 | ||
537 | // Setting offset values has an influence in the analog.c ISR |
549 | // Setting offset values has an influence in the analog.c ISR |
538 | // Therefore run measurement for 100ms to achive stable readings |
550 | // Therefore run measurement for 100ms to achive stable readings |
539 | delay_ms_with_adc_measurement(100, 0); |
551 | delay_ms_with_adc_measurement(100, 0); |
540 | 552 | ||
541 | // Rough estimate. Hmm no nothing happens at calibration anyway. |
553 | // Rough estimate. Hmm no nothing happens at calibration anyway. |
542 | // airPressureSum = simpleAirPressure * (AIRPRESSURE_SUMMATION_FACTOR/2); |
554 | // airPressureSum = simpleAirPressure * (AIRPRESSURE_SUMMATION_FACTOR/2); |
543 | // pressureMeasurementCount = 0; |
555 | // pressureMeasurementCount = 0; |
544 | } |
556 | } |
545 | 557 | ||
546 | void analog_calibrateGyros(void) { |
558 | void analog_calibrateGyros(void) { |
547 | #define GYRO_OFFSET_CYCLES 32 |
559 | #define GYRO_OFFSET_CYCLES 32 |
548 | uint8_t i, axis; |
560 | uint8_t i, axis; |
549 | int32_t offsets[3] = { 0, 0, 0 }; |
561 | int32_t offsets[3] = { 0, 0, 0 }; |
550 | gyro_calibrate(); |
562 | gyro_calibrate(); |
551 | 563 | ||
552 | // determine gyro bias by averaging (requires that the copter does not rotate around any axis!) |
564 | // determine gyro bias by averaging (requires that the copter does not rotate around any axis!) |
553 | for (i = 0; i < GYRO_OFFSET_CYCLES; i++) { |
565 | for (i = 0; i < GYRO_OFFSET_CYCLES; i++) { |
554 | delay_ms_with_adc_measurement(10, 1); |
566 | delay_ms_with_adc_measurement(10, 1); |
555 | for (axis = PITCH; axis <= YAW; axis++) { |
567 | for (axis = PITCH; axis <= YAW; axis++) { |
556 | offsets[axis] += rawGyroValue(axis); |
568 | offsets[axis] += rawGyroValue(axis); |
557 | } |
569 | } |
558 | } |
570 | } |
559 | 571 | ||
560 | for (axis = PITCH; axis <= YAW; axis++) { |
572 | for (axis = PITCH; axis <= YAW; axis++) { |
561 | gyroOffset.offsets[axis] = (offsets[axis] + GYRO_OFFSET_CYCLES / 2) / GYRO_OFFSET_CYCLES; |
573 | gyroOffset.offsets[axis] = (offsets[axis] + GYRO_OFFSET_CYCLES / 2) / GYRO_OFFSET_CYCLES; |
562 | } |
574 | } |
563 | 575 | ||
564 | gyroOffset_writeToEEProm(); |
576 | gyroOffset_writeToEEProm(); |
565 | startAnalogConversionCycle(); |
577 | startAnalogConversionCycle(); |
566 | } |
578 | } |
567 | 579 | ||
568 | /* |
580 | /* |
569 | * Find acc. offsets for a neutral reading, and write them to EEPROM. |
581 | * Find acc. offsets for a neutral reading, and write them to EEPROM. |
570 | * Does not (!} update the local variables. This must be done with a |
582 | * Does not (!} update the local variables. This must be done with a |
571 | * call to analog_calibrate() - this always (?) is done by the caller |
583 | * call to analog_calibrate() - this always (?) is done by the caller |
572 | * anyway. There would be nothing wrong with updating the variables |
584 | * anyway. There would be nothing wrong with updating the variables |
573 | * directly from here, though. |
585 | * directly from here, though. |
574 | */ |
586 | */ |
575 | void analog_calibrateAcc(void) { |
587 | void analog_calibrateAcc(void) { |
576 | #define ACC_OFFSET_CYCLES 32 |
588 | #define ACC_OFFSET_CYCLES 32 |
577 | uint8_t i, axis; |
589 | uint8_t i, axis; |
578 | int32_t offsets[3] = { 0, 0, 0 }; |
590 | int32_t offsets[3] = { 0, 0, 0 }; |
579 | int16_t filteredDelta; |
591 | int16_t filteredDelta; |
580 | 592 | ||
581 | for (i = 0; i < ACC_OFFSET_CYCLES; i++) { |
593 | for (i = 0; i < ACC_OFFSET_CYCLES; i++) { |
582 | delay_ms_with_adc_measurement(10, 1); |
594 | delay_ms_with_adc_measurement(10, 1); |
583 | for (axis = PITCH; axis <= YAW; axis++) { |
595 | for (axis = PITCH; axis <= YAW; axis++) { |
584 | offsets[axis] += rawAccValue(axis); |
596 | offsets[axis] += rawAccValue(axis); |
585 | } |
597 | } |
586 | } |
598 | } |
587 | 599 | ||
588 | for (axis = PITCH; axis <= YAW; axis++) { |
600 | for (axis = PITCH; axis <= YAW; axis++) { |
589 | accOffset.offsets[axis] = (offsets[axis] + ACC_OFFSET_CYCLES / 2) / ACC_OFFSET_CYCLES; |
601 | accOffset.offsets[axis] = (offsets[axis] + ACC_OFFSET_CYCLES / 2) / ACC_OFFSET_CYCLES; |
590 | } |
602 | } |
591 | 603 | ||
592 | accOffset_writeToEEProm(); |
604 | accOffset_writeToEEProm(); |
593 | startAnalogConversionCycle(); |
605 | startAnalogConversionCycle(); |
594 | } |
606 | } |
595 | 607 |