1
2
3
4
5
6
7
8
9
10
11
12
13
14
15
16
17
18
19
20
21
22
23
24
25
26
27
28
29
30
31
32
33
34
35
36
37
38
39
40
41
42
43
44
45
46
47
48
49
50
51
52
53
54
55
56
57
58
59
60
61
62
63
64
65
66
67
68
69
70
71
72
73
74
75
76
77
78
79
80
81
82
83
84
85
86
87
88
89
90
91
92
93
94
95
96
97
98
99
100
101
102
103
104
105
106
107
108
109
110
111
112
113
114
115
116
117
118
119
120
121
122
123
124
125
126
127
128
129
130
131
132
133
134
135
136
137
138
139
140
141
142
143
144
145
146
147
148
149
150
151
152
153
154
155
156
157
158
159
160
161
162
163
164
165
166
167
168
169
170
171
172
173
174
175
176
177
178
179
180
181
182
183
184
185
186
187
188
189
190
191
192
193
194
195
196
197
198
199
200
201
202
203
204
205
206
207
208
209
210
211
212
213
214
215
216
217
218
219
220
221
222
223
224
225
226
227
228
229
230
231
232
233
234
235
236
237
238
239
240
241
242
243
244
245
246
247
248
249
250
251
252
253
254
255
256
257
258
259
260
261
262
263
264
265
266
267
268
269
270
271
272
273
274
275
276
277
278
279
280
281
282
283
284
285
286
287
288
289
290
291
292
293
294
295
296
297
298
299
300
301
302
303
304
305
306
307
308
309
310
311
312
313
314
315
316
317
318
319
320
321
322
323
324
325
326
327
328
329
330
331
332
333
334
335
336
337
338
339
340
341
|
// ADC functions on STM32H7
//
// Copyright (C) 2020 Konstantin Vogel <konstantin.vogel@gmx.net>
//
// This file may be distributed under the terms of the GNU GPLv3 license.
#include "board/irq.h" // irq_save
#include "board/misc.h" // timer_from_us
#include "command.h" // shutdown
#include "compiler.h" // ARRAY_SIZE
#include "generic/armcm_timer.h" // udelay
#include "gpio.h" // gpio_adc_setup
#include "internal.h" // GPIO
#include "sched.h" // sched_shutdown
#if CONFIG_MACH_STM32H7
#define RCC_AHBENR_ADC (RCC->AHB1ENR)
#define RCC_AHBENR_ADCEN (RCC_AHB1ENR_ADC12EN)
#define ADC_CKMODE (0b11)
#define ADC_ATICKS (0b101)
#if CONFIG_MACH_STM32H723
#define PCSEL PCSEL_RES0
#endif
#elif CONFIG_MACH_STM32L4
#define RCC_AHBENR_ADC (RCC->AHB2ENR)
#define RCC_AHBENR_ADCEN (RCC_AHB2ENR_ADCEN)
#define ADC_CKMODE (0)
#define ADC_ATICKS (0b100)
#elif CONFIG_MACH_STM32G4
#define RCC_AHBENR_ADC (RCC->AHB2ENR)
#define RCC_AHBENR_ADCEN (RCC_AHB2ENR_ADC12EN)
#define ADC_CKMODE (0b11)
#define ADC_ATICKS (0b100)
#define ADC_CCR_TSEN (ADC_CCR_VSENSESEL)
#endif
#define ADC_TEMPERATURE_PIN 0xfe
DECL_ENUMERATION("pin", "ADC_TEMPERATURE", ADC_TEMPERATURE_PIN);
DECL_CONSTANT("ADC_MAX", 4095);
#define ADCIN_BANK_SIZE 20
// GPIOs like A0_C are not covered!
// This always gives the pin connected to the positive channel
static const uint8_t adc_pins[] = {
#if CONFIG_MACH_STM32H7
// ADC1
0, // PA0_C ADC12_INP0
0, // PA1_C ADC12_INP1
GPIO('F', 11), // ADC1_INP2
GPIO('A', 6), // ADC12_INP3
GPIO('C', 4), // ADC12_INP4
GPIO('B', 1), // ADC12_INP5
GPIO('F', 12), // ADC1_INP6
GPIO('A', 7), // ADC12_INP7
GPIO('C', 5), // ADC12_INP8
GPIO('B', 0), // ADC12_INP9
GPIO('C', 0), // ADC123_INP10
GPIO('C', 1), // ADC123_INP11
GPIO('C', 2), // ADC123_INP12
GPIO('C', 3), // ADC12_INP13
GPIO('A', 2), // ADC12_INP14
GPIO('A', 3), // ADC12_INP15
GPIO('A', 0), // ADC1_INP16
GPIO('A', 1), // ADC1_INP17
GPIO('A', 4), // ADC12_INP18
GPIO('A', 5), // ADC12_INP19
// ADC2
0, // PA0_C ADC12_INP0
0, // PA1_C ADC12_INP1
GPIO('F', 13), // ADC2_INP2
GPIO('A', 6), // ADC12_INP3
GPIO('C', 4), // ADC12_INP4
GPIO('B', 1), // ADC12_INP5
GPIO('F', 14), // ADC2_INP6
GPIO('A', 7), // ADC12_INP7
GPIO('C', 5), // ADC12_INP8
GPIO('B', 0), // ADC12_INP9
GPIO('C', 0), // ADC123_INP10
GPIO('C', 1), // ADC123_INP11
GPIO('C', 2), // ADC123_INP12
GPIO('C', 3), // ADC12_INP13
GPIO('A', 2), // ADC12_INP14
GPIO('A', 3), // ADC12_INP15
0, // dac_out1
0, // dac_out2
GPIO('A', 4), // ADC12_INP18
GPIO('A', 5), // ADC12_INP19
// ADC3
0, // PC2_C ADC3_INP0
0, // PC3_C ADC3_INP1
GPIO('F', 9) , // ADC3_INP2
GPIO('F', 7), // ADC3_INP3
GPIO('F', 5), // ADC3_INP4
GPIO('F', 3), // ADC3_INP5
GPIO('F', 10), // ADC3_INP6
GPIO('F', 8), // ADC3_INP7
GPIO('F', 6), // ADC3_INP8
GPIO('F', 4), // ADC3_INP9
GPIO('C', 0), // ADC123_INP10
GPIO('C', 1), // ADC123_INP11
GPIO('C', 2), // ADC123_INP12
GPIO('H', 2), // ADC3_INP13
GPIO('H', 3), // ADC3_INP14
GPIO('H', 4), // ADC3_INP15
GPIO('H', 5), // ADC3_INP16
#if CONFIG_MACH_STM32H723
ADC_TEMPERATURE_PIN,
0,
#else
0, // Vbat/4
ADC_TEMPERATURE_PIN,// VSENSE
#endif
0, // VREFINT
#elif CONFIG_MACH_STM32G4
0, // [0] vssa
GPIO('A', 0), // [1]
GPIO('A', 1), // [2]
GPIO('A', 2), // [3]
GPIO('A', 3), // [4]
GPIO('B', 14), // [5]
GPIO('C', 0), // [6]
GPIO('C', 1), // [7]
GPIO('C', 2), // [8]
GPIO('C', 3), // [9]
GPIO('F', 0), // [10]
GPIO('B', 12), // [11]
GPIO('B', 1), // [12]
0, // [13] opamp
GPIO('B', 11), // [14]
GPIO('B', 0), // [15]
ADC_TEMPERATURE_PIN, // [16] vtemp
0, // [17] vbat/3
0, // [18] vref
0,
0, // [0] vssa ADC 2
GPIO('A', 0), // [1]
GPIO('A', 1), // [2]
GPIO('A', 6), // [3]
GPIO('A', 7), // [4]
GPIO('C', 4), // [5]
GPIO('C', 0), // [6]
GPIO('C', 1), // [7]
GPIO('C', 2), // [8]
GPIO('C', 3), // [9]
GPIO('F', 1), // [10]
GPIO('C', 5), // [11]
GPIO('B', 2), // [12]
GPIO('A', 5), // [13]
GPIO('B', 11), // [14]
GPIO('B', 15), // [15]
0, // [16] opamp
GPIO('A', 4), // [17]
0, // [18] opamp
#else // stm32l4
0, // vref
GPIO('C', 0), // ADC12_IN1 .. 16
GPIO('C', 1),
GPIO('C', 2),
GPIO('C', 3),
GPIO('A', 0),
GPIO('A', 1),
GPIO('A', 2),
GPIO('A', 3),
GPIO('A', 4),
GPIO('A', 5),
GPIO('A', 6),
GPIO('A', 7),
GPIO('C', 4),
GPIO('C', 5),
GPIO('B', 0),
GPIO('B', 1),
ADC_TEMPERATURE_PIN, // temp
0, // vbat
#endif
};
// ADC timing:
// ADC clock=30Mhz, Tconv=6.5, Tsamp=64.5, total=2.3666us*OVERSAMPLES
struct gpio_adc
gpio_adc_setup(uint32_t pin)
{
// Find pin in adc_pins table
int chan;
for (chan=0; ; chan++) {
if (chan >= ARRAY_SIZE(adc_pins))
shutdown("Not a valid ADC pin");
if (adc_pins[chan] == pin)
break;
}
// Determine which ADC block to use, enable peripheral clock
// (SYSCLK 480Mhz) /HPRE(2) /CKMODE divider(4) /additional divider(2)
// (ADC clock 30Mhz)
ADC_TypeDef *adc;
ADC_Common_TypeDef *adc_common;
#ifdef ADC3
if (chan >= 2 * ADCIN_BANK_SIZE){
chan -= 2 * ADCIN_BANK_SIZE;
adc = ADC3;
adc_common = ADC3_COMMON;
if (!is_enabled_pclock(ADC3_BASE)) {
enable_pclock(ADC3_BASE);
}
} else
#endif
#ifdef ADC2
if (chan >= ADCIN_BANK_SIZE){
chan -= ADCIN_BANK_SIZE;
adc = ADC2;
adc_common = ADC12_COMMON;
RCC_AHBENR_ADC |= RCC_AHBENR_ADCEN;
} else
#endif
{
adc = ADC1;
adc_common = ADC12_COMMON;
RCC_AHBENR_ADC |= RCC_AHBENR_ADCEN;
}
MODIFY_REG(adc_common->CCR, ADC_CCR_CKMODE_Msk,
ADC_CKMODE << ADC_CCR_CKMODE_Pos);
// Enable the ADC
if (!(adc->CR & ADC_CR_ADEN)) {
// Pwr
// Exit deep power down
MODIFY_REG(adc->CR, ADC_CR_DEEPPWD_Msk, 0);
// Switch on voltage regulator
adc->CR |= ADC_CR_ADVREGEN;
// Wait for voltage regulator to stabilize
uint32_t end = timer_read_time() + timer_from_us(20);
while (timer_is_before(timer_read_time(), end))
;
// Set Boost mode for 25Mhz < ADC clock <= 50Mhz
#ifdef ADC_CR_BOOST
MODIFY_REG(adc->CR, ADC_CR_BOOST_Msk, 0b11 << ADC_CR_BOOST_Pos);
#endif
// Calibration
// Set calibration mode to Single ended (not differential)
MODIFY_REG(adc->CR, ADC_CR_ADCALDIF_Msk, 0);
// Enable linearity calibration
#ifdef ADC_CR_ADCALLIN
MODIFY_REG(adc->CR, ADC_CR_ADCALLIN_Msk, ADC_CR_ADCALLIN);
#endif
// Start the calibration
MODIFY_REG(adc->CR, ADC_CR_ADCAL_Msk, ADC_CR_ADCAL);
while(adc->CR & ADC_CR_ADCAL)
;
// Enable ADC
// "Clear the ADRDY bit in the ADC_ISR register by writing ‘1’"
adc->ISR |= ADC_ISR_ADRDY;
adc->ISR; // Dummy read to make sure write is flushed
adc->CR |= ADC_CR_ADEN;
while(!(adc->ISR & ADC_ISR_ADRDY))
;
// Set 64.5 ADC clock cycles sample time for every channel
// (Reference manual pg.940)
uint32_t aticks = ADC_ATICKS;
// Channel 0-9
adc->SMPR1 = (aticks | (aticks << 3) | (aticks << 6)
| (aticks << 9) | (aticks << 12) | (aticks << 15)
| (aticks << 18) | (aticks << 21) | (aticks << 24)
| (aticks << 27));
// Channel 10-19
adc->SMPR2 = (aticks | (aticks << 3) | (aticks << 6)
| (aticks << 9) | (aticks << 12) | (aticks << 15)
| (aticks << 18) | (aticks << 21) | (aticks << 24)
| (aticks << 27));
// The stm32h7 chips need to be set to 12bit samples
#if CONFIG_MACH_STM32H7
if (!(CONFIG_MACH_STM32H723 && adc == ADC3))
adc->CFGR = ADC_CFGR_JQDIS | (0b110 << ADC_CFGR_RES_Pos);
#endif
}
if (pin == ADC_TEMPERATURE_PIN) {
adc_common->CCR |= ADC_CCR_TSEN;
} else {
gpio_peripheral(pin, GPIO_ANALOG, 0);
}
// Preselect (connect) channel
#ifdef ADC_PCSEL_PCSEL
adc->PCSEL |= (1 << chan);
#endif
return (struct gpio_adc){ .adc = adc, .chan = chan };
}
// Try to sample a value. Returns zero if sample ready, otherwise
// returns the number of clock ticks the caller should wait before
// retrying this function.
uint32_t
gpio_adc_sample(struct gpio_adc g)
{
ADC_TypeDef *adc = g.adc;
uint32_t cr = adc->CR;
if (cr & ADC_CR_ADSTART)
goto need_delay;
if (adc->ISR & ADC_ISR_EOC) {
if (adc->SQR1 == (g.chan << ADC_SQR1_SQ1_Pos))
return 0;
goto need_delay;
}
// Start sample
adc->SQR1 = (g.chan << ADC_SQR1_SQ1_Pos);
adc->CR = cr | ADC_CR_ADSTART;
need_delay:
return timer_from_us(20);
}
// Read a value; use only after gpio_adc_sample() returns zero
uint16_t
gpio_adc_read(struct gpio_adc g)
{
ADC_TypeDef *adc = g.adc;
return adc->DR;
}
// Cancel a sample that may have been started with gpio_adc_sample()
void
gpio_adc_cancel_sample(struct gpio_adc g)
{
ADC_TypeDef *adc = g.adc;
irqstatus_t flag = irq_save();
if (adc->SQR1 == (g.chan << ADC_SQR1_SQ1_Pos)) {
uint32_t cr = adc->CR;
if (cr & ADC_CR_ADSTART)
adc->CR = (cr & ~ADC_CR_ADSTART) | ADC_CR_ADSTP;
if (adc->ISR & ADC_ISR_EOC)
gpio_adc_read(g);
}
irq_restore(flag);
}
|