Merge pull request #11494 from haslinghuis/dshot_gpio
[betaflight.git] / lib / main / STM32G4 / Drivers / STM32G4xx_HAL_Driver / Src / stm32g4xx_hal_adc.c
blob1034b5ed87d93151898e389d70d5faa130196f15
1 /**
2 ******************************************************************************
3 * @file stm32g4xx_hal_adc.c
4 * @author MCD Application Team
5 * @brief This file provides firmware functions to manage the following
6 * functionalities of the Analog to Digital Convertor (ADC)
7 * peripheral:
8 * + Initialization and de-initialization functions
9 * ++ Initialization and Configuration of ADC
10 * + Operation functions
11 * ++ Start, stop, get result of conversions of regular
12 * group, using 3 possible modes: polling, interruption or DMA.
13 * + Control functions
14 * ++ Channels configuration on regular group
15 * ++ Analog Watchdog configuration
16 * + State functions
17 * ++ ADC state machine management
18 * ++ Interrupts and flags management
19 * Other functions (extended functions) are available in file
20 * "stm32g4xx_hal_adc_ex.c".
22 @verbatim
23 ==============================================================================
24 ##### ADC peripheral features #####
25 ==============================================================================
26 [..]
27 (+) 12-bit, 10-bit, 8-bit or 6-bit configurable resolution.
29 (+) Interrupt generation at the end of regular conversion and in case of
30 analog watchdog or overrun events.
32 (+) Single and continuous conversion modes.
34 (+) Scan mode for conversion of several channels sequentially.
36 (+) Data alignment with in-built data coherency.
38 (+) Programmable sampling time (channel wise)
40 (+) External trigger (timer or EXTI) with configurable polarity
42 (+) DMA request generation for transfer of conversions data of regular group.
44 (+) Configurable delay between conversions in Dual interleaved mode.
46 (+) ADC channels selectable single/differential input.
48 (+) ADC offset shared on 4 offset instances.
49 (+) ADC gain compensation
51 (+) ADC calibration
53 (+) ADC conversion of regular group.
55 (+) ADC supply requirements: 1.62 V to 3.6 V.
57 (+) ADC input range: from Vref- (connected to Vssa) to Vref+ (connected to
58 Vdda or to an external voltage reference).
61 ##### How to use this driver #####
62 ==============================================================================
63 [..]
65 *** Configuration of top level parameters related to ADC ***
66 ============================================================
67 [..]
69 (#) Enable the ADC interface
70 (++) As prerequisite, ADC clock must be configured at RCC top level.
72 (++) Two clock settings are mandatory:
73 (+++) ADC clock (core clock, also possibly conversion clock).
75 (+++) ADC clock (conversions clock).
76 Two possible clock sources: synchronous clock derived from AHB clock
77 or asynchronous clock derived from system clock or PLL (output divider P)
78 running up to 75MHz.
80 (+++) Example:
81 Into HAL_ADC_MspInit() (recommended code location) or with
82 other device clock parameters configuration:
83 (+++) __HAL_RCC_ADC_CLK_ENABLE(); (mandatory)
85 RCC_ADCCLKSOURCE_PLL enable: (optional: if asynchronous clock selected)
86 (+++) RCC_PeriphClkInitTypeDef RCC_PeriphClkInit;
87 (+++) PeriphClkInit.PeriphClockSelection = RCC_PERIPHCLK_ADC;
88 (+++) PeriphClkInit.AdcClockSelection = RCC_ADCCLKSOURCE_PLL;
89 (+++) HAL_RCCEx_PeriphCLKConfig(&PeriphClkInit);
91 (++) ADC clock source and clock prescaler are configured at ADC level with
92 parameter "ClockPrescaler" using function HAL_ADC_Init().
94 (#) ADC pins configuration
95 (++) Enable the clock for the ADC GPIOs
96 using macro __HAL_RCC_GPIOx_CLK_ENABLE()
97 (++) Configure these ADC pins in analog mode
98 using function HAL_GPIO_Init()
100 (#) Optionally, in case of usage of ADC with interruptions:
101 (++) Configure the NVIC for ADC
102 using function HAL_NVIC_EnableIRQ(ADCx_IRQn)
103 (++) Insert the ADC interruption handler function HAL_ADC_IRQHandler()
104 into the function of corresponding ADC interruption vector
105 ADCx_IRQHandler().
107 (#) Optionally, in case of usage of DMA:
108 (++) Configure the DMA (DMA channel, mode normal or circular, ...)
109 using function HAL_DMA_Init().
110 (++) Configure the NVIC for DMA
111 using function HAL_NVIC_EnableIRQ(DMAx_Channelx_IRQn)
112 (++) Insert the ADC interruption handler function HAL_ADC_IRQHandler()
113 into the function of corresponding DMA interruption vector
114 DMAx_Channelx_IRQHandler().
116 *** Configuration of ADC, group regular, channels parameters ***
117 ================================================================
118 [..]
120 (#) Configure the ADC parameters (resolution, data alignment, ...)
121 and regular group parameters (conversion trigger, sequencer, ...)
122 using function HAL_ADC_Init().
124 (#) Configure the channels for regular group parameters (channel number,
125 channel rank into sequencer, ..., into regular group)
126 using function HAL_ADC_ConfigChannel().
128 (#) Optionally, configure the analog watchdog parameters (channels
129 monitored, thresholds, ...)
130 using function HAL_ADC_AnalogWDGConfig().
132 *** Execution of ADC conversions ***
133 ====================================
134 [..]
136 (#) Optionally, perform an automatic ADC calibration to improve the
137 conversion accuracy
138 using function HAL_ADCEx_Calibration_Start().
140 (#) ADC driver can be used among three modes: polling, interruption,
141 transfer by DMA.
143 (++) ADC conversion by polling:
144 (+++) Activate the ADC peripheral and start conversions
145 using function HAL_ADC_Start()
146 (+++) Wait for ADC conversion completion
147 using function HAL_ADC_PollForConversion()
148 (+++) Retrieve conversion results
149 using function HAL_ADC_GetValue()
150 (+++) Stop conversion and disable the ADC peripheral
151 using function HAL_ADC_Stop()
153 (++) ADC conversion by interruption:
154 (+++) Activate the ADC peripheral and start conversions
155 using function HAL_ADC_Start_IT()
156 (+++) Wait for ADC conversion completion by call of function
157 HAL_ADC_ConvCpltCallback()
158 (this function must be implemented in user program)
159 (+++) Retrieve conversion results
160 using function HAL_ADC_GetValue()
161 (+++) Stop conversion and disable the ADC peripheral
162 using function HAL_ADC_Stop_IT()
164 (++) ADC conversion with transfer by DMA:
165 (+++) Activate the ADC peripheral and start conversions
166 using function HAL_ADC_Start_DMA()
167 (+++) Wait for ADC conversion completion by call of function
168 HAL_ADC_ConvCpltCallback() or HAL_ADC_ConvHalfCpltCallback()
169 (these functions must be implemented in user program)
170 (+++) Conversion results are automatically transferred by DMA into
171 destination variable address.
172 (+++) Stop conversion and disable the ADC peripheral
173 using function HAL_ADC_Stop_DMA()
175 [..]
177 (@) Callback functions must be implemented in user program:
178 (+@) HAL_ADC_ErrorCallback()
179 (+@) HAL_ADC_LevelOutOfWindowCallback() (callback of analog watchdog)
180 (+@) HAL_ADC_ConvCpltCallback()
181 (+@) HAL_ADC_ConvHalfCpltCallback
183 *** Deinitialization of ADC ***
184 ============================================================
185 [..]
187 (#) Disable the ADC interface
188 (++) ADC clock can be hard reset and disabled at RCC top level.
189 (++) Hard reset of ADC peripherals
190 using macro __ADCx_FORCE_RESET(), __ADCx_RELEASE_RESET().
191 (++) ADC clock disable
192 using the equivalent macro/functions as configuration step.
193 (+++) Example:
194 Into HAL_ADC_MspDeInit() (recommended code location) or with
195 other device clock parameters configuration:
196 (+++) RCC_OscInitStructure.OscillatorType = RCC_OSCILLATORTYPE_HSI14;
197 (+++) RCC_OscInitStructure.HSI14State = RCC_HSI14_OFF; (if not used for system clock)
198 (+++) HAL_RCC_OscConfig(&RCC_OscInitStructure);
200 (#) ADC pins configuration
201 (++) Disable the clock for the ADC GPIOs
202 using macro __HAL_RCC_GPIOx_CLK_DISABLE()
204 (#) Optionally, in case of usage of ADC with interruptions:
205 (++) Disable the NVIC for ADC
206 using function HAL_NVIC_EnableIRQ(ADCx_IRQn)
208 (#) Optionally, in case of usage of DMA:
209 (++) Deinitialize the DMA
210 using function HAL_DMA_Init().
211 (++) Disable the NVIC for DMA
212 using function HAL_NVIC_EnableIRQ(DMAx_Channelx_IRQn)
214 [..]
216 *** Callback registration ***
217 =============================================
218 [..]
220 The compilation flag USE_HAL_ADC_REGISTER_CALLBACKS, when set to 1,
221 allows the user to configure dynamically the driver callbacks.
222 Use Functions @ref HAL_ADC_RegisterCallback()
223 to register an interrupt callback.
224 [..]
226 Function @ref HAL_ADC_RegisterCallback() allows to register following callbacks:
227 (+) ConvCpltCallback : ADC conversion complete callback
228 (+) ConvHalfCpltCallback : ADC conversion DMA half-transfer callback
229 (+) LevelOutOfWindowCallback : ADC analog watchdog 1 callback
230 (+) ErrorCallback : ADC error callback
231 (+) InjectedConvCpltCallback : ADC group injected conversion complete callback
232 (+) InjectedQueueOverflowCallback : ADC group injected context queue overflow callback
233 (+) LevelOutOfWindow2Callback : ADC analog watchdog 2 callback
234 (+) LevelOutOfWindow3Callback : ADC analog watchdog 3 callback
235 (+) EndOfSamplingCallback : ADC end of sampling callback
236 (+) MspInitCallback : ADC Msp Init callback
237 (+) MspDeInitCallback : ADC Msp DeInit callback
238 This function takes as parameters the HAL peripheral handle, the Callback ID
239 and a pointer to the user callback function.
240 [..]
242 Use function @ref HAL_ADC_UnRegisterCallback to reset a callback to the default
243 weak function.
244 [..]
246 @ref HAL_ADC_UnRegisterCallback takes as parameters the HAL peripheral handle,
247 and the Callback ID.
248 This function allows to reset following callbacks:
249 (+) ConvCpltCallback : ADC conversion complete callback
250 (+) ConvHalfCpltCallback : ADC conversion DMA half-transfer callback
251 (+) LevelOutOfWindowCallback : ADC analog watchdog 1 callback
252 (+) ErrorCallback : ADC error callback
253 (+) InjectedConvCpltCallback : ADC group injected conversion complete callback
254 (+) InjectedQueueOverflowCallback : ADC group injected context queue overflow callback
255 (+) LevelOutOfWindow2Callback : ADC analog watchdog 2 callback
256 (+) LevelOutOfWindow3Callback : ADC analog watchdog 3 callback
257 (+) EndOfSamplingCallback : ADC end of sampling callback
258 (+) MspInitCallback : ADC Msp Init callback
259 (+) MspDeInitCallback : ADC Msp DeInit callback
260 [..]
262 By default, after the @ref HAL_ADC_Init() and when the state is @ref HAL_ADC_STATE_RESET
263 all callbacks are set to the corresponding weak functions:
264 examples @ref HAL_ADC_ConvCpltCallback(), @ref HAL_ADC_ErrorCallback().
265 Exception done for MspInit and MspDeInit functions that are
266 reset to the legacy weak functions in the @ref HAL_ADC_Init()/ @ref HAL_ADC_DeInit() only when
267 these callbacks are null (not registered beforehand).
268 [..]
270 If MspInit or MspDeInit are not null, the @ref HAL_ADC_Init()/ @ref HAL_ADC_DeInit()
271 keep and use the user MspInit/MspDeInit callbacks (registered beforehand) whatever the state.
272 [..]
274 Callbacks can be registered/unregistered in @ref HAL_ADC_STATE_READY state only.
275 Exception done MspInit/MspDeInit functions that can be registered/unregistered
276 in @ref HAL_ADC_STATE_READY or @ref HAL_ADC_STATE_RESET state,
277 thus registered (user) MspInit/DeInit callbacks can be used during the Init/DeInit.
278 [..]
280 Then, the user first registers the MspInit/MspDeInit user callbacks
281 using @ref HAL_ADC_RegisterCallback() before calling @ref HAL_ADC_DeInit()
282 or @ref HAL_ADC_Init() function.
283 [..]
285 When the compilation flag USE_HAL_ADC_REGISTER_CALLBACKS is set to 0 or
286 not defined, the callback registration feature is not available and all callbacks
287 are set to the corresponding weak functions.
289 @endverbatim
290 ******************************************************************************
291 * @attention
293 * <h2><center>&copy; Copyright (c) 2017 STMicroelectronics.
294 * All rights reserved.</center></h2>
296 * This software component is licensed by ST under BSD 3-Clause license,
297 * the "License"; You may not use this file except in compliance with the
298 * License. You may obtain a copy of the License at:
299 * opensource.org/licenses/BSD-3-Clause
301 ******************************************************************************
304 /* Includes ------------------------------------------------------------------*/
305 #include "stm32g4xx_hal.h"
307 /** @addtogroup STM32G4xx_HAL_Driver
308 * @{
311 /** @defgroup ADC ADC
312 * @brief ADC HAL module driver
313 * @{
316 #ifdef HAL_ADC_MODULE_ENABLED
318 /* Private typedef -----------------------------------------------------------*/
319 /* Private define ------------------------------------------------------------*/
321 /** @defgroup ADC_Private_Constants ADC Private Constants
322 * @{
325 #define ADC_CFGR_FIELDS_1 ((ADC_CFGR_RES | ADC_CFGR_ALIGN |\
326 ADC_CFGR_CONT | ADC_CFGR_OVRMOD |\
327 ADC_CFGR_DISCEN | ADC_CFGR_DISCNUM |\
328 ADC_CFGR_EXTEN | ADC_CFGR_EXTSEL)) /*!< ADC_CFGR fields of parameters that can be updated
329 when no regular conversion is on-going */
331 /* Timeout values for ADC operations (enable settling time, */
332 /* disable settling time, ...). */
333 /* Values defined to be higher than worst cases: low clock frequency, */
334 /* maximum prescalers. */
335 #define ADC_ENABLE_TIMEOUT (2UL) /*!< ADC enable time-out value */
336 #define ADC_DISABLE_TIMEOUT (2UL) /*!< ADC disable time-out value */
338 /* Timeout to wait for current conversion on going to be completed. */
339 /* Timeout fixed to longest ADC conversion possible, for 1 channel: */
340 /* - maximum sampling time (640.5 adc_clk) */
341 /* - ADC resolution (Tsar 12 bits= 12.5 adc_clk) */
342 /* - System clock / ADC clock <= 4096 (hypothesis of maximum clock ratio) */
343 /* - ADC oversampling ratio 256 */
344 /* Calculation: 653 * 4096 * 256 CPU clock cycles max */
345 /* Unit: cycles of CPU clock. */
346 #define ADC_CONVERSION_TIME_MAX_CPU_CYCLES (653UL * 4096UL * 256UL) /*!< ADC conversion completion time-out value */
350 * @}
353 /* Private macro -------------------------------------------------------------*/
354 /* Private variables ---------------------------------------------------------*/
355 /* Private function prototypes -----------------------------------------------*/
356 /* Exported functions --------------------------------------------------------*/
358 /** @defgroup ADC_Exported_Functions ADC Exported Functions
359 * @{
362 /** @defgroup ADC_Exported_Functions_Group1 Initialization and de-initialization functions
363 * @brief ADC Initialization and Configuration functions
365 @verbatim
366 ===============================================================================
367 ##### Initialization and de-initialization functions #####
368 ===============================================================================
369 [..] This section provides functions allowing to:
370 (+) Initialize and configure the ADC.
371 (+) De-initialize the ADC.
372 @endverbatim
373 * @{
377 * @brief Initialize the ADC peripheral and regular group according to
378 * parameters specified in structure "ADC_InitTypeDef".
379 * @note As prerequisite, ADC clock must be configured at RCC top level
380 * (refer to description of RCC configuration for ADC
381 * in header of this file).
382 * @note Possibility to update parameters on the fly:
383 * This function initializes the ADC MSP (HAL_ADC_MspInit()) only when
384 * coming from ADC state reset. Following calls to this function can
385 * be used to reconfigure some parameters of ADC_InitTypeDef
386 * structure on the fly, without modifying MSP configuration. If ADC
387 * MSP has to be modified again, HAL_ADC_DeInit() must be called
388 * before HAL_ADC_Init().
389 * The setting of these parameters is conditioned to ADC state.
390 * For parameters constraints, see comments of structure
391 * "ADC_InitTypeDef".
392 * @note This function configures the ADC within 2 scopes: scope of entire
393 * ADC and scope of regular group. For parameters details, see comments
394 * of structure "ADC_InitTypeDef".
395 * @note Parameters related to common ADC registers (ADC clock mode) are set
396 * only if all ADCs are disabled.
397 * If this is not the case, these common parameters setting are
398 * bypassed without error reporting: it can be the intended behaviour in
399 * case of update of a parameter of ADC_InitTypeDef on the fly,
400 * without disabling the other ADCs.
401 * @param hadc ADC handle
402 * @retval HAL status
404 HAL_StatusTypeDef HAL_ADC_Init(ADC_HandleTypeDef *hadc)
406 HAL_StatusTypeDef tmp_hal_status = HAL_OK;
407 uint32_t tmpCFGR;
408 uint32_t tmp_adc_reg_is_conversion_on_going;
409 __IO uint32_t wait_loop_index = 0UL;
410 uint32_t tmp_adc_is_conversion_on_going_regular;
411 uint32_t tmp_adc_is_conversion_on_going_injected;
413 /* Check ADC handle */
414 if (hadc == NULL)
416 return HAL_ERROR;
419 /* Check the parameters */
420 assert_param(IS_ADC_ALL_INSTANCE(hadc->Instance));
421 assert_param(IS_ADC_CLOCKPRESCALER(hadc->Init.ClockPrescaler));
422 assert_param(IS_ADC_RESOLUTION(hadc->Init.Resolution));
423 assert_param(IS_ADC_DATA_ALIGN(hadc->Init.DataAlign));
424 assert_param(IS_ADC_GAIN_COMPENSATION(hadc->Init.GainCompensation));
425 assert_param(IS_ADC_SCAN_MODE(hadc->Init.ScanConvMode));
426 assert_param(IS_FUNCTIONAL_STATE(hadc->Init.ContinuousConvMode));
427 assert_param(IS_ADC_EXTTRIG_EDGE(hadc->Init.ExternalTrigConvEdge));
428 assert_param(IS_ADC_EXTTRIG(hadc, hadc->Init.ExternalTrigConv));
429 assert_param(IS_ADC_SAMPLINGMODE(hadc->Init.SamplingMode));
430 assert_param(IS_FUNCTIONAL_STATE(hadc->Init.DMAContinuousRequests));
431 assert_param(IS_ADC_EOC_SELECTION(hadc->Init.EOCSelection));
432 assert_param(IS_ADC_OVERRUN(hadc->Init.Overrun));
433 assert_param(IS_FUNCTIONAL_STATE(hadc->Init.LowPowerAutoWait));
434 assert_param(IS_FUNCTIONAL_STATE(hadc->Init.OversamplingMode));
436 if (hadc->Init.ScanConvMode != ADC_SCAN_DISABLE)
438 assert_param(IS_ADC_REGULAR_NB_CONV(hadc->Init.NbrOfConversion));
439 assert_param(IS_FUNCTIONAL_STATE(hadc->Init.DiscontinuousConvMode));
441 if (hadc->Init.DiscontinuousConvMode == ENABLE)
443 assert_param(IS_ADC_REGULAR_DISCONT_NUMBER(hadc->Init.NbrOfDiscConversion));
447 /* DISCEN and CONT bits cannot be set at the same time */
448 assert_param(!((hadc->Init.DiscontinuousConvMode == ENABLE) && (hadc->Init.ContinuousConvMode == ENABLE)));
450 /* Actions performed only if ADC is coming from state reset: */
451 /* - Initialization of ADC MSP */
452 if (hadc->State == HAL_ADC_STATE_RESET)
454 #if (USE_HAL_ADC_REGISTER_CALLBACKS == 1)
455 /* Init the ADC Callback settings */
456 hadc->ConvCpltCallback = HAL_ADC_ConvCpltCallback; /* Legacy weak callback */
457 hadc->ConvHalfCpltCallback = HAL_ADC_ConvHalfCpltCallback; /* Legacy weak callback */
458 hadc->LevelOutOfWindowCallback = HAL_ADC_LevelOutOfWindowCallback; /* Legacy weak callback */
459 hadc->ErrorCallback = HAL_ADC_ErrorCallback; /* Legacy weak callback */
460 hadc->InjectedConvCpltCallback = HAL_ADCEx_InjectedConvCpltCallback; /* Legacy weak callback */
461 hadc->InjectedQueueOverflowCallback = HAL_ADCEx_InjectedQueueOverflowCallback; /* Legacy weak callback */
462 hadc->LevelOutOfWindow2Callback = HAL_ADCEx_LevelOutOfWindow2Callback; /* Legacy weak callback */
463 hadc->LevelOutOfWindow3Callback = HAL_ADCEx_LevelOutOfWindow3Callback; /* Legacy weak callback */
464 hadc->EndOfSamplingCallback = HAL_ADCEx_EndOfSamplingCallback; /* Legacy weak callback */
466 if (hadc->MspInitCallback == NULL)
468 hadc->MspInitCallback = HAL_ADC_MspInit; /* Legacy weak MspInit */
471 /* Init the low level hardware */
472 hadc->MspInitCallback(hadc);
473 #else
474 /* Init the low level hardware */
475 HAL_ADC_MspInit(hadc);
476 #endif /* USE_HAL_ADC_REGISTER_CALLBACKS */
478 /* Set ADC error code to none */
479 ADC_CLEAR_ERRORCODE(hadc);
481 /* Initialize Lock */
482 hadc->Lock = HAL_UNLOCKED;
485 /* - Exit from deep-power-down mode and ADC voltage regulator enable */
486 if (LL_ADC_IsDeepPowerDownEnabled(hadc->Instance) != 0UL)
488 /* Disable ADC deep power down mode */
489 LL_ADC_DisableDeepPowerDown(hadc->Instance);
491 /* System was in deep power down mode, calibration must
492 be relaunched or a previously saved calibration factor
493 re-applied once the ADC voltage regulator is enabled */
496 if (LL_ADC_IsInternalRegulatorEnabled(hadc->Instance) == 0UL)
498 /* Enable ADC internal voltage regulator */
499 LL_ADC_EnableInternalRegulator(hadc->Instance);
501 /* Note: Variable divided by 2 to compensate partially */
502 /* CPU processing cycles, scaling in us split to not */
503 /* exceed 32 bits register capacity and handle low frequency. */
504 wait_loop_index = ((LL_ADC_DELAY_INTERNAL_REGUL_STAB_US / 10UL) * (SystemCoreClock / (100000UL * 2UL)));
505 while (wait_loop_index != 0UL)
507 wait_loop_index--;
511 /* Verification that ADC voltage regulator is correctly enabled, whether */
512 /* or not ADC is coming from state reset (if any potential problem of */
513 /* clocking, voltage regulator would not be enabled). */
514 if (LL_ADC_IsInternalRegulatorEnabled(hadc->Instance) == 0UL)
516 /* Update ADC state machine to error */
517 SET_BIT(hadc->State, HAL_ADC_STATE_ERROR_INTERNAL);
519 /* Set ADC error code to ADC peripheral internal error */
520 SET_BIT(hadc->ErrorCode, HAL_ADC_ERROR_INTERNAL);
522 tmp_hal_status = HAL_ERROR;
525 /* Configuration of ADC parameters if previous preliminary actions are */
526 /* correctly completed and if there is no conversion on going on regular */
527 /* group (ADC may already be enabled at this point if HAL_ADC_Init() is */
528 /* called to update a parameter on the fly). */
529 tmp_adc_reg_is_conversion_on_going = LL_ADC_REG_IsConversionOngoing(hadc->Instance);
531 if (((hadc->State & HAL_ADC_STATE_ERROR_INTERNAL) == 0UL)
532 && (tmp_adc_reg_is_conversion_on_going == 0UL)
535 /* Set ADC state */
536 ADC_STATE_CLR_SET(hadc->State,
537 HAL_ADC_STATE_REG_BUSY,
538 HAL_ADC_STATE_BUSY_INTERNAL);
540 /* Configuration of common ADC parameters */
542 /* Parameters update conditioned to ADC state: */
543 /* Parameters that can be updated only when ADC is disabled: */
544 /* - clock configuration */
545 if (LL_ADC_IsEnabled(hadc->Instance) == 0UL)
547 if (__LL_ADC_IS_ENABLED_ALL_COMMON_INSTANCE(__LL_ADC_COMMON_INSTANCE(hadc->Instance)) == 0UL)
549 /* Reset configuration of ADC common register CCR: */
550 /* */
551 /* - ADC clock mode and ACC prescaler (CKMODE and PRESC bits)are set */
552 /* according to adc->Init.ClockPrescaler. It selects the clock */
553 /* source and sets the clock division factor. */
554 /* */
555 /* Some parameters of this register are not reset, since they are set */
556 /* by other functions and must be kept in case of usage of this */
557 /* function on the fly (update of a parameter of ADC_InitTypeDef */
558 /* without needing to reconfigure all other ADC groups/channels */
559 /* parameters): */
560 /* - when multimode feature is available, multimode-related */
561 /* parameters: MDMA, DMACFG, DELAY, DUAL (set by API */
562 /* HAL_ADCEx_MultiModeConfigChannel() ) */
563 /* - internal measurement paths: Vbat, temperature sensor, Vref */
564 /* (set into HAL_ADC_ConfigChannel() or */
565 /* HAL_ADCEx_InjectedConfigChannel() ) */
566 LL_ADC_SetCommonClock(__LL_ADC_COMMON_INSTANCE(hadc->Instance), hadc->Init.ClockPrescaler);
570 /* Configuration of ADC: */
571 /* - resolution Init.Resolution */
572 /* - data alignment Init.DataAlign */
573 /* - external trigger to start conversion Init.ExternalTrigConv */
574 /* - external trigger polarity Init.ExternalTrigConvEdge */
575 /* - continuous conversion mode Init.ContinuousConvMode */
576 /* - overrun Init.Overrun */
577 /* - discontinuous mode Init.DiscontinuousConvMode */
578 /* - discontinuous mode channel count Init.NbrOfDiscConversion */
579 tmpCFGR = (ADC_CFGR_CONTINUOUS((uint32_t)hadc->Init.ContinuousConvMode) |
580 hadc->Init.Overrun |
581 hadc->Init.DataAlign |
582 hadc->Init.Resolution |
583 ADC_CFGR_REG_DISCONTINUOUS((uint32_t)hadc->Init.DiscontinuousConvMode));
585 if (hadc->Init.DiscontinuousConvMode == ENABLE)
587 tmpCFGR |= ADC_CFGR_DISCONTINUOUS_NUM(hadc->Init.NbrOfDiscConversion);
590 /* Enable external trigger if trigger selection is different of software */
591 /* start. */
592 /* Note: This configuration keeps the hardware feature of parameter */
593 /* ExternalTrigConvEdge "trigger edge none" equivalent to */
594 /* software start. */
595 if (hadc->Init.ExternalTrigConv != ADC_SOFTWARE_START)
597 tmpCFGR |= ((hadc->Init.ExternalTrigConv & ADC_CFGR_EXTSEL)
598 | hadc->Init.ExternalTrigConvEdge
602 /* Update Configuration Register CFGR */
603 MODIFY_REG(hadc->Instance->CFGR, ADC_CFGR_FIELDS_1, tmpCFGR);
605 /* Configuration of sampling mode */
606 MODIFY_REG(hadc->Instance->CFGR2, ADC_CFGR2_BULB | ADC_CFGR2_SMPTRIG, hadc->Init.SamplingMode);
608 /* Parameters update conditioned to ADC state: */
609 /* Parameters that can be updated when ADC is disabled or enabled without */
610 /* conversion on going on regular and injected groups: */
611 /* - Gain Compensation Init.GainCompensation */
612 /* - DMA continuous request Init.DMAContinuousRequests */
613 /* - LowPowerAutoWait feature Init.LowPowerAutoWait */
614 /* - Oversampling parameters Init.Oversampling */
615 tmp_adc_is_conversion_on_going_regular = LL_ADC_REG_IsConversionOngoing(hadc->Instance);
616 tmp_adc_is_conversion_on_going_injected = LL_ADC_INJ_IsConversionOngoing(hadc->Instance);
617 if ((tmp_adc_is_conversion_on_going_regular == 0UL)
618 && (tmp_adc_is_conversion_on_going_injected == 0UL)
621 tmpCFGR = (ADC_CFGR_DFSDM(hadc) |
622 ADC_CFGR_AUTOWAIT((uint32_t)hadc->Init.LowPowerAutoWait) |
623 ADC_CFGR_DMACONTREQ((uint32_t)hadc->Init.DMAContinuousRequests));
625 MODIFY_REG(hadc->Instance->CFGR, ADC_CFGR_FIELDS_2, tmpCFGR);
627 if (hadc->Init.GainCompensation != 0UL)
629 SET_BIT(hadc->Instance->CFGR2, ADC_CFGR2_GCOMP);
630 MODIFY_REG(hadc->Instance->GCOMP, ADC_GCOMP_GCOMPCOEFF, hadc->Init.GainCompensation);
632 else
634 CLEAR_BIT(hadc->Instance->CFGR2, ADC_CFGR2_GCOMP);
635 MODIFY_REG(hadc->Instance->GCOMP, ADC_GCOMP_GCOMPCOEFF, 0UL);
638 if (hadc->Init.OversamplingMode == ENABLE)
640 assert_param(IS_ADC_OVERSAMPLING_RATIO(hadc->Init.Oversampling.Ratio));
641 assert_param(IS_ADC_RIGHT_BIT_SHIFT(hadc->Init.Oversampling.RightBitShift));
642 assert_param(IS_ADC_TRIGGERED_OVERSAMPLING_MODE(hadc->Init.Oversampling.TriggeredMode));
643 assert_param(IS_ADC_REGOVERSAMPLING_MODE(hadc->Init.Oversampling.OversamplingStopReset));
645 /* Configuration of Oversampler: */
646 /* - Oversampling Ratio */
647 /* - Right bit shift */
648 /* - Triggered mode */
649 /* - Oversampling mode (continued/resumed) */
650 MODIFY_REG(hadc->Instance->CFGR2,
651 ADC_CFGR2_OVSR |
652 ADC_CFGR2_OVSS |
653 ADC_CFGR2_TROVS |
654 ADC_CFGR2_ROVSM,
655 ADC_CFGR2_ROVSE |
656 hadc->Init.Oversampling.Ratio |
657 hadc->Init.Oversampling.RightBitShift |
658 hadc->Init.Oversampling.TriggeredMode |
659 hadc->Init.Oversampling.OversamplingStopReset
662 else
664 /* Disable ADC oversampling scope on ADC group regular */
665 CLEAR_BIT(hadc->Instance->CFGR2, ADC_CFGR2_ROVSE);
670 /* Configuration of regular group sequencer: */
671 /* - if scan mode is disabled, regular channels sequence length is set to */
672 /* 0x00: 1 channel converted (channel on regular rank 1) */
673 /* Parameter "NbrOfConversion" is discarded. */
674 /* Note: Scan mode is not present by hardware on this device, but */
675 /* emulated by software for alignment over all STM32 devices. */
676 /* - if scan mode is enabled, regular channels sequence length is set to */
677 /* parameter "NbrOfConversion". */
679 if (hadc->Init.ScanConvMode == ADC_SCAN_ENABLE)
681 /* Set number of ranks in regular group sequencer */
682 MODIFY_REG(hadc->Instance->SQR1, ADC_SQR1_L, (hadc->Init.NbrOfConversion - (uint8_t)1));
684 else
686 CLEAR_BIT(hadc->Instance->SQR1, ADC_SQR1_L);
689 /* Initialize the ADC state */
690 /* Clear HAL_ADC_STATE_BUSY_INTERNAL bit, set HAL_ADC_STATE_READY bit */
691 ADC_STATE_CLR_SET(hadc->State, HAL_ADC_STATE_BUSY_INTERNAL, HAL_ADC_STATE_READY);
693 else
695 /* Update ADC state machine to error */
696 SET_BIT(hadc->State, HAL_ADC_STATE_ERROR_INTERNAL);
698 tmp_hal_status = HAL_ERROR;
701 /* Return function status */
702 return tmp_hal_status;
706 * @brief Deinitialize the ADC peripheral registers to their default reset
707 * values, with deinitialization of the ADC MSP.
708 * @note For devices with several ADCs: reset of ADC common registers is done
709 * only if all ADCs sharing the same common group are disabled.
710 * (function "HAL_ADC_MspDeInit()" is also called under the same conditions:
711 * all ADC instances use the same core clock at RCC level, disabling
712 * the core clock reset all ADC instances).
713 * If this is not the case, reset of these common parameters reset is
714 * bypassed without error reporting: it can be the intended behavior in
715 * case of reset of a single ADC while the other ADCs sharing the same
716 * common group is still running.
717 * @note By default, HAL_ADC_DeInit() set ADC in mode deep power-down:
718 * this saves more power by reducing leakage currents
719 * and is particularly interesting before entering MCU low-power modes.
720 * @param hadc ADC handle
721 * @retval HAL status
723 HAL_StatusTypeDef HAL_ADC_DeInit(ADC_HandleTypeDef *hadc)
725 HAL_StatusTypeDef tmp_hal_status;
727 /* Check ADC handle */
728 if (hadc == NULL)
730 return HAL_ERROR;
733 /* Check the parameters */
734 assert_param(IS_ADC_ALL_INSTANCE(hadc->Instance));
736 /* Set ADC state */
737 SET_BIT(hadc->State, HAL_ADC_STATE_BUSY_INTERNAL);
739 /* Stop potential conversion on going */
740 tmp_hal_status = ADC_ConversionStop(hadc, ADC_REGULAR_INJECTED_GROUP);
742 /* Disable ADC peripheral if conversions are effectively stopped */
743 /* Flush register JSQR: reset the queue sequencer when injected */
744 /* queue sequencer is enabled and ADC disabled. */
745 /* The software and hardware triggers of the injected sequence are both */
746 /* internally disabled just after the completion of the last valid */
747 /* injected sequence. */
748 SET_BIT(hadc->Instance->CFGR, ADC_CFGR_JQM);
750 /* Disable ADC peripheral if conversions are effectively stopped */
751 if (tmp_hal_status == HAL_OK)
753 /* Disable the ADC peripheral */
754 tmp_hal_status = ADC_Disable(hadc);
756 /* Check if ADC is effectively disabled */
757 if (tmp_hal_status == HAL_OK)
759 /* Change ADC state */
760 hadc->State = HAL_ADC_STATE_READY;
764 /* Note: HAL ADC deInit is done independently of ADC conversion stop */
765 /* and disable return status. In case of status fail, attempt to */
766 /* perform deinitialization anyway and it is up user code in */
767 /* in HAL_ADC_MspDeInit() to reset the ADC peripheral using */
768 /* system RCC hard reset. */
770 /* ========== Reset ADC registers ========== */
771 /* Reset register IER */
772 __HAL_ADC_DISABLE_IT(hadc, (ADC_IT_AWD3 | ADC_IT_AWD2 | ADC_IT_AWD1 |
773 ADC_IT_JQOVF | ADC_IT_OVR |
774 ADC_IT_JEOS | ADC_IT_JEOC |
775 ADC_IT_EOS | ADC_IT_EOC |
776 ADC_IT_EOSMP | ADC_IT_RDY));
778 /* Reset register ISR */
779 __HAL_ADC_CLEAR_FLAG(hadc, (ADC_FLAG_AWD3 | ADC_FLAG_AWD2 | ADC_FLAG_AWD1 |
780 ADC_FLAG_JQOVF | ADC_FLAG_OVR |
781 ADC_FLAG_JEOS | ADC_FLAG_JEOC |
782 ADC_FLAG_EOS | ADC_FLAG_EOC |
783 ADC_FLAG_EOSMP | ADC_FLAG_RDY));
785 /* Reset register CR */
786 /* Bits ADC_CR_JADSTP, ADC_CR_ADSTP, ADC_CR_JADSTART, ADC_CR_ADSTART,
787 ADC_CR_ADCAL, ADC_CR_ADDIS and ADC_CR_ADEN are in access mode "read-set":
788 no direct reset applicable.
789 Update CR register to reset value where doable by software */
790 CLEAR_BIT(hadc->Instance->CR, ADC_CR_ADVREGEN | ADC_CR_ADCALDIF);
791 SET_BIT(hadc->Instance->CR, ADC_CR_DEEPPWD);
793 /* Reset register CFGR */
794 CLEAR_BIT(hadc->Instance->CFGR, ADC_CFGR_FIELDS);
795 SET_BIT(hadc->Instance->CFGR, ADC_CFGR_JQDIS);
797 /* Reset register CFGR2 */
798 CLEAR_BIT(hadc->Instance->CFGR2, ADC_CFGR2_ROVSM | ADC_CFGR2_TROVS | ADC_CFGR2_OVSS |
799 ADC_CFGR2_OVSR | ADC_CFGR2_JOVSE | ADC_CFGR2_ROVSE);
801 /* Reset register SMPR1 */
802 CLEAR_BIT(hadc->Instance->SMPR1, ADC_SMPR1_FIELDS);
804 /* Reset register SMPR2 */
805 CLEAR_BIT(hadc->Instance->SMPR2, ADC_SMPR2_SMP18 | ADC_SMPR2_SMP17 | ADC_SMPR2_SMP16 |
806 ADC_SMPR2_SMP15 | ADC_SMPR2_SMP14 | ADC_SMPR2_SMP13 |
807 ADC_SMPR2_SMP12 | ADC_SMPR2_SMP11 | ADC_SMPR2_SMP10);
809 /* Reset register TR1 */
810 CLEAR_BIT(hadc->Instance->TR1, ADC_TR1_HT1 | ADC_TR1_LT1);
812 /* Reset register TR2 */
813 CLEAR_BIT(hadc->Instance->TR2, ADC_TR2_HT2 | ADC_TR2_LT2);
815 /* Reset register TR3 */
816 CLEAR_BIT(hadc->Instance->TR3, ADC_TR3_HT3 | ADC_TR3_LT3);
818 /* Reset register SQR1 */
819 CLEAR_BIT(hadc->Instance->SQR1, ADC_SQR1_SQ4 | ADC_SQR1_SQ3 | ADC_SQR1_SQ2 |
820 ADC_SQR1_SQ1 | ADC_SQR1_L);
822 /* Reset register SQR2 */
823 CLEAR_BIT(hadc->Instance->SQR2, ADC_SQR2_SQ9 | ADC_SQR2_SQ8 | ADC_SQR2_SQ7 |
824 ADC_SQR2_SQ6 | ADC_SQR2_SQ5);
826 /* Reset register SQR3 */
827 CLEAR_BIT(hadc->Instance->SQR3, ADC_SQR3_SQ14 | ADC_SQR3_SQ13 | ADC_SQR3_SQ12 |
828 ADC_SQR3_SQ11 | ADC_SQR3_SQ10);
830 /* Reset register SQR4 */
831 CLEAR_BIT(hadc->Instance->SQR4, ADC_SQR4_SQ16 | ADC_SQR4_SQ15);
833 /* Register JSQR was reset when the ADC was disabled */
835 /* Reset register DR */
836 /* bits in access mode read only, no direct reset applicable*/
838 /* Reset register OFR1 */
839 CLEAR_BIT(hadc->Instance->OFR1, ADC_OFR1_OFFSET1_EN | ADC_OFR1_OFFSET1_CH | ADC_OFR1_OFFSET1);
840 /* Reset register OFR2 */
841 CLEAR_BIT(hadc->Instance->OFR2, ADC_OFR2_OFFSET2_EN | ADC_OFR2_OFFSET2_CH | ADC_OFR2_OFFSET2);
842 /* Reset register OFR3 */
843 CLEAR_BIT(hadc->Instance->OFR3, ADC_OFR3_OFFSET3_EN | ADC_OFR3_OFFSET3_CH | ADC_OFR3_OFFSET3);
844 /* Reset register OFR4 */
845 CLEAR_BIT(hadc->Instance->OFR4, ADC_OFR4_OFFSET4_EN | ADC_OFR4_OFFSET4_CH | ADC_OFR4_OFFSET4);
847 /* Reset registers JDR1, JDR2, JDR3, JDR4 */
848 /* bits in access mode read only, no direct reset applicable*/
850 /* Reset register AWD2CR */
851 CLEAR_BIT(hadc->Instance->AWD2CR, ADC_AWD2CR_AWD2CH);
853 /* Reset register AWD3CR */
854 CLEAR_BIT(hadc->Instance->AWD3CR, ADC_AWD3CR_AWD3CH);
856 /* Reset register DIFSEL */
857 CLEAR_BIT(hadc->Instance->DIFSEL, ADC_DIFSEL_DIFSEL);
859 /* Reset register CALFACT */
860 CLEAR_BIT(hadc->Instance->CALFACT, ADC_CALFACT_CALFACT_D | ADC_CALFACT_CALFACT_S);
863 /* ========== Reset common ADC registers ========== */
865 /* Software is allowed to change common parameters only when all the other
866 ADCs are disabled. */
867 if (__LL_ADC_IS_ENABLED_ALL_COMMON_INSTANCE(__LL_ADC_COMMON_INSTANCE(hadc->Instance)) == 0UL)
869 /* Reset configuration of ADC common register CCR:
870 - clock mode: CKMODE, PRESCEN
871 - multimode related parameters (when this feature is available): MDMA,
872 DMACFG, DELAY, DUAL (set by HAL_ADCEx_MultiModeConfigChannel() API)
873 - internal measurement paths: Vbat, temperature sensor, Vref (set into
874 HAL_ADC_ConfigChannel() or HAL_ADCEx_InjectedConfigChannel() )
876 ADC_CLEAR_COMMON_CONTROL_REGISTER(hadc);
879 /* DeInit the low level hardware.
881 For example:
882 __HAL_RCC_ADC_FORCE_RESET();
883 __HAL_RCC_ADC_RELEASE_RESET();
884 __HAL_RCC_ADC_CLK_DISABLE();
886 Keep in mind that all ADCs use the same clock: disabling
887 the clock will reset all ADCs.
890 #if (USE_HAL_ADC_REGISTER_CALLBACKS == 1)
891 if (hadc->MspDeInitCallback == NULL)
893 hadc->MspDeInitCallback = HAL_ADC_MspDeInit; /* Legacy weak MspDeInit */
896 /* DeInit the low level hardware: RCC clock, NVIC */
897 hadc->MspDeInitCallback(hadc);
898 #else
899 /* DeInit the low level hardware: RCC clock, NVIC */
900 HAL_ADC_MspDeInit(hadc);
901 #endif /* USE_HAL_ADC_REGISTER_CALLBACKS */
903 /* Set ADC error code to none */
904 ADC_CLEAR_ERRORCODE(hadc);
906 /* Reset injected channel configuration parameters */
907 hadc->InjectionConfig.ContextQueue = 0;
908 hadc->InjectionConfig.ChannelCount = 0;
910 /* Set ADC state */
911 hadc->State = HAL_ADC_STATE_RESET;
913 /* Process unlocked */
914 __HAL_UNLOCK(hadc);
916 /* Return function status */
917 return tmp_hal_status;
921 * @brief Initialize the ADC MSP.
922 * @param hadc ADC handle
923 * @retval None
925 __weak void HAL_ADC_MspInit(ADC_HandleTypeDef *hadc)
927 /* Prevent unused argument(s) compilation warning */
928 UNUSED(hadc);
930 /* NOTE : This function should not be modified. When the callback is needed,
931 function HAL_ADC_MspInit must be implemented in the user file.
936 * @brief DeInitialize the ADC MSP.
937 * @param hadc ADC handle
938 * @note All ADC instances use the same core clock at RCC level, disabling
939 * the core clock reset all ADC instances).
940 * @retval None
942 __weak void HAL_ADC_MspDeInit(ADC_HandleTypeDef *hadc)
944 /* Prevent unused argument(s) compilation warning */
945 UNUSED(hadc);
947 /* NOTE : This function should not be modified. When the callback is needed,
948 function HAL_ADC_MspDeInit must be implemented in the user file.
952 #if (USE_HAL_ADC_REGISTER_CALLBACKS == 1)
954 * @brief Register a User ADC Callback
955 * To be used instead of the weak predefined callback
956 * @param hadc Pointer to a ADC_HandleTypeDef structure that contains
957 * the configuration information for the specified ADC.
958 * @param CallbackID ID of the callback to be registered
959 * This parameter can be one of the following values:
960 * @arg @ref HAL_ADC_CONVERSION_COMPLETE_CB_ID ADC conversion complete callback ID
961 * @arg @ref HAL_ADC_CONVERSION_HALF_CB_ID ADC conversion DMA half-transfer callback ID
962 * @arg @ref HAL_ADC_LEVEL_OUT_OF_WINDOW_1_CB_ID ADC analog watchdog 1 callback ID
963 * @arg @ref HAL_ADC_ERROR_CB_ID ADC error callback ID
964 * @arg @ref HAL_ADC_INJ_CONVERSION_COMPLETE_CB_ID ADC group injected conversion complete callback ID
965 * @arg @ref HAL_ADC_INJ_QUEUE_OVEFLOW_CB_ID ADC group injected context queue overflow callback ID
966 * @arg @ref HAL_ADC_LEVEL_OUT_OF_WINDOW_2_CB_ID ADC analog watchdog 2 callback ID
967 * @arg @ref HAL_ADC_LEVEL_OUT_OF_WINDOW_3_CB_ID ADC analog watchdog 3 callback ID
968 * @arg @ref HAL_ADC_END_OF_SAMPLING_CB_ID ADC end of sampling callback ID
969 * @arg @ref HAL_ADC_MSPINIT_CB_ID ADC Msp Init callback ID
970 * @arg @ref HAL_ADC_MSPDEINIT_CB_ID ADC Msp DeInit callback ID
971 * @arg @ref HAL_ADC_MSPINIT_CB_ID MspInit callback ID
972 * @arg @ref HAL_ADC_MSPDEINIT_CB_ID MspDeInit callback ID
973 * @param pCallback pointer to the Callback function
974 * @retval HAL status
976 HAL_StatusTypeDef HAL_ADC_RegisterCallback(ADC_HandleTypeDef *hadc, HAL_ADC_CallbackIDTypeDef CallbackID, pADC_CallbackTypeDef pCallback)
978 HAL_StatusTypeDef status = HAL_OK;
980 if (pCallback == NULL)
982 /* Update the error code */
983 hadc->ErrorCode |= HAL_ADC_ERROR_INVALID_CALLBACK;
985 return HAL_ERROR;
988 if ((hadc->State & HAL_ADC_STATE_READY) != 0UL)
990 switch (CallbackID)
992 case HAL_ADC_CONVERSION_COMPLETE_CB_ID :
993 hadc->ConvCpltCallback = pCallback;
994 break;
996 case HAL_ADC_CONVERSION_HALF_CB_ID :
997 hadc->ConvHalfCpltCallback = pCallback;
998 break;
1000 case HAL_ADC_LEVEL_OUT_OF_WINDOW_1_CB_ID :
1001 hadc->LevelOutOfWindowCallback = pCallback;
1002 break;
1004 case HAL_ADC_ERROR_CB_ID :
1005 hadc->ErrorCallback = pCallback;
1006 break;
1008 case HAL_ADC_INJ_CONVERSION_COMPLETE_CB_ID :
1009 hadc->InjectedConvCpltCallback = pCallback;
1010 break;
1012 case HAL_ADC_INJ_QUEUE_OVEFLOW_CB_ID :
1013 hadc->InjectedQueueOverflowCallback = pCallback;
1014 break;
1016 case HAL_ADC_LEVEL_OUT_OF_WINDOW_2_CB_ID :
1017 hadc->LevelOutOfWindow2Callback = pCallback;
1018 break;
1020 case HAL_ADC_LEVEL_OUT_OF_WINDOW_3_CB_ID :
1021 hadc->LevelOutOfWindow3Callback = pCallback;
1022 break;
1024 case HAL_ADC_END_OF_SAMPLING_CB_ID :
1025 hadc->EndOfSamplingCallback = pCallback;
1026 break;
1028 case HAL_ADC_MSPINIT_CB_ID :
1029 hadc->MspInitCallback = pCallback;
1030 break;
1032 case HAL_ADC_MSPDEINIT_CB_ID :
1033 hadc->MspDeInitCallback = pCallback;
1034 break;
1036 default :
1037 /* Update the error code */
1038 hadc->ErrorCode |= HAL_ADC_ERROR_INVALID_CALLBACK;
1040 /* Return error status */
1041 status = HAL_ERROR;
1042 break;
1045 else if (HAL_ADC_STATE_RESET == hadc->State)
1047 switch (CallbackID)
1049 case HAL_ADC_MSPINIT_CB_ID :
1050 hadc->MspInitCallback = pCallback;
1051 break;
1053 case HAL_ADC_MSPDEINIT_CB_ID :
1054 hadc->MspDeInitCallback = pCallback;
1055 break;
1057 default :
1058 /* Update the error code */
1059 hadc->ErrorCode |= HAL_ADC_ERROR_INVALID_CALLBACK;
1061 /* Return error status */
1062 status = HAL_ERROR;
1063 break;
1066 else
1068 /* Update the error code */
1069 hadc->ErrorCode |= HAL_ADC_ERROR_INVALID_CALLBACK;
1071 /* Return error status */
1072 status = HAL_ERROR;
1075 return status;
1079 * @brief Unregister a ADC Callback
1080 * ADC callback is redirected to the weak predefined callback
1081 * @param hadc Pointer to a ADC_HandleTypeDef structure that contains
1082 * the configuration information for the specified ADC.
1083 * @param CallbackID ID of the callback to be unregistered
1084 * This parameter can be one of the following values:
1085 * @arg @ref HAL_ADC_CONVERSION_COMPLETE_CB_ID ADC conversion complete callback ID
1086 * @arg @ref HAL_ADC_CONVERSION_HALF_CB_ID ADC conversion DMA half-transfer callback ID
1087 * @arg @ref HAL_ADC_LEVEL_OUT_OF_WINDOW_1_CB_ID ADC analog watchdog 1 callback ID
1088 * @arg @ref HAL_ADC_ERROR_CB_ID ADC error callback ID
1089 * @arg @ref HAL_ADC_INJ_CONVERSION_COMPLETE_CB_ID ADC group injected conversion complete callback ID
1090 * @arg @ref HAL_ADC_INJ_QUEUE_OVEFLOW_CB_ID ADC group injected context queue overflow callback ID
1091 * @arg @ref HAL_ADC_LEVEL_OUT_OF_WINDOW_2_CB_ID ADC analog watchdog 2 callback ID
1092 * @arg @ref HAL_ADC_LEVEL_OUT_OF_WINDOW_3_CB_ID ADC analog watchdog 3 callback ID
1093 * @arg @ref HAL_ADC_END_OF_SAMPLING_CB_ID ADC end of sampling callback ID
1094 * @arg @ref HAL_ADC_MSPINIT_CB_ID ADC Msp Init callback ID
1095 * @arg @ref HAL_ADC_MSPDEINIT_CB_ID ADC Msp DeInit callback ID
1096 * @arg @ref HAL_ADC_MSPINIT_CB_ID MspInit callback ID
1097 * @arg @ref HAL_ADC_MSPDEINIT_CB_ID MspDeInit callback ID
1098 * @retval HAL status
1100 HAL_StatusTypeDef HAL_ADC_UnRegisterCallback(ADC_HandleTypeDef *hadc, HAL_ADC_CallbackIDTypeDef CallbackID)
1102 HAL_StatusTypeDef status = HAL_OK;
1104 if ((hadc->State & HAL_ADC_STATE_READY) != 0UL)
1106 switch (CallbackID)
1108 case HAL_ADC_CONVERSION_COMPLETE_CB_ID :
1109 hadc->ConvCpltCallback = HAL_ADC_ConvCpltCallback;
1110 break;
1112 case HAL_ADC_CONVERSION_HALF_CB_ID :
1113 hadc->ConvHalfCpltCallback = HAL_ADC_ConvHalfCpltCallback;
1114 break;
1116 case HAL_ADC_LEVEL_OUT_OF_WINDOW_1_CB_ID :
1117 hadc->LevelOutOfWindowCallback = HAL_ADC_LevelOutOfWindowCallback;
1118 break;
1120 case HAL_ADC_ERROR_CB_ID :
1121 hadc->ErrorCallback = HAL_ADC_ErrorCallback;
1122 break;
1124 case HAL_ADC_INJ_CONVERSION_COMPLETE_CB_ID :
1125 hadc->InjectedConvCpltCallback = HAL_ADCEx_InjectedConvCpltCallback;
1126 break;
1128 case HAL_ADC_INJ_QUEUE_OVEFLOW_CB_ID :
1129 hadc->InjectedQueueOverflowCallback = HAL_ADCEx_InjectedQueueOverflowCallback;
1130 break;
1132 case HAL_ADC_LEVEL_OUT_OF_WINDOW_2_CB_ID :
1133 hadc->LevelOutOfWindow2Callback = HAL_ADCEx_LevelOutOfWindow2Callback;
1134 break;
1136 case HAL_ADC_LEVEL_OUT_OF_WINDOW_3_CB_ID :
1137 hadc->LevelOutOfWindow3Callback = HAL_ADCEx_LevelOutOfWindow3Callback;
1138 break;
1140 case HAL_ADC_END_OF_SAMPLING_CB_ID :
1141 hadc->EndOfSamplingCallback = HAL_ADCEx_EndOfSamplingCallback;
1142 break;
1144 case HAL_ADC_MSPINIT_CB_ID :
1145 hadc->MspInitCallback = HAL_ADC_MspInit; /* Legacy weak MspInit */
1146 break;
1148 case HAL_ADC_MSPDEINIT_CB_ID :
1149 hadc->MspDeInitCallback = HAL_ADC_MspDeInit; /* Legacy weak MspDeInit */
1150 break;
1152 default :
1153 /* Update the error code */
1154 hadc->ErrorCode |= HAL_ADC_ERROR_INVALID_CALLBACK;
1156 /* Return error status */
1157 status = HAL_ERROR;
1158 break;
1161 else if (HAL_ADC_STATE_RESET == hadc->State)
1163 switch (CallbackID)
1165 case HAL_ADC_MSPINIT_CB_ID :
1166 hadc->MspInitCallback = HAL_ADC_MspInit; /* Legacy weak MspInit */
1167 break;
1169 case HAL_ADC_MSPDEINIT_CB_ID :
1170 hadc->MspDeInitCallback = HAL_ADC_MspDeInit; /* Legacy weak MspDeInit */
1171 break;
1173 default :
1174 /* Update the error code */
1175 hadc->ErrorCode |= HAL_ADC_ERROR_INVALID_CALLBACK;
1177 /* Return error status */
1178 status = HAL_ERROR;
1179 break;
1182 else
1184 /* Update the error code */
1185 hadc->ErrorCode |= HAL_ADC_ERROR_INVALID_CALLBACK;
1187 /* Return error status */
1188 status = HAL_ERROR;
1191 return status;
1194 #endif /* USE_HAL_ADC_REGISTER_CALLBACKS */
1197 * @}
1200 /** @defgroup ADC_Exported_Functions_Group2 ADC Input and Output operation functions
1201 * @brief ADC IO operation functions
1203 @verbatim
1204 ===============================================================================
1205 ##### IO operation functions #####
1206 ===============================================================================
1207 [..] This section provides functions allowing to:
1208 (+) Start conversion of regular group.
1209 (+) Stop conversion of regular group.
1210 (+) Poll for conversion complete on regular group.
1211 (+) Poll for conversion event.
1212 (+) Get result of regular channel conversion.
1213 (+) Start conversion of regular group and enable interruptions.
1214 (+) Stop conversion of regular group and disable interruptions.
1215 (+) Handle ADC interrupt request
1216 (+) Start conversion of regular group and enable DMA transfer.
1217 (+) Stop conversion of regular group and disable ADC DMA transfer.
1218 @endverbatim
1219 * @{
1223 * @brief Enable ADC, start conversion of regular group.
1224 * @note Interruptions enabled in this function: None.
1225 * @note Case of multimode enabled (when multimode feature is available):
1226 * if ADC is Slave, ADC is enabled but conversion is not started,
1227 * if ADC is master, ADC is enabled and multimode conversion is started.
1228 * @param hadc ADC handle
1229 * @retval HAL status
1231 HAL_StatusTypeDef HAL_ADC_Start(ADC_HandleTypeDef *hadc)
1233 HAL_StatusTypeDef tmp_hal_status;
1234 #if defined(ADC_MULTIMODE_SUPPORT)
1235 const ADC_TypeDef *tmpADC_Master;
1236 uint32_t tmp_multimode_config = LL_ADC_GetMultimode(__LL_ADC_COMMON_INSTANCE(hadc->Instance));
1237 #endif
1239 /* Check the parameters */
1240 assert_param(IS_ADC_ALL_INSTANCE(hadc->Instance));
1242 /* Perform ADC enable and conversion start if no conversion is on going */
1243 if (LL_ADC_REG_IsConversionOngoing(hadc->Instance) == 0UL)
1245 /* Process locked */
1246 __HAL_LOCK(hadc);
1248 /* Enable the ADC peripheral */
1249 tmp_hal_status = ADC_Enable(hadc);
1251 /* Start conversion if ADC is effectively enabled */
1252 if (tmp_hal_status == HAL_OK)
1254 /* Set ADC state */
1255 /* - Clear state bitfield related to regular group conversion results */
1256 /* - Set state bitfield related to regular operation */
1257 ADC_STATE_CLR_SET(hadc->State,
1258 HAL_ADC_STATE_READY | HAL_ADC_STATE_REG_EOC | HAL_ADC_STATE_REG_OVR | HAL_ADC_STATE_REG_EOSMP,
1259 HAL_ADC_STATE_REG_BUSY);
1261 #if defined(ADC_MULTIMODE_SUPPORT)
1262 /* Reset HAL_ADC_STATE_MULTIMODE_SLAVE bit
1263 - if ADC instance is master or if multimode feature is not available
1264 - if multimode setting is disabled (ADC instance slave in independent mode) */
1265 if ((__LL_ADC_MULTI_INSTANCE_MASTER(hadc->Instance) == hadc->Instance)
1266 || (tmp_multimode_config == LL_ADC_MULTI_INDEPENDENT)
1269 CLEAR_BIT(hadc->State, HAL_ADC_STATE_MULTIMODE_SLAVE);
1271 #endif
1273 /* Set ADC error code */
1274 /* Check if a conversion is on going on ADC group injected */
1275 if (HAL_IS_BIT_SET(hadc->State, HAL_ADC_STATE_INJ_BUSY))
1277 /* Reset ADC error code fields related to regular conversions only */
1278 CLEAR_BIT(hadc->ErrorCode, (HAL_ADC_ERROR_OVR | HAL_ADC_ERROR_DMA));
1280 else
1282 /* Reset all ADC error code fields */
1283 ADC_CLEAR_ERRORCODE(hadc);
1286 /* Clear ADC group regular conversion flag and overrun flag */
1287 /* (To ensure of no unknown state from potential previous ADC operations) */
1288 __HAL_ADC_CLEAR_FLAG(hadc, (ADC_FLAG_EOC | ADC_FLAG_EOS | ADC_FLAG_OVR));
1290 /* Process unlocked */
1291 /* Unlock before starting ADC conversions: in case of potential */
1292 /* interruption, to let the process to ADC IRQ Handler. */
1293 __HAL_UNLOCK(hadc);
1295 /* Enable conversion of regular group. */
1296 /* If software start has been selected, conversion starts immediately. */
1297 /* If external trigger has been selected, conversion will start at next */
1298 /* trigger event. */
1299 /* Case of multimode enabled (when multimode feature is available): */
1300 /* - if ADC is slave and dual regular conversions are enabled, ADC is */
1301 /* enabled only (conversion is not started), */
1302 /* - if ADC is master, ADC is enabled and conversion is started. */
1303 #if defined(ADC_MULTIMODE_SUPPORT)
1304 if ((__LL_ADC_MULTI_INSTANCE_MASTER(hadc->Instance) == hadc->Instance)
1305 || (tmp_multimode_config == LL_ADC_MULTI_INDEPENDENT)
1306 || (tmp_multimode_config == LL_ADC_MULTI_DUAL_INJ_SIMULT)
1307 || (tmp_multimode_config == LL_ADC_MULTI_DUAL_INJ_ALTERN)
1310 /* ADC instance is not a multimode slave instance with multimode regular conversions enabled */
1311 if (READ_BIT(hadc->Instance->CFGR, ADC_CFGR_JAUTO) != 0UL)
1313 ADC_STATE_CLR_SET(hadc->State, HAL_ADC_STATE_INJ_EOC, HAL_ADC_STATE_INJ_BUSY);
1316 /* Start ADC group regular conversion */
1317 LL_ADC_REG_StartConversion(hadc->Instance);
1319 else
1321 /* ADC instance is a multimode slave instance with multimode regular conversions enabled */
1322 SET_BIT(hadc->State, HAL_ADC_STATE_MULTIMODE_SLAVE);
1323 /* if Master ADC JAUTO bit is set, update Slave State in setting
1324 HAL_ADC_STATE_INJ_BUSY bit and in resetting HAL_ADC_STATE_INJ_EOC bit */
1325 tmpADC_Master = __LL_ADC_MULTI_INSTANCE_MASTER(hadc->Instance);
1326 if (READ_BIT(tmpADC_Master->CFGR, ADC_CFGR_JAUTO) != 0UL)
1328 ADC_STATE_CLR_SET(hadc->State, HAL_ADC_STATE_INJ_EOC, HAL_ADC_STATE_INJ_BUSY);
1332 #else
1333 if (READ_BIT(hadc->Instance->CFGR, ADC_CFGR_JAUTO) != 0UL)
1335 ADC_STATE_CLR_SET(hadc->State, HAL_ADC_STATE_INJ_EOC, HAL_ADC_STATE_INJ_BUSY);
1338 /* Start ADC group regular conversion */
1339 LL_ADC_REG_StartConversion(hadc->Instance);
1340 #endif
1342 else
1344 /* Process unlocked */
1345 __HAL_UNLOCK(hadc);
1348 else
1350 tmp_hal_status = HAL_BUSY;
1353 /* Return function status */
1354 return tmp_hal_status;
1358 * @brief Stop ADC conversion of regular group (and injected channels in
1359 * case of auto_injection mode), disable ADC peripheral.
1360 * @note: ADC peripheral disable is forcing stop of potential
1361 * conversion on injected group. If injected group is under use, it
1362 * should be preliminarily stopped using HAL_ADCEx_InjectedStop function.
1363 * @param hadc ADC handle
1364 * @retval HAL status.
1366 HAL_StatusTypeDef HAL_ADC_Stop(ADC_HandleTypeDef *hadc)
1368 HAL_StatusTypeDef tmp_hal_status;
1370 /* Check the parameters */
1371 assert_param(IS_ADC_ALL_INSTANCE(hadc->Instance));
1373 /* Process locked */
1374 __HAL_LOCK(hadc);
1376 /* 1. Stop potential conversion on going, on ADC groups regular and injected */
1377 tmp_hal_status = ADC_ConversionStop(hadc, ADC_REGULAR_INJECTED_GROUP);
1379 /* Disable ADC peripheral if conversions are effectively stopped */
1380 if (tmp_hal_status == HAL_OK)
1382 /* 2. Disable the ADC peripheral */
1383 tmp_hal_status = ADC_Disable(hadc);
1385 /* Check if ADC is effectively disabled */
1386 if (tmp_hal_status == HAL_OK)
1388 /* Set ADC state */
1389 ADC_STATE_CLR_SET(hadc->State,
1390 HAL_ADC_STATE_REG_BUSY | HAL_ADC_STATE_INJ_BUSY,
1391 HAL_ADC_STATE_READY);
1395 /* Process unlocked */
1396 __HAL_UNLOCK(hadc);
1398 /* Return function status */
1399 return tmp_hal_status;
1403 * @brief Wait for regular group conversion to be completed.
1404 * @note ADC conversion flags EOS (end of sequence) and EOC (end of
1405 * conversion) are cleared by this function, with an exception:
1406 * if low power feature "LowPowerAutoWait" is enabled, flags are
1407 * not cleared to not interfere with this feature until data register
1408 * is read using function HAL_ADC_GetValue().
1409 * @note This function cannot be used in a particular setup: ADC configured
1410 * in DMA mode and polling for end of each conversion (ADC init
1411 * parameter "EOCSelection" set to ADC_EOC_SINGLE_CONV).
1412 * In this case, DMA resets the flag EOC and polling cannot be
1413 * performed on each conversion. Nevertheless, polling can still
1414 * be performed on the complete sequence (ADC init
1415 * parameter "EOCSelection" set to ADC_EOC_SEQ_CONV).
1416 * @param hadc ADC handle
1417 * @param Timeout Timeout value in millisecond.
1418 * @retval HAL status
1420 HAL_StatusTypeDef HAL_ADC_PollForConversion(ADC_HandleTypeDef *hadc, uint32_t Timeout)
1422 uint32_t tickstart;
1423 uint32_t tmp_Flag_End;
1424 uint32_t tmp_cfgr;
1425 #if defined(ADC_MULTIMODE_SUPPORT)
1426 const ADC_TypeDef *tmpADC_Master;
1427 uint32_t tmp_multimode_config = LL_ADC_GetMultimode(__LL_ADC_COMMON_INSTANCE(hadc->Instance));
1428 #endif
1430 /* Check the parameters */
1431 assert_param(IS_ADC_ALL_INSTANCE(hadc->Instance));
1433 /* If end of conversion selected to end of sequence conversions */
1434 if (hadc->Init.EOCSelection == ADC_EOC_SEQ_CONV)
1436 tmp_Flag_End = ADC_FLAG_EOS;
1438 /* If end of conversion selected to end of unitary conversion */
1439 else /* ADC_EOC_SINGLE_CONV */
1441 /* Verification that ADC configuration is compliant with polling for */
1442 /* each conversion: */
1443 /* Particular case is ADC configured in DMA mode and ADC sequencer with */
1444 /* several ranks and polling for end of each conversion. */
1445 /* For code simplicity sake, this particular case is generalized to */
1446 /* ADC configured in DMA mode and and polling for end of each conversion. */
1447 #if defined(ADC_MULTIMODE_SUPPORT)
1448 if ((tmp_multimode_config == LL_ADC_MULTI_INDEPENDENT)
1449 || (tmp_multimode_config == LL_ADC_MULTI_DUAL_INJ_SIMULT)
1450 || (tmp_multimode_config == LL_ADC_MULTI_DUAL_INJ_ALTERN)
1453 /* Check ADC DMA mode in independent mode on ADC group regular */
1454 if (READ_BIT(hadc->Instance->CFGR, ADC_CFGR_DMAEN) != 0UL)
1456 SET_BIT(hadc->State, HAL_ADC_STATE_ERROR_CONFIG);
1457 return HAL_ERROR;
1459 else
1461 tmp_Flag_End = (ADC_FLAG_EOC);
1464 else
1466 /* Check ADC DMA mode in multimode on ADC group regular */
1467 if (LL_ADC_GetMultiDMATransfer(__LL_ADC_COMMON_INSTANCE(hadc->Instance)) != LL_ADC_MULTI_REG_DMA_EACH_ADC)
1469 SET_BIT(hadc->State, HAL_ADC_STATE_ERROR_CONFIG);
1470 return HAL_ERROR;
1472 else
1474 tmp_Flag_End = (ADC_FLAG_EOC);
1477 #else
1478 /* Check ADC DMA mode */
1479 if (READ_BIT(hadc->Instance->CFGR, ADC_CFGR_DMAEN) != 0UL)
1481 SET_BIT(hadc->State, HAL_ADC_STATE_ERROR_CONFIG);
1482 return HAL_ERROR;
1484 else
1486 tmp_Flag_End = (ADC_FLAG_EOC);
1488 #endif
1491 /* Get tick count */
1492 tickstart = HAL_GetTick();
1494 /* Wait until End of unitary conversion or sequence conversions flag is raised */
1495 while ((hadc->Instance->ISR & tmp_Flag_End) == 0UL)
1497 /* Check if timeout is disabled (set to infinite wait) */
1498 if (Timeout != HAL_MAX_DELAY)
1500 if (((HAL_GetTick() - tickstart) > Timeout) || (Timeout == 0UL))
1502 /* Update ADC state machine to timeout */
1503 SET_BIT(hadc->State, HAL_ADC_STATE_TIMEOUT);
1505 /* Process unlocked */
1506 __HAL_UNLOCK(hadc);
1508 return HAL_TIMEOUT;
1513 /* Update ADC state machine */
1514 SET_BIT(hadc->State, HAL_ADC_STATE_REG_EOC);
1516 /* Determine whether any further conversion upcoming on group regular */
1517 /* by external trigger, continuous mode or scan sequence on going. */
1518 if ((LL_ADC_REG_IsTriggerSourceSWStart(hadc->Instance) != 0UL)
1519 && (hadc->Init.ContinuousConvMode == DISABLE)
1522 /* Check whether end of sequence is reached */
1523 if (__HAL_ADC_GET_FLAG(hadc, ADC_FLAG_EOS))
1525 /* Set ADC state */
1526 CLEAR_BIT(hadc->State, HAL_ADC_STATE_REG_BUSY);
1528 if ((hadc->State & HAL_ADC_STATE_INJ_BUSY) == 0UL)
1530 SET_BIT(hadc->State, HAL_ADC_STATE_READY);
1535 /* Get relevant register CFGR in ADC instance of ADC master or slave */
1536 /* in function of multimode state (for devices with multimode */
1537 /* available). */
1538 #if defined(ADC_MULTIMODE_SUPPORT)
1539 if ((__LL_ADC_MULTI_INSTANCE_MASTER(hadc->Instance) == hadc->Instance)
1540 || (tmp_multimode_config == LL_ADC_MULTI_INDEPENDENT)
1541 || (tmp_multimode_config == LL_ADC_MULTI_DUAL_INJ_SIMULT)
1542 || (tmp_multimode_config == LL_ADC_MULTI_DUAL_INJ_ALTERN)
1545 /* Retrieve handle ADC CFGR register */
1546 tmp_cfgr = READ_REG(hadc->Instance->CFGR);
1548 else
1550 /* Retrieve Master ADC CFGR register */
1551 tmpADC_Master = __LL_ADC_MULTI_INSTANCE_MASTER(hadc->Instance);
1552 tmp_cfgr = READ_REG(tmpADC_Master->CFGR);
1554 #else
1555 /* Retrieve handle ADC CFGR register */
1556 tmp_cfgr = READ_REG(hadc->Instance->CFGR);
1557 #endif
1559 /* Clear polled flag */
1560 if (tmp_Flag_End == ADC_FLAG_EOS)
1562 __HAL_ADC_CLEAR_FLAG(hadc, ADC_FLAG_EOS);
1564 else
1566 /* Clear end of conversion EOC flag of regular group if low power feature */
1567 /* "LowPowerAutoWait " is disabled, to not interfere with this feature */
1568 /* until data register is read using function HAL_ADC_GetValue(). */
1569 if (READ_BIT(tmp_cfgr, ADC_CFGR_AUTDLY) == 0UL)
1571 __HAL_ADC_CLEAR_FLAG(hadc, (ADC_FLAG_EOC | ADC_FLAG_EOS));
1575 /* Return function status */
1576 return HAL_OK;
1580 * @brief Poll for ADC event.
1581 * @param hadc ADC handle
1582 * @param EventType the ADC event type.
1583 * This parameter can be one of the following values:
1584 * @arg @ref ADC_EOSMP_EVENT ADC End of Sampling event
1585 * @arg @ref ADC_AWD1_EVENT ADC Analog watchdog 1 event (main analog watchdog, present on all STM32 devices)
1586 * @arg @ref ADC_AWD2_EVENT ADC Analog watchdog 2 event (additional analog watchdog, not present on all STM32 families)
1587 * @arg @ref ADC_AWD3_EVENT ADC Analog watchdog 3 event (additional analog watchdog, not present on all STM32 families)
1588 * @arg @ref ADC_OVR_EVENT ADC Overrun event
1589 * @arg @ref ADC_JQOVF_EVENT ADC Injected context queue overflow event
1590 * @param Timeout Timeout value in millisecond.
1591 * @note The relevant flag is cleared if found to be set, except for ADC_FLAG_OVR.
1592 * Indeed, the latter is reset only if hadc->Init.Overrun field is set
1593 * to ADC_OVR_DATA_OVERWRITTEN. Otherwise, data register may be potentially overwritten
1594 * by a new converted data as soon as OVR is cleared.
1595 * To reset OVR flag once the preserved data is retrieved, the user can resort
1596 * to macro __HAL_ADC_CLEAR_FLAG(hadc, ADC_FLAG_OVR);
1597 * @retval HAL status
1599 HAL_StatusTypeDef HAL_ADC_PollForEvent(ADC_HandleTypeDef *hadc, uint32_t EventType, uint32_t Timeout)
1601 uint32_t tickstart;
1603 /* Check the parameters */
1604 assert_param(IS_ADC_ALL_INSTANCE(hadc->Instance));
1605 assert_param(IS_ADC_EVENT_TYPE(EventType));
1607 /* Get tick count */
1608 tickstart = HAL_GetTick();
1610 /* Check selected event flag */
1611 while (__HAL_ADC_GET_FLAG(hadc, EventType) == 0UL)
1613 /* Check if timeout is disabled (set to infinite wait) */
1614 if (Timeout != HAL_MAX_DELAY)
1616 if (((HAL_GetTick() - tickstart) > Timeout) || (Timeout == 0UL))
1618 /* Update ADC state machine to timeout */
1619 SET_BIT(hadc->State, HAL_ADC_STATE_TIMEOUT);
1621 /* Process unlocked */
1622 __HAL_UNLOCK(hadc);
1624 return HAL_TIMEOUT;
1629 switch (EventType)
1631 /* End Of Sampling event */
1632 case ADC_EOSMP_EVENT:
1633 /* Set ADC state */
1634 SET_BIT(hadc->State, HAL_ADC_STATE_REG_EOSMP);
1636 /* Clear the End Of Sampling flag */
1637 __HAL_ADC_CLEAR_FLAG(hadc, ADC_FLAG_EOSMP);
1639 break;
1641 /* Analog watchdog (level out of window) event */
1642 /* Note: In case of several analog watchdog enabled, if needed to know */
1643 /* which one triggered and on which ADCx, test ADC state of analog watchdog */
1644 /* flags HAL_ADC_STATE_AWD1/2/3 using function "HAL_ADC_GetState()". */
1645 /* For example: */
1646 /* " if ((HAL_ADC_GetState(hadc1) & HAL_ADC_STATE_AWD1) != 0UL) " */
1647 /* " if ((HAL_ADC_GetState(hadc1) & HAL_ADC_STATE_AWD2) != 0UL) " */
1648 /* " if ((HAL_ADC_GetState(hadc1) & HAL_ADC_STATE_AWD3) != 0UL) " */
1650 /* Check analog watchdog 1 flag */
1651 case ADC_AWD_EVENT:
1652 /* Set ADC state */
1653 SET_BIT(hadc->State, HAL_ADC_STATE_AWD1);
1655 /* Clear ADC analog watchdog flag */
1656 __HAL_ADC_CLEAR_FLAG(hadc, ADC_FLAG_AWD1);
1658 break;
1660 /* Check analog watchdog 2 flag */
1661 case ADC_AWD2_EVENT:
1662 /* Set ADC state */
1663 SET_BIT(hadc->State, HAL_ADC_STATE_AWD2);
1665 /* Clear ADC analog watchdog flag */
1666 __HAL_ADC_CLEAR_FLAG(hadc, ADC_FLAG_AWD2);
1668 break;
1670 /* Check analog watchdog 3 flag */
1671 case ADC_AWD3_EVENT:
1672 /* Set ADC state */
1673 SET_BIT(hadc->State, HAL_ADC_STATE_AWD3);
1675 /* Clear ADC analog watchdog flag */
1676 __HAL_ADC_CLEAR_FLAG(hadc, ADC_FLAG_AWD3);
1678 break;
1680 /* Injected context queue overflow event */
1681 case ADC_JQOVF_EVENT:
1682 /* Set ADC state */
1683 SET_BIT(hadc->State, HAL_ADC_STATE_INJ_JQOVF);
1685 /* Set ADC error code to Injected context queue overflow */
1686 SET_BIT(hadc->ErrorCode, HAL_ADC_ERROR_JQOVF);
1688 /* Clear ADC Injected context queue overflow flag */
1689 __HAL_ADC_CLEAR_FLAG(hadc, ADC_FLAG_JQOVF);
1691 break;
1693 /* Overrun event */
1694 default: /* Case ADC_OVR_EVENT */
1695 /* If overrun is set to overwrite previous data, overrun event is not */
1696 /* considered as an error. */
1697 /* (cf ref manual "Managing conversions without using the DMA and without */
1698 /* overrun ") */
1699 if (hadc->Init.Overrun == ADC_OVR_DATA_PRESERVED)
1701 /* Set ADC state */
1702 SET_BIT(hadc->State, HAL_ADC_STATE_REG_OVR);
1704 /* Set ADC error code to overrun */
1705 SET_BIT(hadc->ErrorCode, HAL_ADC_ERROR_OVR);
1707 else
1709 /* Clear ADC Overrun flag only if Overrun is set to ADC_OVR_DATA_OVERWRITTEN
1710 otherwise, data register is potentially overwritten by new converted data as soon
1711 as OVR is cleared. */
1712 __HAL_ADC_CLEAR_FLAG(hadc, ADC_FLAG_OVR);
1714 break;
1717 /* Return function status */
1718 return HAL_OK;
1722 * @brief Enable ADC, start conversion of regular group with interruption.
1723 * @note Interruptions enabled in this function according to initialization
1724 * setting : EOC (end of conversion), EOS (end of sequence),
1725 * OVR overrun.
1726 * Each of these interruptions has its dedicated callback function.
1727 * @note Case of multimode enabled (when multimode feature is available):
1728 * HAL_ADC_Start_IT() must be called for ADC Slave first, then for
1729 * ADC Master.
1730 * For ADC Slave, ADC is enabled only (conversion is not started).
1731 * For ADC Master, ADC is enabled and multimode conversion is started.
1732 * @note To guarantee a proper reset of all interruptions once all the needed
1733 * conversions are obtained, HAL_ADC_Stop_IT() must be called to ensure
1734 * a correct stop of the IT-based conversions.
1735 * @note By default, HAL_ADC_Start_IT() does not enable the End Of Sampling
1736 * interruption. If required (e.g. in case of oversampling with trigger
1737 * mode), the user must:
1738 * 1. first clear the EOSMP flag if set with macro __HAL_ADC_CLEAR_FLAG(hadc, ADC_FLAG_EOSMP)
1739 * 2. then enable the EOSMP interrupt with macro __HAL_ADC_ENABLE_IT(hadc, ADC_IT_EOSMP)
1740 * before calling HAL_ADC_Start_IT().
1741 * @param hadc ADC handle
1742 * @retval HAL status
1744 HAL_StatusTypeDef HAL_ADC_Start_IT(ADC_HandleTypeDef *hadc)
1746 HAL_StatusTypeDef tmp_hal_status;
1747 #if defined(ADC_MULTIMODE_SUPPORT)
1748 const ADC_TypeDef *tmpADC_Master;
1749 uint32_t tmp_multimode_config = LL_ADC_GetMultimode(__LL_ADC_COMMON_INSTANCE(hadc->Instance));
1750 #endif
1752 /* Check the parameters */
1753 assert_param(IS_ADC_ALL_INSTANCE(hadc->Instance));
1755 /* Perform ADC enable and conversion start if no conversion is on going */
1756 if (LL_ADC_REG_IsConversionOngoing(hadc->Instance) == 0UL)
1758 /* Process locked */
1759 __HAL_LOCK(hadc);
1761 /* Enable the ADC peripheral */
1762 tmp_hal_status = ADC_Enable(hadc);
1764 /* Start conversion if ADC is effectively enabled */
1765 if (tmp_hal_status == HAL_OK)
1767 /* Set ADC state */
1768 /* - Clear state bitfield related to regular group conversion results */
1769 /* - Set state bitfield related to regular operation */
1770 ADC_STATE_CLR_SET(hadc->State,
1771 HAL_ADC_STATE_READY | HAL_ADC_STATE_REG_EOC | HAL_ADC_STATE_REG_OVR | HAL_ADC_STATE_REG_EOSMP,
1772 HAL_ADC_STATE_REG_BUSY);
1774 #if defined(ADC_MULTIMODE_SUPPORT)
1775 /* Reset HAL_ADC_STATE_MULTIMODE_SLAVE bit
1776 - if ADC instance is master or if multimode feature is not available
1777 - if multimode setting is disabled (ADC instance slave in independent mode) */
1778 if ((__LL_ADC_MULTI_INSTANCE_MASTER(hadc->Instance) == hadc->Instance)
1779 || (tmp_multimode_config == LL_ADC_MULTI_INDEPENDENT)
1782 CLEAR_BIT(hadc->State, HAL_ADC_STATE_MULTIMODE_SLAVE);
1784 #endif
1786 /* Set ADC error code */
1787 /* Check if a conversion is on going on ADC group injected */
1788 if ((hadc->State & HAL_ADC_STATE_INJ_BUSY) != 0UL)
1790 /* Reset ADC error code fields related to regular conversions only */
1791 CLEAR_BIT(hadc->ErrorCode, (HAL_ADC_ERROR_OVR | HAL_ADC_ERROR_DMA));
1793 else
1795 /* Reset all ADC error code fields */
1796 ADC_CLEAR_ERRORCODE(hadc);
1799 /* Clear ADC group regular conversion flag and overrun flag */
1800 /* (To ensure of no unknown state from potential previous ADC operations) */
1801 __HAL_ADC_CLEAR_FLAG(hadc, (ADC_FLAG_EOC | ADC_FLAG_EOS | ADC_FLAG_OVR));
1803 /* Process unlocked */
1804 /* Unlock before starting ADC conversions: in case of potential */
1805 /* interruption, to let the process to ADC IRQ Handler. */
1806 __HAL_UNLOCK(hadc);
1808 /* Disable all interruptions before enabling the desired ones */
1809 __HAL_ADC_DISABLE_IT(hadc, (ADC_IT_EOC | ADC_IT_EOS | ADC_IT_OVR));
1811 /* Enable ADC end of conversion interrupt */
1812 switch (hadc->Init.EOCSelection)
1814 case ADC_EOC_SEQ_CONV:
1815 __HAL_ADC_ENABLE_IT(hadc, ADC_IT_EOS);
1816 break;
1817 /* case ADC_EOC_SINGLE_CONV */
1818 default:
1819 __HAL_ADC_ENABLE_IT(hadc, ADC_IT_EOC);
1820 break;
1823 /* Enable ADC overrun interrupt */
1824 /* If hadc->Init.Overrun is set to ADC_OVR_DATA_PRESERVED, only then is
1825 ADC_IT_OVR enabled; otherwise data overwrite is considered as normal
1826 behavior and no CPU time is lost for a non-processed interruption */
1827 if (hadc->Init.Overrun == ADC_OVR_DATA_PRESERVED)
1829 __HAL_ADC_ENABLE_IT(hadc, ADC_IT_OVR);
1832 /* Enable conversion of regular group. */
1833 /* If software start has been selected, conversion starts immediately. */
1834 /* If external trigger has been selected, conversion will start at next */
1835 /* trigger event. */
1836 /* Case of multimode enabled (when multimode feature is available): */
1837 /* - if ADC is slave and dual regular conversions are enabled, ADC is */
1838 /* enabled only (conversion is not started), */
1839 /* - if ADC is master, ADC is enabled and conversion is started. */
1840 #if defined(ADC_MULTIMODE_SUPPORT)
1841 if ((__LL_ADC_MULTI_INSTANCE_MASTER(hadc->Instance) == hadc->Instance)
1842 || (tmp_multimode_config == LL_ADC_MULTI_INDEPENDENT)
1843 || (tmp_multimode_config == LL_ADC_MULTI_DUAL_INJ_SIMULT)
1844 || (tmp_multimode_config == LL_ADC_MULTI_DUAL_INJ_ALTERN)
1847 /* ADC instance is not a multimode slave instance with multimode regular conversions enabled */
1848 if (READ_BIT(hadc->Instance->CFGR, ADC_CFGR_JAUTO) != 0UL)
1850 ADC_STATE_CLR_SET(hadc->State, HAL_ADC_STATE_INJ_EOC, HAL_ADC_STATE_INJ_BUSY);
1852 /* Enable as well injected interruptions in case
1853 HAL_ADCEx_InjectedStart_IT() has not been called beforehand. This
1854 allows to start regular and injected conversions when JAUTO is
1855 set with a single call to HAL_ADC_Start_IT() */
1856 switch (hadc->Init.EOCSelection)
1858 case ADC_EOC_SEQ_CONV:
1859 __HAL_ADC_DISABLE_IT(hadc, ADC_IT_JEOC);
1860 __HAL_ADC_ENABLE_IT(hadc, ADC_IT_JEOS);
1861 break;
1862 /* case ADC_EOC_SINGLE_CONV */
1863 default:
1864 __HAL_ADC_DISABLE_IT(hadc, ADC_IT_JEOS);
1865 __HAL_ADC_ENABLE_IT(hadc, ADC_IT_JEOC);
1866 break;
1870 /* Start ADC group regular conversion */
1871 LL_ADC_REG_StartConversion(hadc->Instance);
1873 else
1875 /* ADC instance is a multimode slave instance with multimode regular conversions enabled */
1876 SET_BIT(hadc->State, HAL_ADC_STATE_MULTIMODE_SLAVE);
1877 /* if Master ADC JAUTO bit is set, Slave injected interruptions
1878 are enabled nevertheless (for same reason as above) */
1879 tmpADC_Master = __LL_ADC_MULTI_INSTANCE_MASTER(hadc->Instance);
1880 if (READ_BIT(tmpADC_Master->CFGR, ADC_CFGR_JAUTO) != 0UL)
1882 /* First, update Slave State in setting HAL_ADC_STATE_INJ_BUSY bit
1883 and in resetting HAL_ADC_STATE_INJ_EOC bit */
1884 ADC_STATE_CLR_SET(hadc->State, HAL_ADC_STATE_INJ_EOC, HAL_ADC_STATE_INJ_BUSY);
1885 /* Next, set Slave injected interruptions */
1886 switch (hadc->Init.EOCSelection)
1888 case ADC_EOC_SEQ_CONV:
1889 __HAL_ADC_DISABLE_IT(hadc, ADC_IT_JEOC);
1890 __HAL_ADC_ENABLE_IT(hadc, ADC_IT_JEOS);
1891 break;
1892 /* case ADC_EOC_SINGLE_CONV */
1893 default:
1894 __HAL_ADC_DISABLE_IT(hadc, ADC_IT_JEOS);
1895 __HAL_ADC_ENABLE_IT(hadc, ADC_IT_JEOC);
1896 break;
1900 #else
1901 /* ADC instance is not a multimode slave instance with multimode regular conversions enabled */
1902 if (READ_BIT(hadc->Instance->CFGR, ADC_CFGR_JAUTO) != 0UL)
1904 ADC_STATE_CLR_SET(hadc->State, HAL_ADC_STATE_INJ_EOC, HAL_ADC_STATE_INJ_BUSY);
1906 /* Enable as well injected interruptions in case
1907 HAL_ADCEx_InjectedStart_IT() has not been called beforehand. This
1908 allows to start regular and injected conversions when JAUTO is
1909 set with a single call to HAL_ADC_Start_IT() */
1910 switch (hadc->Init.EOCSelection)
1912 case ADC_EOC_SEQ_CONV:
1913 __HAL_ADC_DISABLE_IT(hadc, ADC_IT_JEOC);
1914 __HAL_ADC_ENABLE_IT(hadc, ADC_IT_JEOS);
1915 break;
1916 /* case ADC_EOC_SINGLE_CONV */
1917 default:
1918 __HAL_ADC_DISABLE_IT(hadc, ADC_IT_JEOS);
1919 __HAL_ADC_ENABLE_IT(hadc, ADC_IT_JEOC);
1920 break;
1924 /* Start ADC group regular conversion */
1925 LL_ADC_REG_StartConversion(hadc->Instance);
1926 #endif
1928 else
1930 /* Process unlocked */
1931 __HAL_UNLOCK(hadc);
1935 else
1937 tmp_hal_status = HAL_BUSY;
1940 /* Return function status */
1941 return tmp_hal_status;
1945 * @brief Stop ADC conversion of regular group (and injected group in
1946 * case of auto_injection mode), disable interrution of
1947 * end-of-conversion, disable ADC peripheral.
1948 * @param hadc ADC handle
1949 * @retval HAL status.
1951 HAL_StatusTypeDef HAL_ADC_Stop_IT(ADC_HandleTypeDef *hadc)
1953 HAL_StatusTypeDef tmp_hal_status;
1955 /* Check the parameters */
1956 assert_param(IS_ADC_ALL_INSTANCE(hadc->Instance));
1958 /* Process locked */
1959 __HAL_LOCK(hadc);
1961 /* 1. Stop potential conversion on going, on ADC groups regular and injected */
1962 tmp_hal_status = ADC_ConversionStop(hadc, ADC_REGULAR_INJECTED_GROUP);
1964 /* Disable ADC peripheral if conversions are effectively stopped */
1965 if (tmp_hal_status == HAL_OK)
1967 /* Disable ADC end of conversion interrupt for regular group */
1968 /* Disable ADC overrun interrupt */
1969 __HAL_ADC_DISABLE_IT(hadc, (ADC_IT_EOC | ADC_IT_EOS | ADC_IT_OVR));
1971 /* 2. Disable the ADC peripheral */
1972 tmp_hal_status = ADC_Disable(hadc);
1974 /* Check if ADC is effectively disabled */
1975 if (tmp_hal_status == HAL_OK)
1977 /* Set ADC state */
1978 ADC_STATE_CLR_SET(hadc->State,
1979 HAL_ADC_STATE_REG_BUSY | HAL_ADC_STATE_INJ_BUSY,
1980 HAL_ADC_STATE_READY);
1984 /* Process unlocked */
1985 __HAL_UNLOCK(hadc);
1987 /* Return function status */
1988 return tmp_hal_status;
1992 * @brief Enable ADC, start conversion of regular group and transfer result through DMA.
1993 * @note Interruptions enabled in this function:
1994 * overrun (if applicable), DMA half transfer, DMA transfer complete.
1995 * Each of these interruptions has its dedicated callback function.
1996 * @note Case of multimode enabled (when multimode feature is available): HAL_ADC_Start_DMA()
1997 * is designed for single-ADC mode only. For multimode, the dedicated
1998 * HAL_ADCEx_MultiModeStart_DMA() function must be used.
1999 * @param hadc ADC handle
2000 * @param pData Destination Buffer address.
2001 * @param Length Number of data to be transferred from ADC peripheral to memory
2002 * @retval HAL status.
2004 HAL_StatusTypeDef HAL_ADC_Start_DMA(ADC_HandleTypeDef *hadc, uint32_t *pData, uint32_t Length)
2006 HAL_StatusTypeDef tmp_hal_status;
2007 #if defined(ADC_MULTIMODE_SUPPORT)
2008 uint32_t tmp_multimode_config = LL_ADC_GetMultimode(__LL_ADC_COMMON_INSTANCE(hadc->Instance));
2009 #endif
2011 /* Check the parameters */
2012 assert_param(IS_ADC_ALL_INSTANCE(hadc->Instance));
2014 /* Perform ADC enable and conversion start if no conversion is on going */
2015 if (LL_ADC_REG_IsConversionOngoing(hadc->Instance) == 0UL)
2017 /* Process locked */
2018 __HAL_LOCK(hadc);
2020 #if defined(ADC_MULTIMODE_SUPPORT)
2021 /* Ensure that multimode regular conversions are not enabled. */
2022 /* Otherwise, dedicated API HAL_ADCEx_MultiModeStart_DMA() must be used. */
2023 if ((tmp_multimode_config == LL_ADC_MULTI_INDEPENDENT)
2024 || (tmp_multimode_config == LL_ADC_MULTI_DUAL_INJ_SIMULT)
2025 || (tmp_multimode_config == LL_ADC_MULTI_DUAL_INJ_ALTERN)
2027 #endif
2029 /* Enable the ADC peripheral */
2030 tmp_hal_status = ADC_Enable(hadc);
2032 /* Start conversion if ADC is effectively enabled */
2033 if (tmp_hal_status == HAL_OK)
2035 /* Set ADC state */
2036 /* - Clear state bitfield related to regular group conversion results */
2037 /* - Set state bitfield related to regular operation */
2038 ADC_STATE_CLR_SET(hadc->State,
2039 HAL_ADC_STATE_READY | HAL_ADC_STATE_REG_EOC | HAL_ADC_STATE_REG_OVR | HAL_ADC_STATE_REG_EOSMP,
2040 HAL_ADC_STATE_REG_BUSY);
2042 #if defined(ADC_MULTIMODE_SUPPORT)
2043 /* Reset HAL_ADC_STATE_MULTIMODE_SLAVE bit
2044 - if ADC instance is master or if multimode feature is not available
2045 - if multimode setting is disabled (ADC instance slave in independent mode) */
2046 if ((__LL_ADC_MULTI_INSTANCE_MASTER(hadc->Instance) == hadc->Instance)
2047 || (tmp_multimode_config == LL_ADC_MULTI_INDEPENDENT)
2050 CLEAR_BIT(hadc->State, HAL_ADC_STATE_MULTIMODE_SLAVE);
2052 #endif
2054 /* Check if a conversion is on going on ADC group injected */
2055 if ((hadc->State & HAL_ADC_STATE_INJ_BUSY) != 0UL)
2057 /* Reset ADC error code fields related to regular conversions only */
2058 CLEAR_BIT(hadc->ErrorCode, (HAL_ADC_ERROR_OVR | HAL_ADC_ERROR_DMA));
2060 else
2062 /* Reset all ADC error code fields */
2063 ADC_CLEAR_ERRORCODE(hadc);
2066 /* Set the DMA transfer complete callback */
2067 hadc->DMA_Handle->XferCpltCallback = ADC_DMAConvCplt;
2069 /* Set the DMA half transfer complete callback */
2070 hadc->DMA_Handle->XferHalfCpltCallback = ADC_DMAHalfConvCplt;
2072 /* Set the DMA error callback */
2073 hadc->DMA_Handle->XferErrorCallback = ADC_DMAError;
2076 /* Manage ADC and DMA start: ADC overrun interruption, DMA start, */
2077 /* ADC start (in case of SW start): */
2079 /* Clear regular group conversion flag and overrun flag */
2080 /* (To ensure of no unknown state from potential previous ADC */
2081 /* operations) */
2082 __HAL_ADC_CLEAR_FLAG(hadc, (ADC_FLAG_EOC | ADC_FLAG_EOS | ADC_FLAG_OVR));
2084 /* Process unlocked */
2085 /* Unlock before starting ADC conversions: in case of potential */
2086 /* interruption, to let the process to ADC IRQ Handler. */
2087 __HAL_UNLOCK(hadc);
2089 /* With DMA, overrun event is always considered as an error even if
2090 hadc->Init.Overrun is set to ADC_OVR_DATA_OVERWRITTEN. Therefore,
2091 ADC_IT_OVR is enabled. */
2092 __HAL_ADC_ENABLE_IT(hadc, ADC_IT_OVR);
2094 /* Enable ADC DMA mode */
2095 SET_BIT(hadc->Instance->CFGR, ADC_CFGR_DMAEN);
2097 /* Start the DMA channel */
2098 tmp_hal_status = HAL_DMA_Start_IT(hadc->DMA_Handle, (uint32_t)&hadc->Instance->DR, (uint32_t)pData, Length);
2100 /* Enable conversion of regular group. */
2101 /* If software start has been selected, conversion starts immediately. */
2102 /* If external trigger has been selected, conversion will start at next */
2103 /* trigger event. */
2104 /* Start ADC group regular conversion */
2105 LL_ADC_REG_StartConversion(hadc->Instance);
2107 else
2109 /* Process unlocked */
2110 __HAL_UNLOCK(hadc);
2114 #if defined(ADC_MULTIMODE_SUPPORT)
2115 else
2117 tmp_hal_status = HAL_ERROR;
2118 /* Process unlocked */
2119 __HAL_UNLOCK(hadc);
2121 #endif
2123 else
2125 tmp_hal_status = HAL_BUSY;
2128 /* Return function status */
2129 return tmp_hal_status;
2133 * @brief Stop ADC conversion of regular group (and injected group in
2134 * case of auto_injection mode), disable ADC DMA transfer, disable
2135 * ADC peripheral.
2136 * @note: ADC peripheral disable is forcing stop of potential
2137 * conversion on ADC group injected. If ADC group injected is under use, it
2138 * should be preliminarily stopped using HAL_ADCEx_InjectedStop function.
2139 * @note Case of multimode enabled (when multimode feature is available):
2140 * HAL_ADC_Stop_DMA() function is dedicated to single-ADC mode only.
2141 * For multimode, the dedicated HAL_ADCEx_MultiModeStop_DMA() API must be used.
2142 * @param hadc ADC handle
2143 * @retval HAL status.
2145 HAL_StatusTypeDef HAL_ADC_Stop_DMA(ADC_HandleTypeDef *hadc)
2147 HAL_StatusTypeDef tmp_hal_status;
2149 /* Check the parameters */
2150 assert_param(IS_ADC_ALL_INSTANCE(hadc->Instance));
2152 /* Process locked */
2153 __HAL_LOCK(hadc);
2155 /* 1. Stop potential ADC group regular conversion on going */
2156 tmp_hal_status = ADC_ConversionStop(hadc, ADC_REGULAR_INJECTED_GROUP);
2158 /* Disable ADC peripheral if conversions are effectively stopped */
2159 if (tmp_hal_status == HAL_OK)
2161 /* Disable ADC DMA (ADC DMA configuration of continous requests is kept) */
2162 CLEAR_BIT(hadc->Instance->CFGR, ADC_CFGR_DMAEN);
2164 /* Disable the DMA channel (in case of DMA in circular mode or stop */
2165 /* while DMA transfer is on going) */
2166 if (hadc->DMA_Handle->State == HAL_DMA_STATE_BUSY)
2168 tmp_hal_status = HAL_DMA_Abort(hadc->DMA_Handle);
2170 /* Check if DMA channel effectively disabled */
2171 if (tmp_hal_status != HAL_OK)
2173 /* Update ADC state machine to error */
2174 SET_BIT(hadc->State, HAL_ADC_STATE_ERROR_DMA);
2178 /* Disable ADC overrun interrupt */
2179 __HAL_ADC_DISABLE_IT(hadc, ADC_IT_OVR);
2181 /* 2. Disable the ADC peripheral */
2182 /* Update "tmp_hal_status" only if DMA channel disabling passed, */
2183 /* to keep in memory a potential failing status. */
2184 if (tmp_hal_status == HAL_OK)
2186 tmp_hal_status = ADC_Disable(hadc);
2188 else
2190 (void)ADC_Disable(hadc);
2193 /* Check if ADC is effectively disabled */
2194 if (tmp_hal_status == HAL_OK)
2196 /* Set ADC state */
2197 ADC_STATE_CLR_SET(hadc->State,
2198 HAL_ADC_STATE_REG_BUSY | HAL_ADC_STATE_INJ_BUSY,
2199 HAL_ADC_STATE_READY);
2204 /* Process unlocked */
2205 __HAL_UNLOCK(hadc);
2207 /* Return function status */
2208 return tmp_hal_status;
2212 * @brief Get ADC regular group conversion result.
2213 * @note Reading register DR automatically clears ADC flag EOC
2214 * (ADC group regular end of unitary conversion).
2215 * @note This function does not clear ADC flag EOS
2216 * (ADC group regular end of sequence conversion).
2217 * Occurrence of flag EOS rising:
2218 * - If sequencer is composed of 1 rank, flag EOS is equivalent
2219 * to flag EOC.
2220 * - If sequencer is composed of several ranks, during the scan
2221 * sequence flag EOC only is raised, at the end of the scan sequence
2222 * both flags EOC and EOS are raised.
2223 * To clear this flag, either use function:
2224 * in programming model IT: @ref HAL_ADC_IRQHandler(), in programming
2225 * model polling: @ref HAL_ADC_PollForConversion()
2226 * or @ref __HAL_ADC_CLEAR_FLAG(&hadc, ADC_FLAG_EOS).
2227 * @param hadc ADC handle
2228 * @retval ADC group regular conversion data
2230 uint32_t HAL_ADC_GetValue(ADC_HandleTypeDef *hadc)
2232 /* Check the parameters */
2233 assert_param(IS_ADC_ALL_INSTANCE(hadc->Instance));
2235 /* Note: EOC flag is not cleared here by software because automatically */
2236 /* cleared by hardware when reading register DR. */
2238 /* Return ADC converted value */
2239 return hadc->Instance->DR;
2243 * @brief Start ADC conversion sampling phase of regular group
2244 * @note: This function should only be called to start sampling when
2245 * - @ref ADC_SAMPLING_MODE_TRIGGER_CONTROLED sampling
2246 * mode has been selected
2247 * - @ref ADC_SOFTWARE_START has been selected as trigger source
2248 * @param hadc ADC handle
2249 * @retval HAL status.
2251 HAL_StatusTypeDef HAL_ADC_StartSampling(ADC_HandleTypeDef *hadc)
2253 /* Check the parameters */
2254 assert_param(IS_ADC_ALL_INSTANCE(hadc->Instance));
2256 /* Start sampling */
2257 SET_BIT(hadc->Instance->CFGR2, ADC_CFGR2_SWTRIG);
2259 /* Return function status */
2260 return HAL_OK;
2264 * @brief Stop ADC conversion sampling phase of regular group and start conversion
2265 * @note: This function should only be called to stop sampling when
2266 * - @ref ADC_SAMPLING_MODE_TRIGGER_CONTROLED sampling
2267 * mode has been selected
2268 * - @ref ADC_SOFTWARE_START has been selected as trigger source
2269 * - after sampling has been started using @ref HAL_ADC_StartSampling.
2270 * @param hadc ADC handle
2271 * @retval HAL status.
2273 HAL_StatusTypeDef HAL_ADC_StopSampling(ADC_HandleTypeDef *hadc)
2275 /* Check the parameters */
2276 assert_param(IS_ADC_ALL_INSTANCE(hadc->Instance));
2278 /* Start sampling */
2279 CLEAR_BIT(hadc->Instance->CFGR2, ADC_CFGR2_SWTRIG);
2281 /* Return function status */
2282 return HAL_OK;
2286 * @brief Handle ADC interrupt request.
2287 * @param hadc ADC handle
2288 * @retval None
2290 void HAL_ADC_IRQHandler(ADC_HandleTypeDef *hadc)
2292 uint32_t overrun_error = 0UL; /* flag set if overrun occurrence has to be considered as an error */
2293 uint32_t tmp_isr = hadc->Instance->ISR;
2294 uint32_t tmp_ier = hadc->Instance->IER;
2295 uint32_t tmp_adc_inj_is_trigger_source_sw_start;
2296 uint32_t tmp_adc_reg_is_trigger_source_sw_start;
2297 uint32_t tmp_cfgr;
2298 #if defined(ADC_MULTIMODE_SUPPORT)
2299 const ADC_TypeDef *tmpADC_Master;
2300 uint32_t tmp_multimode_config = LL_ADC_GetMultimode(__LL_ADC_COMMON_INSTANCE(hadc->Instance));
2301 #endif
2303 /* Check the parameters */
2304 assert_param(IS_ADC_ALL_INSTANCE(hadc->Instance));
2305 assert_param(IS_ADC_EOC_SELECTION(hadc->Init.EOCSelection));
2307 /* ========== Check End of Sampling flag for ADC group regular ========== */
2308 if (((tmp_isr & ADC_FLAG_EOSMP) == ADC_FLAG_EOSMP) && ((tmp_ier & ADC_IT_EOSMP) == ADC_IT_EOSMP))
2310 /* Update state machine on end of sampling status if not in error state */
2311 if ((hadc->State & HAL_ADC_STATE_ERROR_INTERNAL) == 0UL)
2313 /* Set ADC state */
2314 SET_BIT(hadc->State, HAL_ADC_STATE_REG_EOSMP);
2317 /* End Of Sampling callback */
2318 #if (USE_HAL_ADC_REGISTER_CALLBACKS == 1)
2319 hadc->EndOfSamplingCallback(hadc);
2320 #else
2321 HAL_ADCEx_EndOfSamplingCallback(hadc);
2322 #endif /* USE_HAL_ADC_REGISTER_CALLBACKS */
2324 /* Clear regular group conversion flag */
2325 __HAL_ADC_CLEAR_FLAG(hadc, ADC_FLAG_EOSMP);
2328 /* ====== Check ADC group regular end of unitary conversion sequence conversions ===== */
2329 if ((((tmp_isr & ADC_FLAG_EOC) == ADC_FLAG_EOC) && ((tmp_ier & ADC_IT_EOC) == ADC_IT_EOC)) ||
2330 (((tmp_isr & ADC_FLAG_EOS) == ADC_FLAG_EOS) && ((tmp_ier & ADC_IT_EOS) == ADC_IT_EOS)))
2332 /* Update state machine on conversion status if not in error state */
2333 if ((hadc->State & HAL_ADC_STATE_ERROR_INTERNAL) == 0UL)
2335 /* Set ADC state */
2336 SET_BIT(hadc->State, HAL_ADC_STATE_REG_EOC);
2339 /* Determine whether any further conversion upcoming on group regular */
2340 /* by external trigger, continuous mode or scan sequence on going */
2341 /* to disable interruption. */
2342 if (LL_ADC_REG_IsTriggerSourceSWStart(hadc->Instance) != 0UL)
2344 /* Get relevant register CFGR in ADC instance of ADC master or slave */
2345 /* in function of multimode state (for devices with multimode */
2346 /* available). */
2347 #if defined(ADC_MULTIMODE_SUPPORT)
2348 if ((__LL_ADC_MULTI_INSTANCE_MASTER(hadc->Instance) == hadc->Instance)
2349 || (tmp_multimode_config == LL_ADC_MULTI_INDEPENDENT)
2350 || (tmp_multimode_config == LL_ADC_MULTI_DUAL_INJ_SIMULT)
2351 || (tmp_multimode_config == LL_ADC_MULTI_DUAL_INJ_ALTERN)
2354 /* check CONT bit directly in handle ADC CFGR register */
2355 tmp_cfgr = READ_REG(hadc->Instance->CFGR);
2357 else
2359 /* else need to check Master ADC CONT bit */
2360 tmpADC_Master = __LL_ADC_MULTI_INSTANCE_MASTER(hadc->Instance);
2361 tmp_cfgr = READ_REG(tmpADC_Master->CFGR);
2363 #else
2364 tmp_cfgr = READ_REG(hadc->Instance->CFGR);
2365 #endif
2367 /* Carry on if continuous mode is disabled */
2368 if (READ_BIT(tmp_cfgr, ADC_CFGR_CONT) != ADC_CFGR_CONT)
2370 /* If End of Sequence is reached, disable interrupts */
2371 if (__HAL_ADC_GET_FLAG(hadc, ADC_FLAG_EOS))
2373 /* Allowed to modify bits ADC_IT_EOC/ADC_IT_EOS only if bit */
2374 /* ADSTART==0 (no conversion on going) */
2375 if (LL_ADC_REG_IsConversionOngoing(hadc->Instance) == 0UL)
2377 /* Disable ADC end of sequence conversion interrupt */
2378 /* Note: Overrun interrupt was enabled with EOC interrupt in */
2379 /* HAL_Start_IT(), but is not disabled here because can be used */
2380 /* by overrun IRQ process below. */
2381 __HAL_ADC_DISABLE_IT(hadc, ADC_IT_EOC | ADC_IT_EOS);
2383 /* Set ADC state */
2384 CLEAR_BIT(hadc->State, HAL_ADC_STATE_REG_BUSY);
2386 if ((hadc->State & HAL_ADC_STATE_INJ_BUSY) == 0UL)
2388 SET_BIT(hadc->State, HAL_ADC_STATE_READY);
2391 else
2393 /* Change ADC state to error state */
2394 SET_BIT(hadc->State, HAL_ADC_STATE_ERROR_INTERNAL);
2396 /* Set ADC error code to ADC peripheral internal error */
2397 SET_BIT(hadc->ErrorCode, HAL_ADC_ERROR_INTERNAL);
2403 /* Conversion complete callback */
2404 /* Note: Into callback function "HAL_ADC_ConvCpltCallback()", */
2405 /* to determine if conversion has been triggered from EOC or EOS, */
2406 /* possibility to use: */
2407 /* " if( __HAL_ADC_GET_FLAG(&hadc, ADC_FLAG_EOS)) " */
2408 #if (USE_HAL_ADC_REGISTER_CALLBACKS == 1)
2409 hadc->ConvCpltCallback(hadc);
2410 #else
2411 HAL_ADC_ConvCpltCallback(hadc);
2412 #endif /* USE_HAL_ADC_REGISTER_CALLBACKS */
2414 /* Clear regular group conversion flag */
2415 /* Note: in case of overrun set to ADC_OVR_DATA_PRESERVED, end of */
2416 /* conversion flags clear induces the release of the preserved data.*/
2417 /* Therefore, if the preserved data value is needed, it must be */
2418 /* read preliminarily into HAL_ADC_ConvCpltCallback(). */
2419 __HAL_ADC_CLEAR_FLAG(hadc, (ADC_FLAG_EOC | ADC_FLAG_EOS));
2422 /* ====== Check ADC group injected end of unitary conversion sequence conversions ===== */
2423 if ((((tmp_isr & ADC_FLAG_JEOC) == ADC_FLAG_JEOC) && ((tmp_ier & ADC_IT_JEOC) == ADC_IT_JEOC)) ||
2424 (((tmp_isr & ADC_FLAG_JEOS) == ADC_FLAG_JEOS) && ((tmp_ier & ADC_IT_JEOS) == ADC_IT_JEOS)))
2426 /* Update state machine on conversion status if not in error state */
2427 if ((hadc->State & HAL_ADC_STATE_ERROR_INTERNAL) == 0UL)
2429 /* Set ADC state */
2430 SET_BIT(hadc->State, HAL_ADC_STATE_INJ_EOC);
2433 /* Retrieve ADC configuration */
2434 tmp_adc_inj_is_trigger_source_sw_start = LL_ADC_INJ_IsTriggerSourceSWStart(hadc->Instance);
2435 tmp_adc_reg_is_trigger_source_sw_start = LL_ADC_REG_IsTriggerSourceSWStart(hadc->Instance);
2436 /* Get relevant register CFGR in ADC instance of ADC master or slave */
2437 /* in function of multimode state (for devices with multimode */
2438 /* available). */
2439 #if defined(ADC_MULTIMODE_SUPPORT)
2440 if ((__LL_ADC_MULTI_INSTANCE_MASTER(hadc->Instance) == hadc->Instance)
2441 || (tmp_multimode_config == LL_ADC_MULTI_INDEPENDENT)
2442 || (tmp_multimode_config == LL_ADC_MULTI_DUAL_REG_SIMULT)
2443 || (tmp_multimode_config == LL_ADC_MULTI_DUAL_REG_INTERL)
2446 tmp_cfgr = READ_REG(hadc->Instance->CFGR);
2448 else
2450 tmpADC_Master = __LL_ADC_MULTI_INSTANCE_MASTER(hadc->Instance);
2451 tmp_cfgr = READ_REG(tmpADC_Master->CFGR);
2453 #else
2454 tmp_cfgr = READ_REG(hadc->Instance->CFGR);
2455 #endif
2457 /* Disable interruption if no further conversion upcoming by injected */
2458 /* external trigger or by automatic injected conversion with regular */
2459 /* group having no further conversion upcoming (same conditions as */
2460 /* regular group interruption disabling above), */
2461 /* and if injected scan sequence is completed. */
2462 if ((tmp_adc_inj_is_trigger_source_sw_start != 0UL) ||
2463 ((READ_BIT(tmp_cfgr, ADC_CFGR_JAUTO) == 0UL) &&
2464 ((tmp_adc_reg_is_trigger_source_sw_start != 0UL) &&
2465 (READ_BIT(tmp_cfgr, ADC_CFGR_CONT) == 0UL))))
2467 /* If End of Sequence is reached, disable interrupts */
2468 if (__HAL_ADC_GET_FLAG(hadc, ADC_FLAG_JEOS))
2470 /* Particular case if injected contexts queue is enabled: */
2471 /* when the last context has been fully processed, JSQR is reset */
2472 /* by the hardware. Even if no injected conversion is planned to come */
2473 /* (queue empty, triggers are ignored), it can start again */
2474 /* immediately after setting a new context (JADSTART is still set). */
2475 /* Therefore, state of HAL ADC injected group is kept to busy. */
2476 if (READ_BIT(tmp_cfgr, ADC_CFGR_JQM) == 0UL)
2478 /* Allowed to modify bits ADC_IT_JEOC/ADC_IT_JEOS only if bit */
2479 /* JADSTART==0 (no conversion on going) */
2480 if (LL_ADC_INJ_IsConversionOngoing(hadc->Instance) == 0UL)
2482 /* Disable ADC end of sequence conversion interrupt */
2483 __HAL_ADC_DISABLE_IT(hadc, ADC_IT_JEOC | ADC_IT_JEOS);
2485 /* Set ADC state */
2486 CLEAR_BIT(hadc->State, HAL_ADC_STATE_INJ_BUSY);
2488 if ((hadc->State & HAL_ADC_STATE_REG_BUSY) == 0UL)
2490 SET_BIT(hadc->State, HAL_ADC_STATE_READY);
2493 else
2495 /* Update ADC state machine to error */
2496 SET_BIT(hadc->State, HAL_ADC_STATE_ERROR_INTERNAL);
2498 /* Set ADC error code to ADC peripheral internal error */
2499 SET_BIT(hadc->ErrorCode, HAL_ADC_ERROR_INTERNAL);
2505 /* Injected Conversion complete callback */
2506 /* Note: HAL_ADCEx_InjectedConvCpltCallback can resort to
2507 if( __HAL_ADC_GET_FLAG(&hadc, ADC_FLAG_JEOS)) or
2508 if( __HAL_ADC_GET_FLAG(&hadc, ADC_FLAG_JEOC)) to determine whether
2509 interruption has been triggered by end of conversion or end of
2510 sequence. */
2511 #if (USE_HAL_ADC_REGISTER_CALLBACKS == 1)
2512 hadc->InjectedConvCpltCallback(hadc);
2513 #else
2514 HAL_ADCEx_InjectedConvCpltCallback(hadc);
2515 #endif /* USE_HAL_ADC_REGISTER_CALLBACKS */
2517 /* Clear injected group conversion flag */
2518 __HAL_ADC_CLEAR_FLAG(hadc, ADC_FLAG_JEOC | ADC_FLAG_JEOS);
2521 /* ========== Check Analog watchdog 1 flag ========== */
2522 if (((tmp_isr & ADC_FLAG_AWD1) == ADC_FLAG_AWD1) && ((tmp_ier & ADC_IT_AWD1) == ADC_IT_AWD1))
2524 /* Set ADC state */
2525 SET_BIT(hadc->State, HAL_ADC_STATE_AWD1);
2527 /* Level out of window 1 callback */
2528 #if (USE_HAL_ADC_REGISTER_CALLBACKS == 1)
2529 hadc->LevelOutOfWindowCallback(hadc);
2530 #else
2531 HAL_ADC_LevelOutOfWindowCallback(hadc);
2532 #endif /* USE_HAL_ADC_REGISTER_CALLBACKS */
2534 /* Clear ADC analog watchdog flag */
2535 __HAL_ADC_CLEAR_FLAG(hadc, ADC_FLAG_AWD1);
2538 /* ========== Check analog watchdog 2 flag ========== */
2539 if (((tmp_isr & ADC_FLAG_AWD2) == ADC_FLAG_AWD2) && ((tmp_ier & ADC_IT_AWD2) == ADC_IT_AWD2))
2541 /* Set ADC state */
2542 SET_BIT(hadc->State, HAL_ADC_STATE_AWD2);
2544 /* Level out of window 2 callback */
2545 #if (USE_HAL_ADC_REGISTER_CALLBACKS == 1)
2546 hadc->LevelOutOfWindow2Callback(hadc);
2547 #else
2548 HAL_ADCEx_LevelOutOfWindow2Callback(hadc);
2549 #endif /* USE_HAL_ADC_REGISTER_CALLBACKS */
2551 /* Clear ADC analog watchdog flag */
2552 __HAL_ADC_CLEAR_FLAG(hadc, ADC_FLAG_AWD2);
2555 /* ========== Check analog watchdog 3 flag ========== */
2556 if (((tmp_isr & ADC_FLAG_AWD3) == ADC_FLAG_AWD3) && ((tmp_ier & ADC_IT_AWD3) == ADC_IT_AWD3))
2558 /* Set ADC state */
2559 SET_BIT(hadc->State, HAL_ADC_STATE_AWD3);
2561 /* Level out of window 3 callback */
2562 #if (USE_HAL_ADC_REGISTER_CALLBACKS == 1)
2563 hadc->LevelOutOfWindow3Callback(hadc);
2564 #else
2565 HAL_ADCEx_LevelOutOfWindow3Callback(hadc);
2566 #endif /* USE_HAL_ADC_REGISTER_CALLBACKS */
2568 /* Clear ADC analog watchdog flag */
2569 __HAL_ADC_CLEAR_FLAG(hadc, ADC_FLAG_AWD3);
2572 /* ========== Check Overrun flag ========== */
2573 if (((tmp_isr & ADC_FLAG_OVR) == ADC_FLAG_OVR) && ((tmp_ier & ADC_IT_OVR) == ADC_IT_OVR))
2575 /* If overrun is set to overwrite previous data (default setting), */
2576 /* overrun event is not considered as an error. */
2577 /* (cf ref manual "Managing conversions without using the DMA and without */
2578 /* overrun ") */
2579 /* Exception for usage with DMA overrun event always considered as an */
2580 /* error. */
2581 if (hadc->Init.Overrun == ADC_OVR_DATA_PRESERVED)
2583 overrun_error = 1UL;
2585 else
2587 /* Check DMA configuration */
2588 #if defined(ADC_MULTIMODE_SUPPORT)
2589 if (tmp_multimode_config != LL_ADC_MULTI_INDEPENDENT)
2591 /* Multimode (when feature is available) is enabled,
2592 Common Control Register MDMA bits must be checked. */
2593 if (LL_ADC_GetMultiDMATransfer(__LL_ADC_COMMON_INSTANCE(hadc->Instance)) != LL_ADC_MULTI_REG_DMA_EACH_ADC)
2595 overrun_error = 1UL;
2598 else
2599 #endif
2601 /* Multimode not set or feature not available or ADC independent */
2602 if ((hadc->Instance->CFGR & ADC_CFGR_DMAEN) != 0UL)
2604 overrun_error = 1UL;
2609 if (overrun_error == 1UL)
2611 /* Change ADC state to error state */
2612 SET_BIT(hadc->State, HAL_ADC_STATE_REG_OVR);
2614 /* Set ADC error code to overrun */
2615 SET_BIT(hadc->ErrorCode, HAL_ADC_ERROR_OVR);
2617 /* Error callback */
2618 /* Note: In case of overrun, ADC conversion data is preserved until */
2619 /* flag OVR is reset. */
2620 /* Therefore, old ADC conversion data can be retrieved in */
2621 /* function "HAL_ADC_ErrorCallback()". */
2622 #if (USE_HAL_ADC_REGISTER_CALLBACKS == 1)
2623 hadc->ErrorCallback(hadc);
2624 #else
2625 HAL_ADC_ErrorCallback(hadc);
2626 #endif /* USE_HAL_ADC_REGISTER_CALLBACKS */
2629 /* Clear ADC overrun flag */
2630 __HAL_ADC_CLEAR_FLAG(hadc, ADC_FLAG_OVR);
2633 /* ========== Check Injected context queue overflow flag ========== */
2634 if (((tmp_isr & ADC_FLAG_JQOVF) == ADC_FLAG_JQOVF) && ((tmp_ier & ADC_IT_JQOVF) == ADC_IT_JQOVF))
2636 /* Change ADC state to overrun state */
2637 SET_BIT(hadc->State, HAL_ADC_STATE_INJ_JQOVF);
2639 /* Set ADC error code to Injected context queue overflow */
2640 SET_BIT(hadc->ErrorCode, HAL_ADC_ERROR_JQOVF);
2642 /* Clear the Injected context queue overflow flag */
2643 __HAL_ADC_CLEAR_FLAG(hadc, ADC_FLAG_JQOVF);
2645 /* Injected context queue overflow callback */
2646 #if (USE_HAL_ADC_REGISTER_CALLBACKS == 1)
2647 hadc->InjectedQueueOverflowCallback(hadc);
2648 #else
2649 HAL_ADCEx_InjectedQueueOverflowCallback(hadc);
2650 #endif /* USE_HAL_ADC_REGISTER_CALLBACKS */
2656 * @brief Conversion complete callback in non-blocking mode.
2657 * @param hadc ADC handle
2658 * @retval None
2660 __weak void HAL_ADC_ConvCpltCallback(ADC_HandleTypeDef *hadc)
2662 /* Prevent unused argument(s) compilation warning */
2663 UNUSED(hadc);
2665 /* NOTE : This function should not be modified. When the callback is needed,
2666 function HAL_ADC_ConvCpltCallback must be implemented in the user file.
2671 * @brief Conversion DMA half-transfer callback in non-blocking mode.
2672 * @param hadc ADC handle
2673 * @retval None
2675 __weak void HAL_ADC_ConvHalfCpltCallback(ADC_HandleTypeDef *hadc)
2677 /* Prevent unused argument(s) compilation warning */
2678 UNUSED(hadc);
2680 /* NOTE : This function should not be modified. When the callback is needed,
2681 function HAL_ADC_ConvHalfCpltCallback must be implemented in the user file.
2686 * @brief Analog watchdog 1 callback in non-blocking mode.
2687 * @param hadc ADC handle
2688 * @retval None
2690 __weak void HAL_ADC_LevelOutOfWindowCallback(ADC_HandleTypeDef *hadc)
2692 /* Prevent unused argument(s) compilation warning */
2693 UNUSED(hadc);
2695 /* NOTE : This function should not be modified. When the callback is needed,
2696 function HAL_ADC_LevelOutOfWindowCallback must be implemented in the user file.
2701 * @brief ADC error callback in non-blocking mode
2702 * (ADC conversion with interruption or transfer by DMA).
2703 * @note In case of error due to overrun when using ADC with DMA transfer
2704 * (HAL ADC handle parameter "ErrorCode" to state "HAL_ADC_ERROR_OVR"):
2705 * - Reinitialize the DMA using function "HAL_ADC_Stop_DMA()".
2706 * - If needed, restart a new ADC conversion using function
2707 * "HAL_ADC_Start_DMA()"
2708 * (this function is also clearing overrun flag)
2709 * @param hadc ADC handle
2710 * @retval None
2712 __weak void HAL_ADC_ErrorCallback(ADC_HandleTypeDef *hadc)
2714 /* Prevent unused argument(s) compilation warning */
2715 UNUSED(hadc);
2717 /* NOTE : This function should not be modified. When the callback is needed,
2718 function HAL_ADC_ErrorCallback must be implemented in the user file.
2723 * @}
2726 /** @defgroup ADC_Exported_Functions_Group3 Peripheral Control functions
2727 * @brief Peripheral Control functions
2729 @verbatim
2730 ===============================================================================
2731 ##### Peripheral Control functions #####
2732 ===============================================================================
2733 [..] This section provides functions allowing to:
2734 (+) Configure channels on regular group
2735 (+) Configure the analog watchdog
2737 @endverbatim
2738 * @{
2742 * @brief Configure a channel to be assigned to ADC group regular.
2743 * @note In case of usage of internal measurement channels:
2744 * Vbat/VrefInt/TempSensor.
2745 * These internal paths can be disabled using function
2746 * HAL_ADC_DeInit().
2747 * @note Possibility to update parameters on the fly:
2748 * This function initializes channel into ADC group regular,
2749 * following calls to this function can be used to reconfigure
2750 * some parameters of structure "ADC_ChannelConfTypeDef" on the fly,
2751 * without resetting the ADC.
2752 * The setting of these parameters is conditioned to ADC state:
2753 * Refer to comments of structure "ADC_ChannelConfTypeDef".
2754 * @param hadc ADC handle
2755 * @param sConfig Structure of ADC channel assigned to ADC group regular.
2756 * @retval HAL status
2758 HAL_StatusTypeDef HAL_ADC_ConfigChannel(ADC_HandleTypeDef *hadc, ADC_ChannelConfTypeDef *sConfig)
2760 HAL_StatusTypeDef tmp_hal_status = HAL_OK;
2761 uint32_t tmpOffsetShifted;
2762 uint32_t tmp_config_internal_channel;
2763 __IO uint32_t wait_loop_index = 0;
2764 uint32_t tmp_adc_is_conversion_on_going_regular;
2765 uint32_t tmp_adc_is_conversion_on_going_injected;
2767 /* Check the parameters */
2768 assert_param(IS_ADC_ALL_INSTANCE(hadc->Instance));
2769 assert_param(IS_ADC_REGULAR_RANK(sConfig->Rank));
2770 assert_param(IS_ADC_SAMPLE_TIME(sConfig->SamplingTime));
2771 assert_param(IS_ADC_SINGLE_DIFFERENTIAL(sConfig->SingleDiff));
2772 assert_param(IS_ADC_OFFSET_NUMBER(sConfig->OffsetNumber));
2773 assert_param(IS_ADC_RANGE(ADC_GET_RESOLUTION(hadc), sConfig->Offset));
2775 /* if ROVSE is set, the value of the OFFSETy_EN bit in ADCx_OFRy register is
2776 ignored (considered as reset) */
2777 assert_param(!((sConfig->OffsetNumber != ADC_OFFSET_NONE) && (hadc->Init.OversamplingMode == ENABLE)));
2779 /* Verification of channel number */
2780 if (sConfig->SingleDiff != ADC_DIFFERENTIAL_ENDED)
2782 assert_param(IS_ADC_CHANNEL(hadc, sConfig->Channel));
2784 else
2786 assert_param(IS_ADC_DIFF_CHANNEL(hadc, sConfig->Channel));
2789 /* Process locked */
2790 __HAL_LOCK(hadc);
2792 /* Parameters update conditioned to ADC state: */
2793 /* Parameters that can be updated when ADC is disabled or enabled without */
2794 /* conversion on going on regular group: */
2795 /* - Channel number */
2796 /* - Channel rank */
2797 if (LL_ADC_REG_IsConversionOngoing(hadc->Instance) == 0UL)
2799 /* Set ADC group regular sequence: channel on the selected scan sequence rank */
2800 LL_ADC_REG_SetSequencerRanks(hadc->Instance, sConfig->Rank, sConfig->Channel);
2802 /* Parameters update conditioned to ADC state: */
2803 /* Parameters that can be updated when ADC is disabled or enabled without */
2804 /* conversion on going on regular group: */
2805 /* - Channel sampling time */
2806 /* - Channel offset */
2807 tmp_adc_is_conversion_on_going_regular = LL_ADC_REG_IsConversionOngoing(hadc->Instance);
2808 tmp_adc_is_conversion_on_going_injected = LL_ADC_INJ_IsConversionOngoing(hadc->Instance);
2809 if ((tmp_adc_is_conversion_on_going_regular == 0UL)
2810 && (tmp_adc_is_conversion_on_going_injected == 0UL)
2813 /* Manage specific case of sampling time 3.5 cycles replacing 2.5 cyles */
2814 if (sConfig->SamplingTime == ADC_SAMPLETIME_3CYCLES_5)
2816 /* Set sampling time of the selected ADC channel */
2817 LL_ADC_SetChannelSamplingTime(hadc->Instance, sConfig->Channel, LL_ADC_SAMPLINGTIME_2CYCLES_5);
2819 /* Set ADC sampling time common configuration */
2820 LL_ADC_SetSamplingTimeCommonConfig(hadc->Instance, LL_ADC_SAMPLINGTIME_COMMON_3C5_REPL_2C5);
2822 else
2824 /* Set sampling time of the selected ADC channel */
2825 LL_ADC_SetChannelSamplingTime(hadc->Instance, sConfig->Channel, sConfig->SamplingTime);
2827 /* Set ADC sampling time common configuration */
2828 LL_ADC_SetSamplingTimeCommonConfig(hadc->Instance, LL_ADC_SAMPLINGTIME_COMMON_DEFAULT);
2831 /* Configure the offset: offset enable/disable, channel, offset value */
2833 /* Shift the offset with respect to the selected ADC resolution. */
2834 /* Offset has to be left-aligned on bit 11, the LSB (right bits) are set to 0 */
2835 tmpOffsetShifted = ADC_OFFSET_SHIFT_RESOLUTION(hadc, (uint32_t)sConfig->Offset);
2837 if (sConfig->OffsetNumber != ADC_OFFSET_NONE)
2839 /* Set ADC selected offset number */
2840 LL_ADC_SetOffset(hadc->Instance, sConfig->OffsetNumber, sConfig->Channel, tmpOffsetShifted);
2842 assert_param(IS_ADC_OFFSET_SIGN(sConfig->OffsetSign));
2843 assert_param(IS_FUNCTIONAL_STATE(sConfig->OffsetSaturation));
2844 /* Set ADC selected offset sign & saturation */
2845 LL_ADC_SetOffsetSign(hadc->Instance, sConfig->OffsetNumber, sConfig->OffsetSign);
2846 LL_ADC_SetOffsetSaturation(hadc->Instance, sConfig->OffsetNumber, (sConfig->OffsetSaturation == ENABLE) ? LL_ADC_OFFSET_SATURATION_ENABLE : LL_ADC_OFFSET_SATURATION_DISABLE);
2848 else
2850 /* Scan each offset register to check if the selected channel is targeted. */
2851 /* If this is the case, the corresponding offset number is disabled. */
2852 if(__LL_ADC_CHANNEL_TO_DECIMAL_NB(LL_ADC_GetOffsetChannel(hadc->Instance, LL_ADC_OFFSET_1)) == __LL_ADC_CHANNEL_TO_DECIMAL_NB(sConfig->Channel))
2854 LL_ADC_SetOffsetState(hadc->Instance, LL_ADC_OFFSET_1, LL_ADC_OFFSET_DISABLE);
2856 if(__LL_ADC_CHANNEL_TO_DECIMAL_NB(LL_ADC_GetOffsetChannel(hadc->Instance, LL_ADC_OFFSET_2)) == __LL_ADC_CHANNEL_TO_DECIMAL_NB(sConfig->Channel))
2858 LL_ADC_SetOffsetState(hadc->Instance, LL_ADC_OFFSET_2, LL_ADC_OFFSET_DISABLE);
2860 if(__LL_ADC_CHANNEL_TO_DECIMAL_NB(LL_ADC_GetOffsetChannel(hadc->Instance, LL_ADC_OFFSET_3)) == __LL_ADC_CHANNEL_TO_DECIMAL_NB(sConfig->Channel))
2862 LL_ADC_SetOffsetState(hadc->Instance, LL_ADC_OFFSET_3, LL_ADC_OFFSET_DISABLE);
2864 if(__LL_ADC_CHANNEL_TO_DECIMAL_NB(LL_ADC_GetOffsetChannel(hadc->Instance, LL_ADC_OFFSET_4)) == __LL_ADC_CHANNEL_TO_DECIMAL_NB(sConfig->Channel))
2866 LL_ADC_SetOffsetState(hadc->Instance, LL_ADC_OFFSET_4, LL_ADC_OFFSET_DISABLE);
2871 /* Parameters update conditioned to ADC state: */
2872 /* Parameters that can be updated only when ADC is disabled: */
2873 /* - Single or differential mode */
2874 if (LL_ADC_IsEnabled(hadc->Instance) == 0UL)
2876 /* Set mode single-ended or differential input of the selected ADC channel */
2877 LL_ADC_SetChannelSingleDiff(hadc->Instance, sConfig->Channel, sConfig->SingleDiff);
2879 /* Configuration of differential mode */
2880 if (sConfig->SingleDiff == ADC_DIFFERENTIAL_ENDED)
2882 /* Set sampling time of the selected ADC channel */
2883 /* Note: ADC channel number masked with value "0x1F" to ensure shift value within 32 bits range */
2884 LL_ADC_SetChannelSamplingTime(hadc->Instance,
2885 (uint32_t)(__LL_ADC_DECIMAL_NB_TO_CHANNEL((__LL_ADC_CHANNEL_TO_DECIMAL_NB((uint32_t)sConfig->Channel) + 1UL) & 0x1FUL)),
2886 sConfig->SamplingTime);
2891 /* Management of internal measurement channels: Vbat/VrefInt/TempSensor. */
2892 /* If internal channel selected, enable dedicated internal buffers and */
2893 /* paths. */
2894 /* Note: these internal measurement paths can be disabled using */
2895 /* HAL_ADC_DeInit(). */
2897 if (__LL_ADC_IS_CHANNEL_INTERNAL(sConfig->Channel))
2899 tmp_config_internal_channel = LL_ADC_GetCommonPathInternalCh(__LL_ADC_COMMON_INSTANCE(hadc->Instance));
2901 /* If the requested internal measurement path has already been enabled, */
2902 /* bypass the configuration processing. */
2903 if (((sConfig->Channel == ADC_CHANNEL_TEMPSENSOR_ADC1) || (sConfig->Channel == ADC_CHANNEL_TEMPSENSOR_ADC5))
2904 && ((tmp_config_internal_channel & LL_ADC_PATH_INTERNAL_TEMPSENSOR) == 0UL))
2906 if (ADC_TEMPERATURE_SENSOR_INSTANCE(hadc))
2908 LL_ADC_SetCommonPathInternalCh(__LL_ADC_COMMON_INSTANCE(hadc->Instance),
2909 LL_ADC_PATH_INTERNAL_TEMPSENSOR | tmp_config_internal_channel);
2911 /* Delay for temperature sensor stabilization time */
2912 /* Wait loop initialization and execution */
2913 /* Note: Variable divided by 2 to compensate partially */
2914 /* CPU processing cycles, scaling in us split to not */
2915 /* exceed 32 bits register capacity and handle low frequency. */
2916 wait_loop_index = ((LL_ADC_DELAY_TEMPSENSOR_STAB_US / 10UL) * (SystemCoreClock / (100000UL * 2UL)));
2917 while (wait_loop_index != 0UL)
2919 wait_loop_index--;
2923 else if ((sConfig->Channel == ADC_CHANNEL_VBAT) && ((tmp_config_internal_channel & LL_ADC_PATH_INTERNAL_VBAT) == 0UL))
2925 if (ADC_BATTERY_VOLTAGE_INSTANCE(hadc))
2927 LL_ADC_SetCommonPathInternalCh(__LL_ADC_COMMON_INSTANCE(hadc->Instance),
2928 LL_ADC_PATH_INTERNAL_VBAT | tmp_config_internal_channel);
2931 else if ((sConfig->Channel == ADC_CHANNEL_VREFINT)
2932 && ((tmp_config_internal_channel & LL_ADC_PATH_INTERNAL_VREFINT) == 0UL))
2934 if (ADC_VREFINT_INSTANCE(hadc))
2936 LL_ADC_SetCommonPathInternalCh(__LL_ADC_COMMON_INSTANCE(hadc->Instance),
2937 LL_ADC_PATH_INTERNAL_VREFINT | tmp_config_internal_channel);
2940 else
2942 /* nothing to do */
2947 /* If a conversion is on going on regular group, no update on regular */
2948 /* channel could be done on neither of the channel configuration structure */
2949 /* parameters. */
2950 else
2952 /* Update ADC state machine to error */
2953 SET_BIT(hadc->State, HAL_ADC_STATE_ERROR_CONFIG);
2955 tmp_hal_status = HAL_ERROR;
2958 /* Process unlocked */
2959 __HAL_UNLOCK(hadc);
2961 /* Return function status */
2962 return tmp_hal_status;
2966 * @brief Configure the analog watchdog.
2967 * @note Possibility to update parameters on the fly:
2968 * This function initializes the selected analog watchdog, successive
2969 * calls to this function can be used to reconfigure some parameters
2970 * of structure "ADC_AnalogWDGConfTypeDef" on the fly, without resetting
2971 * the ADC.
2972 * The setting of these parameters is conditioned to ADC state.
2973 * For parameters constraints, see comments of structure
2974 * "ADC_AnalogWDGConfTypeDef".
2975 * @note On this STM32 serie, analog watchdog thresholds can be modified
2976 * while ADC conversion is on going.
2977 * In this case, some constraints must be taken into account:
2978 * the programmed threshold values are effective from the next
2979 * ADC EOC (end of unitary conversion).
2980 * Considering that registers write delay may happen due to
2981 * bus activity, this might cause an uncertainty on the
2982 * effective timing of the new programmed threshold values.
2983 * @param hadc ADC handle
2984 * @param AnalogWDGConfig Structure of ADC analog watchdog configuration
2985 * @retval HAL status
2987 HAL_StatusTypeDef HAL_ADC_AnalogWDGConfig(ADC_HandleTypeDef *hadc, ADC_AnalogWDGConfTypeDef *AnalogWDGConfig)
2989 HAL_StatusTypeDef tmp_hal_status = HAL_OK;
2990 uint32_t tmpAWDHighThresholdShifted;
2991 uint32_t tmpAWDLowThresholdShifted;
2992 uint32_t tmp_adc_is_conversion_on_going_regular;
2993 uint32_t tmp_adc_is_conversion_on_going_injected;
2995 /* Check the parameters */
2996 assert_param(IS_ADC_ALL_INSTANCE(hadc->Instance));
2997 assert_param(IS_ADC_ANALOG_WATCHDOG_NUMBER(AnalogWDGConfig->WatchdogNumber));
2998 assert_param(IS_ADC_ANALOG_WATCHDOG_MODE(AnalogWDGConfig->WatchdogMode));
2999 assert_param(IS_ADC_ANALOG_WATCHDOG_FILTERING_MODE(AnalogWDGConfig->FilteringConfig));
3000 assert_param(IS_FUNCTIONAL_STATE(AnalogWDGConfig->ITMode));
3002 if ((AnalogWDGConfig->WatchdogMode == ADC_ANALOGWATCHDOG_SINGLE_REG) ||
3003 (AnalogWDGConfig->WatchdogMode == ADC_ANALOGWATCHDOG_SINGLE_INJEC) ||
3004 (AnalogWDGConfig->WatchdogMode == ADC_ANALOGWATCHDOG_SINGLE_REGINJEC))
3006 assert_param(IS_ADC_CHANNEL(hadc, AnalogWDGConfig->Channel));
3009 /* Verify thresholds range */
3010 if (hadc->Init.OversamplingMode == ENABLE)
3012 /* Case of oversampling enabled: depending on ratio and shift configuration,
3013 analog watchdog thresholds can be higher than ADC resolution.
3014 Verify if thresholds are within maximum thresholds range. */
3015 assert_param(IS_ADC_RANGE(ADC_RESOLUTION_12B, AnalogWDGConfig->HighThreshold));
3016 assert_param(IS_ADC_RANGE(ADC_RESOLUTION_12B, AnalogWDGConfig->LowThreshold));
3018 else
3020 /* Verify if thresholds are within the selected ADC resolution */
3021 assert_param(IS_ADC_RANGE(ADC_GET_RESOLUTION(hadc), AnalogWDGConfig->HighThreshold));
3022 assert_param(IS_ADC_RANGE(ADC_GET_RESOLUTION(hadc), AnalogWDGConfig->LowThreshold));
3025 /* Process locked */
3026 __HAL_LOCK(hadc);
3028 /* Parameters update conditioned to ADC state: */
3029 /* Parameters that can be updated when ADC is disabled or enabled without */
3030 /* conversion on going on ADC groups regular and injected: */
3031 /* - Analog watchdog channels */
3032 tmp_adc_is_conversion_on_going_regular = LL_ADC_REG_IsConversionOngoing(hadc->Instance);
3033 tmp_adc_is_conversion_on_going_injected = LL_ADC_INJ_IsConversionOngoing(hadc->Instance);
3034 if ((tmp_adc_is_conversion_on_going_regular == 0UL)
3035 && (tmp_adc_is_conversion_on_going_injected == 0UL)
3038 /* Analog watchdog configuration */
3039 if (AnalogWDGConfig->WatchdogNumber == ADC_ANALOGWATCHDOG_1)
3041 /* Configuration of analog watchdog: */
3042 /* - Set the analog watchdog enable mode: one or overall group of */
3043 /* channels, on groups regular and-or injected. */
3044 switch (AnalogWDGConfig->WatchdogMode)
3046 case ADC_ANALOGWATCHDOG_SINGLE_REG:
3047 LL_ADC_SetAnalogWDMonitChannels(hadc->Instance, LL_ADC_AWD1, __LL_ADC_ANALOGWD_CHANNEL_GROUP(AnalogWDGConfig->Channel,
3048 LL_ADC_GROUP_REGULAR));
3049 break;
3051 case ADC_ANALOGWATCHDOG_SINGLE_INJEC:
3052 LL_ADC_SetAnalogWDMonitChannels(hadc->Instance, LL_ADC_AWD1, __LL_ADC_ANALOGWD_CHANNEL_GROUP(AnalogWDGConfig->Channel,
3053 LL_ADC_GROUP_INJECTED));
3054 break;
3056 case ADC_ANALOGWATCHDOG_SINGLE_REGINJEC:
3057 LL_ADC_SetAnalogWDMonitChannels(hadc->Instance, LL_ADC_AWD1, __LL_ADC_ANALOGWD_CHANNEL_GROUP(AnalogWDGConfig->Channel,
3058 LL_ADC_GROUP_REGULAR_INJECTED));
3059 break;
3061 case ADC_ANALOGWATCHDOG_ALL_REG:
3062 LL_ADC_SetAnalogWDMonitChannels(hadc->Instance, LL_ADC_AWD1, LL_ADC_AWD_ALL_CHANNELS_REG);
3063 break;
3065 case ADC_ANALOGWATCHDOG_ALL_INJEC:
3066 LL_ADC_SetAnalogWDMonitChannels(hadc->Instance, LL_ADC_AWD1, LL_ADC_AWD_ALL_CHANNELS_INJ);
3067 break;
3069 case ADC_ANALOGWATCHDOG_ALL_REGINJEC:
3070 LL_ADC_SetAnalogWDMonitChannels(hadc->Instance, LL_ADC_AWD1, LL_ADC_AWD_ALL_CHANNELS_REG_INJ);
3071 break;
3073 default: /* ADC_ANALOGWATCHDOG_NONE */
3074 LL_ADC_SetAnalogWDMonitChannels(hadc->Instance, LL_ADC_AWD1, LL_ADC_AWD_DISABLE);
3075 break;
3078 /* Set the filtering configuration */
3079 MODIFY_REG(hadc->Instance->TR1,
3080 ADC_TR1_AWDFILT,
3081 AnalogWDGConfig->FilteringConfig);
3083 /* Update state, clear previous result related to AWD1 */
3084 CLEAR_BIT(hadc->State, HAL_ADC_STATE_AWD1);
3086 /* Clear flag ADC analog watchdog */
3087 /* Note: Flag cleared Clear the ADC Analog watchdog flag to be ready */
3088 /* to use for HAL_ADC_IRQHandler() or HAL_ADC_PollForEvent() */
3089 /* (in case left enabled by previous ADC operations). */
3090 LL_ADC_ClearFlag_AWD1(hadc->Instance);
3092 /* Configure ADC analog watchdog interrupt */
3093 if (AnalogWDGConfig->ITMode == ENABLE)
3095 LL_ADC_EnableIT_AWD1(hadc->Instance);
3097 else
3099 LL_ADC_DisableIT_AWD1(hadc->Instance);
3102 /* Case of ADC_ANALOGWATCHDOG_2 or ADC_ANALOGWATCHDOG_3 */
3103 else
3105 switch (AnalogWDGConfig->WatchdogMode)
3107 case ADC_ANALOGWATCHDOG_SINGLE_REG:
3108 case ADC_ANALOGWATCHDOG_SINGLE_INJEC:
3109 case ADC_ANALOGWATCHDOG_SINGLE_REGINJEC:
3110 /* Update AWD by bitfield to keep the possibility to monitor */
3111 /* several channels by successive calls of this function. */
3112 if (AnalogWDGConfig->WatchdogNumber == ADC_ANALOGWATCHDOG_2)
3114 SET_BIT(hadc->Instance->AWD2CR, (1UL << (__LL_ADC_CHANNEL_TO_DECIMAL_NB(AnalogWDGConfig->Channel) & 0x1FUL)));
3116 else
3118 SET_BIT(hadc->Instance->AWD3CR, (1UL << (__LL_ADC_CHANNEL_TO_DECIMAL_NB(AnalogWDGConfig->Channel) & 0x1FUL)));
3120 break;
3122 case ADC_ANALOGWATCHDOG_ALL_REG:
3123 case ADC_ANALOGWATCHDOG_ALL_INJEC:
3124 case ADC_ANALOGWATCHDOG_ALL_REGINJEC:
3125 LL_ADC_SetAnalogWDMonitChannels(hadc->Instance, AnalogWDGConfig->WatchdogNumber, LL_ADC_AWD_ALL_CHANNELS_REG_INJ);
3126 break;
3128 default: /* ADC_ANALOGWATCHDOG_NONE */
3129 LL_ADC_SetAnalogWDMonitChannels(hadc->Instance, AnalogWDGConfig->WatchdogNumber, LL_ADC_AWD_DISABLE);
3130 break;
3133 if (AnalogWDGConfig->WatchdogNumber == ADC_ANALOGWATCHDOG_2)
3135 /* Update state, clear previous result related to AWD2 */
3136 CLEAR_BIT(hadc->State, HAL_ADC_STATE_AWD2);
3138 /* Clear flag ADC analog watchdog */
3139 /* Note: Flag cleared Clear the ADC Analog watchdog flag to be ready */
3140 /* to use for HAL_ADC_IRQHandler() or HAL_ADC_PollForEvent() */
3141 /* (in case left enabled by previous ADC operations). */
3142 LL_ADC_ClearFlag_AWD2(hadc->Instance);
3144 /* Configure ADC analog watchdog interrupt */
3145 if (AnalogWDGConfig->ITMode == ENABLE)
3147 LL_ADC_EnableIT_AWD2(hadc->Instance);
3149 else
3151 LL_ADC_DisableIT_AWD2(hadc->Instance);
3154 /* (AnalogWDGConfig->WatchdogNumber == ADC_ANALOGWATCHDOG_3) */
3155 else
3157 /* Update state, clear previous result related to AWD3 */
3158 CLEAR_BIT(hadc->State, HAL_ADC_STATE_AWD3);
3160 /* Clear flag ADC analog watchdog */
3161 /* Note: Flag cleared Clear the ADC Analog watchdog flag to be ready */
3162 /* to use for HAL_ADC_IRQHandler() or HAL_ADC_PollForEvent() */
3163 /* (in case left enabled by previous ADC operations). */
3164 LL_ADC_ClearFlag_AWD3(hadc->Instance);
3166 /* Configure ADC analog watchdog interrupt */
3167 if (AnalogWDGConfig->ITMode == ENABLE)
3169 LL_ADC_EnableIT_AWD3(hadc->Instance);
3171 else
3173 LL_ADC_DisableIT_AWD3(hadc->Instance);
3180 /* Analog watchdog thresholds configuration */
3181 if (AnalogWDGConfig->WatchdogNumber == ADC_ANALOGWATCHDOG_1)
3183 /* Shift the offset with respect to the selected ADC resolution: */
3184 /* Thresholds have to be left-aligned on bit 11, the LSB (right bits) */
3185 /* are set to 0. */
3186 tmpAWDHighThresholdShifted = ADC_AWD1THRESHOLD_SHIFT_RESOLUTION(hadc, AnalogWDGConfig->HighThreshold);
3187 tmpAWDLowThresholdShifted = ADC_AWD1THRESHOLD_SHIFT_RESOLUTION(hadc, AnalogWDGConfig->LowThreshold);
3189 /* Case of ADC_ANALOGWATCHDOG_2 and ADC_ANALOGWATCHDOG_3 */
3190 else
3192 /* Shift the offset with respect to the selected ADC resolution: */
3193 /* Thresholds have to be left-aligned on bit 7, the LSB (right bits) */
3194 /* are set to 0. */
3195 tmpAWDHighThresholdShifted = ADC_AWD23THRESHOLD_SHIFT_RESOLUTION(hadc, AnalogWDGConfig->HighThreshold);
3196 tmpAWDLowThresholdShifted = ADC_AWD23THRESHOLD_SHIFT_RESOLUTION(hadc, AnalogWDGConfig->LowThreshold);
3199 /* Set ADC analog watchdog thresholds value of both thresholds high and low */
3200 LL_ADC_ConfigAnalogWDThresholds(hadc->Instance, AnalogWDGConfig->WatchdogNumber, tmpAWDHighThresholdShifted,
3201 tmpAWDLowThresholdShifted);
3203 /* Process unlocked */
3204 __HAL_UNLOCK(hadc);
3206 /* Return function status */
3207 return tmp_hal_status;
3212 * @}
3215 /** @defgroup ADC_Exported_Functions_Group4 Peripheral State functions
3216 * @brief ADC Peripheral State functions
3218 @verbatim
3219 ===============================================================================
3220 ##### Peripheral state and errors functions #####
3221 ===============================================================================
3222 [..]
3223 This subsection provides functions to get in run-time the status of the
3224 peripheral.
3225 (+) Check the ADC state
3226 (+) Check the ADC error code
3228 @endverbatim
3229 * @{
3233 * @brief Return the ADC handle state.
3234 * @note ADC state machine is managed by bitfields, ADC status must be
3235 * compared with states bits.
3236 * For example:
3237 * " if ((HAL_ADC_GetState(hadc1) & HAL_ADC_STATE_REG_BUSY) != 0UL) "
3238 * " if ((HAL_ADC_GetState(hadc1) & HAL_ADC_STATE_AWD1) != 0UL) "
3239 * @param hadc ADC handle
3240 * @retval ADC handle state (bitfield on 32 bits)
3242 uint32_t HAL_ADC_GetState(ADC_HandleTypeDef *hadc)
3244 /* Check the parameters */
3245 assert_param(IS_ADC_ALL_INSTANCE(hadc->Instance));
3247 /* Return ADC handle state */
3248 return hadc->State;
3252 * @brief Return the ADC error code.
3253 * @param hadc ADC handle
3254 * @retval ADC error code (bitfield on 32 bits)
3256 uint32_t HAL_ADC_GetError(ADC_HandleTypeDef *hadc)
3258 /* Check the parameters */
3259 assert_param(IS_ADC_ALL_INSTANCE(hadc->Instance));
3261 return hadc->ErrorCode;
3265 * @}
3269 * @}
3272 /** @defgroup ADC_Private_Functions ADC Private Functions
3273 * @{
3277 * @brief Stop ADC conversion.
3278 * @param hadc ADC handle
3279 * @param ConversionGroup ADC group regular and/or injected.
3280 * This parameter can be one of the following values:
3281 * @arg @ref ADC_REGULAR_GROUP ADC regular conversion type.
3282 * @arg @ref ADC_INJECTED_GROUP ADC injected conversion type.
3283 * @arg @ref ADC_REGULAR_INJECTED_GROUP ADC regular and injected conversion type.
3284 * @retval HAL status.
3286 HAL_StatusTypeDef ADC_ConversionStop(ADC_HandleTypeDef *hadc, uint32_t ConversionGroup)
3288 uint32_t tickstart;
3289 uint32_t Conversion_Timeout_CPU_cycles = 0UL;
3290 uint32_t conversion_group_reassigned = ConversionGroup;
3291 uint32_t tmp_ADC_CR_ADSTART_JADSTART;
3292 uint32_t tmp_adc_is_conversion_on_going_regular;
3293 uint32_t tmp_adc_is_conversion_on_going_injected;
3295 /* Check the parameters */
3296 assert_param(IS_ADC_ALL_INSTANCE(hadc->Instance));
3297 assert_param(IS_ADC_CONVERSION_GROUP(ConversionGroup));
3299 /* Verification if ADC is not already stopped (on regular and injected */
3300 /* groups) to bypass this function if not needed. */
3301 tmp_adc_is_conversion_on_going_regular = LL_ADC_REG_IsConversionOngoing(hadc->Instance);
3302 tmp_adc_is_conversion_on_going_injected = LL_ADC_INJ_IsConversionOngoing(hadc->Instance);
3303 if ((tmp_adc_is_conversion_on_going_regular != 0UL)
3304 || (tmp_adc_is_conversion_on_going_injected != 0UL)
3307 /* Particular case of continuous auto-injection mode combined with */
3308 /* auto-delay mode. */
3309 /* In auto-injection mode, regular group stop ADC_CR_ADSTP is used (not */
3310 /* injected group stop ADC_CR_JADSTP). */
3311 /* Procedure to be followed: Wait until JEOS=1, clear JEOS, set ADSTP=1 */
3312 /* (see reference manual). */
3313 if (((hadc->Instance->CFGR & ADC_CFGR_JAUTO) != 0UL)
3314 && (hadc->Init.ContinuousConvMode == ENABLE)
3315 && (hadc->Init.LowPowerAutoWait == ENABLE)
3318 /* Use stop of regular group */
3319 conversion_group_reassigned = ADC_REGULAR_GROUP;
3321 /* Wait until JEOS=1 (maximum Timeout: 4 injected conversions) */
3322 while (__HAL_ADC_GET_FLAG(hadc, ADC_FLAG_JEOS) == 0UL)
3324 if (Conversion_Timeout_CPU_cycles >= (ADC_CONVERSION_TIME_MAX_CPU_CYCLES * 4UL))
3326 /* Update ADC state machine to error */
3327 SET_BIT(hadc->State, HAL_ADC_STATE_ERROR_INTERNAL);
3329 /* Set ADC error code to ADC peripheral internal error */
3330 SET_BIT(hadc->ErrorCode, HAL_ADC_ERROR_INTERNAL);
3332 return HAL_ERROR;
3334 Conversion_Timeout_CPU_cycles ++;
3337 /* Clear JEOS */
3338 __HAL_ADC_CLEAR_FLAG(hadc, ADC_FLAG_JEOS);
3341 /* Stop potential conversion on going on ADC group regular */
3342 if (conversion_group_reassigned != ADC_INJECTED_GROUP)
3344 /* Software is allowed to set ADSTP only when ADSTART=1 and ADDIS=0 */
3345 if (LL_ADC_REG_IsConversionOngoing(hadc->Instance) != 0UL)
3347 if (LL_ADC_IsDisableOngoing(hadc->Instance) == 0UL)
3349 /* Stop ADC group regular conversion */
3350 LL_ADC_REG_StopConversion(hadc->Instance);
3355 /* Stop potential conversion on going on ADC group injected */
3356 if (conversion_group_reassigned != ADC_REGULAR_GROUP)
3358 /* Software is allowed to set JADSTP only when JADSTART=1 and ADDIS=0 */
3359 if (LL_ADC_INJ_IsConversionOngoing(hadc->Instance) != 0UL)
3361 if (LL_ADC_IsDisableOngoing(hadc->Instance) == 0UL)
3363 /* Stop ADC group injected conversion */
3364 LL_ADC_INJ_StopConversion(hadc->Instance);
3369 /* Selection of start and stop bits with respect to the regular or injected group */
3370 switch (conversion_group_reassigned)
3372 case ADC_REGULAR_INJECTED_GROUP:
3373 tmp_ADC_CR_ADSTART_JADSTART = (ADC_CR_ADSTART | ADC_CR_JADSTART);
3374 break;
3375 case ADC_INJECTED_GROUP:
3376 tmp_ADC_CR_ADSTART_JADSTART = ADC_CR_JADSTART;
3377 break;
3378 /* Case ADC_REGULAR_GROUP only*/
3379 default:
3380 tmp_ADC_CR_ADSTART_JADSTART = ADC_CR_ADSTART;
3381 break;
3384 /* Wait for conversion effectively stopped */
3385 tickstart = HAL_GetTick();
3387 while ((hadc->Instance->CR & tmp_ADC_CR_ADSTART_JADSTART) != 0UL)
3389 if ((HAL_GetTick() - tickstart) > ADC_STOP_CONVERSION_TIMEOUT)
3391 /* Update ADC state machine to error */
3392 SET_BIT(hadc->State, HAL_ADC_STATE_ERROR_INTERNAL);
3394 /* Set ADC error code to ADC peripheral internal error */
3395 SET_BIT(hadc->ErrorCode, HAL_ADC_ERROR_INTERNAL);
3397 return HAL_ERROR;
3403 /* Return HAL status */
3404 return HAL_OK;
3410 * @brief Enable the selected ADC.
3411 * @note Prerequisite condition to use this function: ADC must be disabled
3412 * and voltage regulator must be enabled (done into HAL_ADC_Init()).
3413 * @param hadc ADC handle
3414 * @retval HAL status.
3416 HAL_StatusTypeDef ADC_Enable(ADC_HandleTypeDef *hadc)
3418 uint32_t tickstart;
3420 /* ADC enable and wait for ADC ready (in case of ADC is disabled or */
3421 /* enabling phase not yet completed: flag ADC ready not yet set). */
3422 /* Timeout implemented to not be stuck if ADC cannot be enabled (possible */
3423 /* causes: ADC clock not running, ...). */
3424 if (LL_ADC_IsEnabled(hadc->Instance) == 0UL)
3426 /* Check if conditions to enable the ADC are fulfilled */
3427 if ((hadc->Instance->CR & (ADC_CR_ADCAL | ADC_CR_JADSTP | ADC_CR_ADSTP | ADC_CR_JADSTART | ADC_CR_ADSTART | ADC_CR_ADDIS | ADC_CR_ADEN)) != 0UL)
3429 /* Update ADC state machine to error */
3430 SET_BIT(hadc->State, HAL_ADC_STATE_ERROR_INTERNAL);
3432 /* Set ADC error code to ADC peripheral internal error */
3433 SET_BIT(hadc->ErrorCode, HAL_ADC_ERROR_INTERNAL);
3435 return HAL_ERROR;
3438 /* Enable the ADC peripheral */
3439 LL_ADC_Enable(hadc->Instance);
3441 /* Wait for ADC effectively enabled */
3442 tickstart = HAL_GetTick();
3444 while (__HAL_ADC_GET_FLAG(hadc, ADC_FLAG_RDY) == 0UL)
3446 /* If ADEN bit is set less than 4 ADC clock cycles after the ADCAL bit
3447 has been cleared (after a calibration), ADEN bit is reset by the
3448 calibration logic.
3449 The workaround is to continue setting ADEN until ADRDY is becomes 1.
3450 Additionally, ADC_ENABLE_TIMEOUT is defined to encompass this
3451 4 ADC clock cycle duration */
3452 /* Note: Test of ADC enabled required due to hardware constraint to */
3453 /* not enable ADC if already enabled. */
3454 if (LL_ADC_IsEnabled(hadc->Instance) == 0UL)
3456 LL_ADC_Enable(hadc->Instance);
3459 if ((HAL_GetTick() - tickstart) > ADC_ENABLE_TIMEOUT)
3461 /* Update ADC state machine to error */
3462 SET_BIT(hadc->State, HAL_ADC_STATE_ERROR_INTERNAL);
3464 /* Set ADC error code to ADC peripheral internal error */
3465 SET_BIT(hadc->ErrorCode, HAL_ADC_ERROR_INTERNAL);
3467 return HAL_ERROR;
3472 /* Return HAL status */
3473 return HAL_OK;
3477 * @brief Disable the selected ADC.
3478 * @note Prerequisite condition to use this function: ADC conversions must be
3479 * stopped.
3480 * @param hadc ADC handle
3481 * @retval HAL status.
3483 HAL_StatusTypeDef ADC_Disable(ADC_HandleTypeDef *hadc)
3485 uint32_t tickstart;
3486 const uint32_t tmp_adc_is_disable_on_going = LL_ADC_IsDisableOngoing(hadc->Instance);
3488 /* Verification if ADC is not already disabled: */
3489 /* Note: forbidden to disable ADC (set bit ADC_CR_ADDIS) if ADC is already */
3490 /* disabled. */
3491 if ((LL_ADC_IsEnabled(hadc->Instance) != 0UL)
3492 && (tmp_adc_is_disable_on_going == 0UL)
3495 /* Check if conditions to disable the ADC are fulfilled */
3496 if ((hadc->Instance->CR & (ADC_CR_JADSTART | ADC_CR_ADSTART | ADC_CR_ADEN)) == ADC_CR_ADEN)
3498 /* Disable the ADC peripheral */
3499 LL_ADC_Disable(hadc->Instance);
3500 __HAL_ADC_CLEAR_FLAG(hadc, (ADC_FLAG_EOSMP | ADC_FLAG_RDY));
3502 else
3504 /* Update ADC state machine to error */
3505 SET_BIT(hadc->State, HAL_ADC_STATE_ERROR_INTERNAL);
3507 /* Set ADC error code to ADC peripheral internal error */
3508 SET_BIT(hadc->ErrorCode, HAL_ADC_ERROR_INTERNAL);
3510 return HAL_ERROR;
3513 /* Wait for ADC effectively disabled */
3514 /* Get tick count */
3515 tickstart = HAL_GetTick();
3517 while ((hadc->Instance->CR & ADC_CR_ADEN) != 0UL)
3519 if ((HAL_GetTick() - tickstart) > ADC_DISABLE_TIMEOUT)
3521 /* Update ADC state machine to error */
3522 SET_BIT(hadc->State, HAL_ADC_STATE_ERROR_INTERNAL);
3524 /* Set ADC error code to ADC peripheral internal error */
3525 SET_BIT(hadc->ErrorCode, HAL_ADC_ERROR_INTERNAL);
3527 return HAL_ERROR;
3532 /* Return HAL status */
3533 return HAL_OK;
3537 * @brief DMA transfer complete callback.
3538 * @param hdma pointer to DMA handle.
3539 * @retval None
3541 void ADC_DMAConvCplt(DMA_HandleTypeDef *hdma)
3543 /* Retrieve ADC handle corresponding to current DMA handle */
3544 ADC_HandleTypeDef *hadc = (ADC_HandleTypeDef *)((DMA_HandleTypeDef *)hdma)->Parent;
3546 /* Update state machine on conversion status if not in error state */
3547 if ((hadc->State & (HAL_ADC_STATE_ERROR_INTERNAL | HAL_ADC_STATE_ERROR_DMA)) == 0UL)
3549 /* Set ADC state */
3550 SET_BIT(hadc->State, HAL_ADC_STATE_REG_EOC);
3552 /* Determine whether any further conversion upcoming on group regular */
3553 /* by external trigger, continuous mode or scan sequence on going */
3554 /* to disable interruption. */
3555 /* Is it the end of the regular sequence ? */
3556 if ((hadc->Instance->ISR & ADC_FLAG_EOS) != 0UL)
3558 /* Are conversions software-triggered ? */
3559 if (LL_ADC_REG_IsTriggerSourceSWStart(hadc->Instance) != 0UL)
3561 /* Is CONT bit set ? */
3562 if (READ_BIT(hadc->Instance->CFGR, ADC_CFGR_CONT) == 0UL)
3564 /* CONT bit is not set, no more conversions expected */
3565 CLEAR_BIT(hadc->State, HAL_ADC_STATE_REG_BUSY);
3566 if ((hadc->State & HAL_ADC_STATE_INJ_BUSY) == 0UL)
3568 SET_BIT(hadc->State, HAL_ADC_STATE_READY);
3573 else
3575 /* DMA End of Transfer interrupt was triggered but conversions sequence
3576 is not over. If DMACFG is set to 0, conversions are stopped. */
3577 if (READ_BIT(hadc->Instance->CFGR, ADC_CFGR_DMACFG) == 0UL)
3579 /* DMACFG bit is not set, conversions are stopped. */
3580 CLEAR_BIT(hadc->State, HAL_ADC_STATE_REG_BUSY);
3581 if ((hadc->State & HAL_ADC_STATE_INJ_BUSY) == 0UL)
3583 SET_BIT(hadc->State, HAL_ADC_STATE_READY);
3588 /* Conversion complete callback */
3589 #if (USE_HAL_ADC_REGISTER_CALLBACKS == 1)
3590 hadc->ConvCpltCallback(hadc);
3591 #else
3592 HAL_ADC_ConvCpltCallback(hadc);
3593 #endif /* USE_HAL_ADC_REGISTER_CALLBACKS */
3595 else /* DMA and-or internal error occurred */
3597 if ((hadc->State & HAL_ADC_STATE_ERROR_INTERNAL) != 0UL)
3599 /* Call HAL ADC Error Callback function */
3600 #if (USE_HAL_ADC_REGISTER_CALLBACKS == 1)
3601 hadc->ErrorCallback(hadc);
3602 #else
3603 HAL_ADC_ErrorCallback(hadc);
3604 #endif /* USE_HAL_ADC_REGISTER_CALLBACKS */
3606 else
3608 /* Call ADC DMA error callback */
3609 hadc->DMA_Handle->XferErrorCallback(hdma);
3615 * @brief DMA half transfer complete callback.
3616 * @param hdma pointer to DMA handle.
3617 * @retval None
3619 void ADC_DMAHalfConvCplt(DMA_HandleTypeDef *hdma)
3621 /* Retrieve ADC handle corresponding to current DMA handle */
3622 ADC_HandleTypeDef *hadc = (ADC_HandleTypeDef *)((DMA_HandleTypeDef *)hdma)->Parent;
3624 /* Half conversion callback */
3625 #if (USE_HAL_ADC_REGISTER_CALLBACKS == 1)
3626 hadc->ConvHalfCpltCallback(hadc);
3627 #else
3628 HAL_ADC_ConvHalfCpltCallback(hadc);
3629 #endif /* USE_HAL_ADC_REGISTER_CALLBACKS */
3633 * @brief DMA error callback.
3634 * @param hdma pointer to DMA handle.
3635 * @retval None
3637 void ADC_DMAError(DMA_HandleTypeDef *hdma)
3639 /* Retrieve ADC handle corresponding to current DMA handle */
3640 ADC_HandleTypeDef *hadc = (ADC_HandleTypeDef *)((DMA_HandleTypeDef *)hdma)->Parent;
3642 /* Set ADC state */
3643 SET_BIT(hadc->State, HAL_ADC_STATE_ERROR_DMA);
3645 /* Set ADC error code to DMA error */
3646 SET_BIT(hadc->ErrorCode, HAL_ADC_ERROR_DMA);
3648 /* Error callback */
3649 #if (USE_HAL_ADC_REGISTER_CALLBACKS == 1)
3650 hadc->ErrorCallback(hadc);
3651 #else
3652 HAL_ADC_ErrorCallback(hadc);
3653 #endif /* USE_HAL_ADC_REGISTER_CALLBACKS */
3657 * @}
3660 #endif /* HAL_ADC_MODULE_ENABLED */
3662 * @}
3666 * @}
3669 /************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/