Merge pull request #11297 from SteveCEvans/baro_state
[betaflight.git] / src / main / drivers / adc_stm32h7xx.c
blob0069859a961da233fa21328bc86ab7ee63c75fc7
1 /*
2 * This file is part of Cleanflight and Betaflight.
4 * Cleanflight and Betaflight are free software. You can redistribute
5 * this software and/or modify this software under the terms of the
6 * GNU General Public License as published by the Free Software
7 * Foundation, either version 3 of the License, or (at your option)
8 * any later version.
10 * Cleanflight and Betaflight are distributed in the hope that they
11 * will be useful, but WITHOUT ANY WARRANTY; without even the implied
12 * warranty of MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.
13 * See the GNU General Public License for more details.
15 * You should have received a copy of the GNU General Public License
16 * along with this software.
18 * If not, see <http://www.gnu.org/licenses/>.
21 #include <stdbool.h>
22 #include <stdint.h>
23 #include <string.h>
25 #include "platform.h"
27 #ifdef USE_ADC
29 #include "build/debug.h"
31 #include "drivers/dma_reqmap.h"
32 #include "drivers/io.h"
33 #include "drivers/io_impl.h"
34 #include "drivers/rcc.h"
35 #include "drivers/resource.h"
36 #include "drivers/dma.h"
38 #include "drivers/sensor.h"
40 #include "drivers/adc.h"
41 #include "drivers/adc_impl.h"
43 #include "pg/adc.h"
45 #ifndef ADC1_DMA_STREAM
46 #define ADC1_DMA_STREAM NULL
47 #endif
48 #ifndef ADC2_DMA_STREAM
49 #define ADC2_DMA_STREAM NULL
50 #endif
51 #ifndef ADC3_DMA_STREAM
52 #define ADC3_DMA_STREAM NULL
53 #endif
55 const adcDevice_t adcHardware[ADCDEV_COUNT] = {
57 .ADCx = ADC1,
58 .rccADC = RCC_AHB1(ADC12),
59 #if !defined(USE_DMA_SPEC)
60 .dmaResource = (dmaResource_t *)ADC1_DMA_STREAM,
61 .channel = DMA_REQUEST_ADC1,
62 #endif
64 { .ADCx = ADC2,
65 .rccADC = RCC_AHB1(ADC12),
66 #if !defined(USE_DMA_SPEC)
67 .dmaResource = (dmaResource_t *)ADC2_DMA_STREAM,
68 .channel = DMA_REQUEST_ADC2,
69 #endif
71 #if !(defined(STM32H7A3xx) || defined(STM32H7A3xxQ))
72 // ADC3 is not available on all H7 MCUs, e.g. H7A3
73 // On H743 and H750, ADC3 can be serviced by BDMA also, but we settle for DMA1 or 2 (for now).
75 .ADCx = ADC3,
76 .rccADC = RCC_AHB4(ADC3),
77 #if !defined(USE_DMA_SPEC)
78 .dmaResource = (dmaResource_t *)ADC3_DMA_STREAM,
79 .channel = DMA_REQUEST_ADC3,
80 #endif
82 #endif // ADC3
85 adcDevice_t adcDevice[ADCDEV_COUNT];
87 #if defined(STM32H743xx) || defined(STM32H750xx) || defined(STM32H723xx) || defined(STM32H725xx) || defined(STM32H730xx)
88 #define ADC_DEVICE_FOR_INTERNAL ADC_DEVICES_3
89 #elif defined(STM32H7A3xx) || defined(STM32H7A3xxQ)
90 #define ADC_DEVICE_FOR_INTERNAL ADC_DEVICES_2
91 #else
92 #error Unknown MCU
93 #endif
95 /* note these could be packed up for saving space */
96 const adcTagMap_t adcTagMap[] = {
97 #ifdef USE_ADC_INTERNAL
98 // Pseudo entries for internal sensor.
99 // Keep these at the beginning for easy indexing by ADC_TAG_MAP_{VREFINT,TEMPSENSOR}
100 #define ADC_TAG_MAP_VREFINT 0
101 #define ADC_TAG_MAP_TEMPSENSOR 1
102 #define ADC_TAG_MAP_VBAT4 2
104 #if defined(STM32H723xx) || defined(STM32H725xx) || defined(STM32H730xx) // RM0468 Rev 2 Table 240. ADC interconnection
105 { DEFIO_TAG_E__NONE, ADC_DEVICE_FOR_INTERNAL, ADC_CHANNEL_VREFINT, 18 }, // 18 VREFINT
106 { DEFIO_TAG_E__NONE, ADC_DEVICE_FOR_INTERNAL, ADC_CHANNEL_TEMPSENSOR, 17 }, // 17 VSENSE
107 { DEFIO_TAG_E__NONE, ADC_DEVICE_FOR_INTERNAL, ADC_CHANNEL_VBAT, 16 }, // 16 VBAT/4
108 #elif defined(STM32H743xx) || defined(STM32H750xx) // RM0433 Rev 7 Table 205. ADC interconnection
109 { DEFIO_TAG_E__NONE, ADC_DEVICE_FOR_INTERNAL, ADC_CHANNEL_VREFINT, 19 }, // 19 VREFINT
110 { DEFIO_TAG_E__NONE, ADC_DEVICE_FOR_INTERNAL, ADC_CHANNEL_TEMPSENSOR, 18 }, // 18 VSENSE
111 { DEFIO_TAG_E__NONE, ADC_DEVICE_FOR_INTERNAL, ADC_CHANNEL_VBAT, 17 }, // 17 VBAT/4
112 #elif defined(STM32H7A3xx) || defined(STM32H7A3xxQ) // RM0455 Rev 5 187. ADC interconnection
113 { DEFIO_TAG_E__NONE, ADC_DEVICE_FOR_INTERNAL, ADC_CHANNEL_VREFINT, 19 }, // 19 VREFINT
114 { DEFIO_TAG_E__NONE, ADC_DEVICE_FOR_INTERNAL, ADC_CHANNEL_TEMPSENSOR, 18 }, // 18 VSENSE
115 { DEFIO_TAG_E__NONE, ADC_DEVICE_FOR_INTERNAL, ADC_CHANNEL_VBAT, 17 }, // 17 VBAT/4
116 #elif
117 #error MCU not defined
118 #endif
120 #endif // USE_ADC_INTERNAL
122 #if defined(STM32H7A3xx) || defined(STM32H7A3xxQ)
123 // See DS13195 Rev 6 Page 51/52
124 { DEFIO_TAG_E__PC0, ADC_DEVICES_12, ADC_CHANNEL_10, 10 },
125 { DEFIO_TAG_E__PC1, ADC_DEVICES_12, ADC_CHANNEL_11, 11 },
126 { DEFIO_TAG_E__PC2, ADC_DEVICES_12, ADC_CHANNEL_12, 0 },
127 { DEFIO_TAG_E__PC3, ADC_DEVICES_12, ADC_CHANNEL_13, 1 },
128 #else
129 { DEFIO_TAG_E__PC0, ADC_DEVICES_123, ADC_CHANNEL_10, 10 },
130 { DEFIO_TAG_E__PC1, ADC_DEVICES_123, ADC_CHANNEL_11, 11 },
131 { DEFIO_TAG_E__PC2, ADC_DEVICES_3, ADC_CHANNEL_0, 0 },
132 { DEFIO_TAG_E__PC3, ADC_DEVICES_3, ADC_CHANNEL_1, 1 },
133 #endif
134 { DEFIO_TAG_E__PC4, ADC_DEVICES_12, ADC_CHANNEL_4, 4 },
135 { DEFIO_TAG_E__PC5, ADC_DEVICES_12, ADC_CHANNEL_8, 8 },
136 { DEFIO_TAG_E__PB0, ADC_DEVICES_12, ADC_CHANNEL_9, 9 },
137 { DEFIO_TAG_E__PB1, ADC_DEVICES_12, ADC_CHANNEL_5, 5 },
138 { DEFIO_TAG_E__PA0, ADC_DEVICES_1, ADC_CHANNEL_16, 16 },
139 { DEFIO_TAG_E__PA1, ADC_DEVICES_1, ADC_CHANNEL_17, 17 },
140 { DEFIO_TAG_E__PA2, ADC_DEVICES_12, ADC_CHANNEL_14, 14 },
141 { DEFIO_TAG_E__PA3, ADC_DEVICES_12, ADC_CHANNEL_15, 15 },
142 { DEFIO_TAG_E__PA4, ADC_DEVICES_12, ADC_CHANNEL_18, 18 },
143 { DEFIO_TAG_E__PA5, ADC_DEVICES_12, ADC_CHANNEL_19, 19 },
144 { DEFIO_TAG_E__PA6, ADC_DEVICES_12, ADC_CHANNEL_3, 3 },
145 { DEFIO_TAG_E__PA7, ADC_DEVICES_12, ADC_CHANNEL_7, 7 },
147 #if 0
148 // Inputs available for packages larger than LQFP144
149 { DEFIO_TAG_E__PF3, ADC_DEVICES_3, ADC_CHANNEL_5, 5 },
150 { DEFIO_TAG_E__PF4, ADC_DEVICES_3, ADC_CHANNEL_9, 9 },
151 { DEFIO_TAG_E__PF5, ADC_DEVICES_3, ADC_CHANNEL_4, 4 },
152 { DEFIO_TAG_E__PF6, ADC_DEVICES_3, ADC_CHANNEL_8, 8 },
153 { DEFIO_TAG_E__PF7, ADC_DEVICES_3, ADC_CHANNEL_3, 3 },
154 { DEFIO_TAG_E__PF8, ADC_DEVICES_3, ADC_CHANNEL_7, 7 },
155 { DEFIO_TAG_E__PF9, ADC_DEVICES_3, ADC_CHANNEL_2, 2 },
156 { DEFIO_TAG_E__PF10, ADC_DEVICES_3, ADC_CHANNEL_6, 6 },
157 { DEFIO_TAG_E__PF11, ADC_DEVICES_1, ADC_CHANNEL_2, 2 },
158 { DEFIO_TAG_E__PF12, ADC_DEVICES_1, ADC_CHANNEL_6, 6 },
159 { DEFIO_TAG_E__PF13, ADC_DEVICES_2, ADC_CHANNEL_2, 2 },
160 { DEFIO_TAG_E__PF14, ADC_DEVICES_2, ADC_CHANNEL_6, 6 },
161 #endif
164 // Translate rank number x to ADC_REGULAR_RANK_x (Note that array index is 0-origin)
166 #define RANK(n) ADC_REGULAR_RANK_ ## n
168 static uint32_t adcRegularRankMap[] = {
169 RANK(1),
170 RANK(2),
171 RANK(3),
172 RANK(4),
173 RANK(5),
174 RANK(6),
175 RANK(7),
176 RANK(8),
177 RANK(9),
178 RANK(10),
179 RANK(11),
180 RANK(12),
181 RANK(13),
182 RANK(14),
183 RANK(15),
184 RANK(16),
187 #undef RANK
189 static void errorHandler(void) { while (1) { } }
191 // Note on sampling time.
192 // Temperature sensor has minimum sample time of 9us.
193 // With prescaler = 4 at 200MHz (AHB1), fADC = 50MHz (tcycle = 0.02us), 9us = 450cycles < 810
195 void adcInitDevice(adcDevice_t *adcdev, int channelCount)
197 ADC_HandleTypeDef *hadc = &adcdev->ADCHandle; // For clarity
199 hadc->Instance = adcdev->ADCx;
201 // DeInit is done in adcInit().
203 hadc->Init.ClockPrescaler = ADC_CLOCK_SYNC_PCLK_DIV4;
204 hadc->Init.Resolution = ADC_RESOLUTION_12B;
205 hadc->Init.ScanConvMode = ENABLE; // Works with single channel, too
206 hadc->Init.EOCSelection = ADC_EOC_SINGLE_CONV;
207 hadc->Init.LowPowerAutoWait = DISABLE;
208 hadc->Init.ContinuousConvMode = ENABLE;
209 hadc->Init.NbrOfConversion = channelCount;
210 hadc->Init.DiscontinuousConvMode = DISABLE;
211 hadc->Init.NbrOfDiscConversion = 1; // Don't care
212 hadc->Init.ExternalTrigConv = ADC_SOFTWARE_START;
213 hadc->Init.ExternalTrigConvEdge = ADC_EXTERNALTRIGCONVEDGE_NONE; // Don't care
215 // Enable circular DMA.
216 // ADC3 of H72X and H73X has a special way of doing this.
217 #if defined(STM32H723xx) || defined(STM32H725xx) || defined(STM32H730xx)
218 if (adcdev->ADCx == ADC3) {
219 hadc->Init.DMAContinuousRequests = ENABLE;
220 } else
221 #else
223 hadc->Init.ConversionDataManagement = ADC_CONVERSIONDATA_DMA_CIRCULAR;
225 #endif
227 hadc->Init.Overrun = ADC_OVR_DATA_OVERWRITTEN;
228 hadc->Init.OversamplingMode = DISABLE;
230 // Initialize this ADC peripheral
232 if (HAL_ADC_Init(hadc) != HAL_OK) {
233 errorHandler();
236 // Execute calibration
238 if (HAL_ADCEx_Calibration_Start(hadc, ADC_CALIB_OFFSET, ADC_SINGLE_ENDED) != HAL_OK) {
239 errorHandler();
243 int adcFindTagMapEntry(ioTag_t tag)
245 for (int i = 0; i < ADC_TAG_MAP_COUNT; i++) {
246 if (adcTagMap[i].tag == tag) {
247 return i;
250 return -1;
253 // H743, H750 and H7A3 seems to use 16-bit precision value,
254 // while H723, H725 and H730 seems to use 12-bit precision value.
255 #if defined(STM32H743xx) || defined(STM32H750xx) || defined(STM32H7A3xx) || defined(STM32H7A3xxQ)
256 #define VREFINT_CAL_SHIFT 4
257 #elif defined(STM32H723xx) || defined(STM32H725xx) || defined(STM32H730xx)
258 #define VREFINT_CAL_SHIFT 0
259 #else
260 #error Unknown MCU
261 #endif
263 void adcInitCalibrationValues(void)
265 adcVREFINTCAL = *VREFINT_CAL_ADDR >> VREFINT_CAL_SHIFT;
266 adcTSCAL1 = *TEMPSENSOR_CAL1_ADDR >> VREFINT_CAL_SHIFT;
267 adcTSCAL2 = *TEMPSENSOR_CAL2_ADDR >> VREFINT_CAL_SHIFT;
268 adcTSSlopeK = (TEMPSENSOR_CAL2_TEMP - TEMPSENSOR_CAL1_TEMP) * 1000 / (adcTSCAL2 - adcTSCAL1);
271 // ADC conversion result DMA buffer
272 // Need this separate from the main adcValue[] array, because channels are numbered
273 // by ADC instance order that is different from ADC_xxx numbering.
275 static volatile DMA_RAM uint16_t adcConversionBuffer[ADC_CHANNEL_COUNT] __attribute__((aligned(32)));
277 void adcInit(const adcConfig_t *config)
279 memset(adcOperatingConfig, 0, sizeof(adcOperatingConfig));
280 memcpy(adcDevice, adcHardware, sizeof(adcDevice));
282 if (config->vbat.enabled) {
283 adcOperatingConfig[ADC_BATTERY].tag = config->vbat.ioTag;
284 adcOperatingConfig[ADC_BATTERY].adcDevice = config->vbat.device;
287 if (config->rssi.enabled) {
288 adcOperatingConfig[ADC_RSSI].tag = config->rssi.ioTag; //RSSI_ADC_CHANNEL;
289 adcOperatingConfig[ADC_RSSI].adcDevice = config->rssi.device;
292 if (config->external1.enabled) {
293 adcOperatingConfig[ADC_EXTERNAL1].tag = config->external1.ioTag; //EXTERNAL1_ADC_CHANNEL;
294 adcOperatingConfig[ADC_EXTERNAL1].adcDevice = config->external1.device;
297 if (config->current.enabled) {
298 adcOperatingConfig[ADC_CURRENT].tag = config->current.ioTag; //CURRENT_METER_ADC_CHANNEL;
299 adcOperatingConfig[ADC_CURRENT].adcDevice = config->current.device;
302 #ifdef USE_ADC_INTERNAL
303 adcInitCalibrationValues();
304 #endif
306 for (int i = 0; i < ADC_CHANNEL_COUNT; i++) {
307 int map;
308 int dev;
310 #ifdef USE_ADC_INTERNAL
311 if (i == ADC_TEMPSENSOR) {
312 map = ADC_TAG_MAP_TEMPSENSOR;
313 dev = ffs(adcTagMap[map].devices) - 1;
314 } else if (i == ADC_VREFINT) {
315 map = ADC_TAG_MAP_VREFINT;
316 dev = ffs(adcTagMap[map].devices) - 1;
317 } else if (i == ADC_VBAT4) {
318 map = ADC_TAG_MAP_VBAT4;
319 dev = ffs(adcTagMap[map].devices) - 1;
320 } else {
321 #else
323 #endif
324 dev = ADC_CFG_TO_DEV(adcOperatingConfig[i].adcDevice);
326 if (!adcOperatingConfig[i].tag) {
327 continue;
330 map = adcFindTagMapEntry(adcOperatingConfig[i].tag);
331 if (map < 0) {
332 continue;
335 // Found a tag map entry for this input pin
336 // Find an ADC device that can handle this input pin
338 bool useConfiguredDevice = (dev != ADCINVALID) && (adcTagMap[map].devices & (1 << dev));
340 if (!useConfiguredDevice) {
341 // If the ADC was configured to use a specific device, but that device was not active, then try and find another active instance that works for the pin.
343 for (dev = 0; dev < ADCDEV_COUNT; dev++) {
344 if (!adcDevice[dev].ADCx
345 #ifndef USE_DMA_SPEC
346 || !adcDevice[dev].dmaResource
347 #endif
349 // Instance not activated
350 continue;
352 if (adcTagMap[map].devices & (1 << dev)) {
353 // Found an activated ADC instance for this input pin
354 break;
358 if (dev == ADCDEV_COUNT) {
359 // No valid device found, go next channel.
360 continue;
365 // At this point, map is an entry for the input pin and dev is a valid ADCx for the pin for input i
367 adcOperatingConfig[i].adcDevice = dev;
368 adcOperatingConfig[i].adcChannel = adcTagMap[map].channel;
369 adcOperatingConfig[i].sampleTime = ADC_SAMPLETIME_810CYCLES_5;
370 adcOperatingConfig[i].enabled = true;
372 adcDevice[dev].channelBits |= (1 << adcTagMap[map].channelOrdinal);
374 // Configure a pin for ADC
375 if (adcOperatingConfig[i].tag) {
376 IOInit(IOGetByTag(adcOperatingConfig[i].tag), OWNER_ADC_BATT + i, 0);
377 IOConfigGPIO(IOGetByTag(adcOperatingConfig[i].tag), IO_CONFIG(GPIO_MODE_ANALOG, 0, GPIO_NOPULL));
381 // DeInit ADCx with inputs
382 // We have to batch call DeInit() for all devices as DeInit() initializes ADCx_COMMON register.
384 for (int dev = 0; dev < ADCDEV_COUNT; dev++) {
385 adcDevice_t *adc = &adcDevice[dev];
387 if (!(adc->ADCx && adc->channelBits)) {
388 continue;
391 adc->ADCHandle.Instance = adc->ADCx;
393 if (HAL_ADC_DeInit(&adc->ADCHandle) != HAL_OK) {
394 // ADC de-initialization Error
395 errorHandler();
399 // Configure ADCx with inputs
401 int dmaBufferIndex = 0;
403 for (int dev = 0; dev < ADCDEV_COUNT; dev++) {
404 adcDevice_t *adc = &adcDevice[dev];
406 if (!adc->channelBits) {
407 continue;
410 RCC_ClockCmd(adc->rccADC, ENABLE);
412 #ifdef USE_ADC3_DIRECT_HAL_INIT
413 // XXX (Only) ADC3 (sometimes) fails to self calibrate without these? Need to verify
415 // ADC Periph clock enable
416 __HAL_RCC_ADC3_CLK_ENABLE();
418 // ADC Periph interface clock configuration
419 __HAL_RCC_ADC_CONFIG(RCC_ADCCLKSOURCE_CLKP);
420 #endif
422 int configuredAdcChannels = BITCOUNT(adc->channelBits);
424 adcInitDevice(adc, configuredAdcChannels);
426 // Configure channels
428 int rank = 0;
430 for (int adcChan = 0; adcChan < ADC_CHANNEL_COUNT; adcChan++) {
432 if (!adcOperatingConfig[adcChan].enabled) {
433 continue;
436 if (adcOperatingConfig[adcChan].adcDevice != dev) {
437 continue;
440 adcOperatingConfig[adcChan].dmaIndex = dmaBufferIndex++;
442 ADC_ChannelConfTypeDef sConfig;
444 sConfig.Channel = adcOperatingConfig[adcChan].adcChannel; /* Sampled channel number */
445 sConfig.Rank = adcRegularRankMap[rank++]; /* Rank of sampled channel number ADCx_CHANNEL */
446 sConfig.SamplingTime = ADC_SAMPLETIME_387CYCLES_5; /* Sampling time (number of clock cycles unit) */
447 sConfig.SingleDiff = ADC_SINGLE_ENDED; /* Single-ended input channel */
448 sConfig.OffsetNumber = ADC_OFFSET_NONE; /* No offset subtraction */
449 sConfig.Offset = 0; /* Parameter discarded because offset correction is disabled */
451 if (HAL_ADC_ConfigChannel(&adc->ADCHandle, &sConfig) != HAL_OK) {
452 errorHandler();
456 // Configure DMA for this ADC peripheral
458 #ifdef USE_DMA_SPEC
459 const dmaChannelSpec_t *dmaSpec = dmaGetChannelSpecByPeripheral(DMA_PERIPH_ADC, dev, config->dmaopt[dev]);
460 dmaIdentifier_e dmaIdentifier = dmaGetIdentifier(dmaSpec->ref);
462 if (!dmaSpec || !dmaAllocate(dmaIdentifier, OWNER_ADC, RESOURCE_INDEX(dev))) {
463 return;
466 adc->DmaHandle.Instance = dmaSpec->ref;
467 adc->DmaHandle.Init.Request = dmaSpec->channel;
468 #else
469 dmaIdentifier_e dmaIdentifier = dmaGetIdentifier(adc->dmaResource);
471 if (!dmaAllocate(dmaIdentifier, OWNER_ADC, RESOURCE_INDEX(dev))) {
472 return;
475 adc->DmaHandle.Instance = (DMA_ARCH_TYPE *)adc->dmaResource;
476 adc->DmaHandle.Init.Request = adc->channel;
477 #endif
478 adc->DmaHandle.Init.Direction = DMA_PERIPH_TO_MEMORY;
479 adc->DmaHandle.Init.PeriphInc = DMA_PINC_DISABLE;
480 adc->DmaHandle.Init.MemInc = DMA_MINC_ENABLE;
481 adc->DmaHandle.Init.PeriphDataAlignment = DMA_PDATAALIGN_HALFWORD;
482 adc->DmaHandle.Init.MemDataAlignment = DMA_MDATAALIGN_HALFWORD;
483 adc->DmaHandle.Init.Mode = DMA_CIRCULAR;
484 adc->DmaHandle.Init.Priority = DMA_PRIORITY_MEDIUM;
486 // Deinitialize & Initialize the DMA for new transfer
488 // dmaEnable must be called before calling HAL_DMA_Init,
489 // to enable clock for associated DMA if not already done so.
490 dmaEnable(dmaIdentifier);
492 HAL_DMA_DeInit(&adc->DmaHandle);
493 HAL_DMA_Init(&adc->DmaHandle);
495 // Associate the DMA handle
497 __HAL_LINKDMA(&adc->ADCHandle, DMA_Handle, adc->DmaHandle);
499 #ifdef USE_ADC_INTERRUPT
500 // XXX No interrupt used, so we can skip this.
501 // If interrupt is needed in any case, use dmaXXX facility instead,
502 // using dmaIdentifier obtained above.
504 // NVIC configuration for DMA Input data interrupt
506 HAL_NVIC_SetPriority(DMA1_Stream1_IRQn, 1, 0);
507 HAL_NVIC_EnableIRQ(DMA1_Stream1_IRQn);
508 #endif
511 // Start channels.
512 // This must be done after channel configuration is complete, as HAL_ADC_ConfigChannel
513 // throws an error when configuring internal channels if ADC1 or ADC2 are already enabled.
515 dmaBufferIndex = 0;
517 for (int dev = 0; dev < ADCDEV_COUNT; dev++) {
519 adcDevice_t *adc = &adcDevice[dev];
521 if (!adc->channelBits) {
522 continue;
525 // Start conversion in DMA mode
527 if (HAL_ADC_Start_DMA(&adc->ADCHandle, (uint32_t *)&adcConversionBuffer[dmaBufferIndex], BITCOUNT(adc->channelBits)) != HAL_OK) {
528 errorHandler();
531 dmaBufferIndex += BITCOUNT(adc->channelBits);
535 void adcGetChannelValues(void)
537 // Transfer values in conversion buffer into adcValues[]
538 // Cache coherency should be maintained by MPU facility
540 for (int i = 0; i < ADC_CHANNEL_INTERNAL_FIRST_ID; i++) {
541 if (adcOperatingConfig[i].enabled) {
542 adcValues[adcOperatingConfig[i].dmaIndex] = adcConversionBuffer[adcOperatingConfig[i].dmaIndex];
547 #ifdef USE_ADC_INTERNAL
549 bool adcInternalIsBusy(void)
551 return false;
554 void adcInternalStartConversion(void)
556 return;
559 uint16_t adcInternalRead(int channel)
561 int dmaIndex = adcOperatingConfig[channel].dmaIndex;
563 return adcConversionBuffer[dmaIndex];
566 uint16_t adcInternalReadVrefint(void)
568 uint16_t value = adcInternalRead(ADC_VREFINT);
569 return value;
572 uint16_t adcInternalReadTempsensor(void)
574 uint16_t value = adcInternalRead(ADC_TEMPSENSOR);
575 return value;
577 #endif // USE_ADC_INTERNAL
579 #endif // USE_ADC