2 ******************************************************************************
3 * @file stm32h7xx_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)
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.
14 * ++ Channels configuration on regular group
15 * ++ Analog Watchdog configuration
17 * ++ ADC state machine management
18 * ++ Interrupts and flags management
19 * Other functions (extended functions) are available in file
20 * "stm32h7xx_hal_adc_ex.c".
23 ==============================================================================
24 ##### ADC peripheral features #####
25 ==============================================================================
27 (+) 16-bit, 14-bit, 12-bit, 10-bit or 8-bit configurable resolution.
28 Note: On devices STM32H72xx and STM32H73xx, these resolution are applicable to instances ADC1 and ADC2.
29 ADC3 is featuring resolutions 12-bit, 10-bit, 8-bit, 6-bit.
31 (+) Interrupt generation at the end of regular conversion and in case of
32 analog watchdog or overrun events.
34 (+) Single and continuous conversion modes.
36 (+) Scan mode for conversion of several channels sequentially.
38 (+) Data alignment with in-built data coherency.
40 (+) Programmable sampling time (channel wise)
42 (+) External trigger (timer or EXTI) with configurable polarity
44 (+) DMA request generation for transfer of conversions data of regular group.
46 (+) Configurable delay between conversions in Dual interleaved mode.
48 (+) ADC channels selectable single/differential input.
50 (+) ADC offset shared on 4 offset instances.
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 ==============================================================================
65 *** Configuration of top level parameters related to ADC ***
66 ============================================================
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, the PLL2 or the PLL3 running up to 400MHz.
80 Into HAL_ADC_MspInit() (recommended code location) or with
81 other device clock parameters configuration:
82 (+++) __HAL_RCC_ADC_CLK_ENABLE(); (mandatory)
84 RCC_ADCCLKSOURCE_PLL2 enable: (optional: if asynchronous clock selected)
85 (+++) RCC_PeriphClkInitTypeDef RCC_PeriphClkInit;
86 (+++) PeriphClkInit.PeriphClockSelection = RCC_PERIPHCLK_ADC;
87 (+++) PeriphClkInit.AdcClockSelection = RCC_ADCCLKSOURCE_PLL2;
88 (+++) HAL_RCCEx_PeriphCLKConfig(&PeriphClkInit);
90 (++) ADC clock source and clock prescaler are configured at ADC level with
91 parameter "ClockPrescaler" using function HAL_ADC_Init().
93 (#) ADC pins configuration
94 (++) Enable the clock for the ADC GPIOs
95 using macro __HAL_RCC_GPIOx_CLK_ENABLE()
96 (++) Configure these ADC pins in analog mode
97 using function HAL_GPIO_Init()
99 (#) Optionally, in case of usage of ADC with interruptions:
100 (++) Configure the NVIC for ADC
101 using function HAL_NVIC_EnableIRQ(ADCx_IRQn)
102 (++) Insert the ADC interruption handler function HAL_ADC_IRQHandler()
103 into the function of corresponding ADC interruption vector
106 (#) Optionally, in case of usage of DMA:
107 (++) Configure the DMA (DMA channel, mode normal or circular, ...)
108 using function HAL_DMA_Init().
109 (++) Configure the NVIC for DMA
110 using function HAL_NVIC_EnableIRQ(DMAx_Channelx_IRQn)
111 (++) Insert the ADC interruption handler function HAL_ADC_IRQHandler()
112 into the function of corresponding DMA interruption vector
113 DMAx_Channelx_IRQHandler().
115 *** Configuration of ADC, group regular, channels parameters ***
116 ================================================================
119 (#) Configure the ADC parameters (resolution, data alignment, ...)
120 and regular group parameters (conversion trigger, sequencer, ...)
121 using function HAL_ADC_Init().
123 (#) Configure the channels for regular group parameters (channel number,
124 channel rank into sequencer, ..., into regular group)
125 using function HAL_ADC_ConfigChannel().
127 (#) Optionally, configure the analog watchdog parameters (channels
128 monitored, thresholds, ...)
129 using function HAL_ADC_AnalogWDGConfig().
131 *** Execution of ADC conversions ***
132 ====================================
135 (#) Optionally, perform an automatic ADC calibration to improve the
137 using function HAL_ADCEx_Calibration_Start().
139 (#) ADC driver can be used among three modes: polling, interruption,
142 (++) ADC conversion by polling:
143 (+++) Activate the ADC peripheral and start conversions
144 using function HAL_ADC_Start()
145 (+++) Wait for ADC conversion completion
146 using function HAL_ADC_PollForConversion()
147 (+++) Retrieve conversion results
148 using function HAL_ADC_GetValue()
149 (+++) Stop conversion and disable the ADC peripheral
150 using function HAL_ADC_Stop()
152 (++) ADC conversion by interruption:
153 (+++) Activate the ADC peripheral and start conversions
154 using function HAL_ADC_Start_IT()
155 (+++) Wait for ADC conversion completion by call of function
156 HAL_ADC_ConvCpltCallback()
157 (this function must be implemented in user program)
158 (+++) Retrieve conversion results
159 using function HAL_ADC_GetValue()
160 (+++) Stop conversion and disable the ADC peripheral
161 using function HAL_ADC_Stop_IT()
163 (++) ADC conversion with transfer by DMA:
164 (+++) Activate the ADC peripheral and start conversions
165 using function HAL_ADC_Start_DMA()
166 (+++) Wait for ADC conversion completion by call of function
167 HAL_ADC_ConvCpltCallback() or HAL_ADC_ConvHalfCpltCallback()
168 (these functions must be implemented in user program)
169 (+++) Conversion results are automatically transferred by DMA into
170 destination variable address.
171 (+++) Stop conversion and disable the ADC peripheral
172 using function HAL_ADC_Stop_DMA()
176 (@) Callback functions must be implemented in user program:
177 (+@) HAL_ADC_ErrorCallback()
178 (+@) HAL_ADC_LevelOutOfWindowCallback() (callback of analog watchdog)
179 (+@) HAL_ADC_ConvCpltCallback()
180 (+@) HAL_ADC_ConvHalfCpltCallback
182 *** Deinitialization of ADC ***
183 ============================================================
186 (#) Disable the ADC interface
187 (++) ADC clock can be hard reset and disabled at RCC top level.
188 (++) Hard reset of ADC peripherals
189 using macro __HAL_RCC_ADCx_FORCE_RESET(), __HAL_RCC_ADCx_RELEASE_RESET().
190 (++) ADC clock disable
191 using the equivalent macro/functions as configuration step.
193 Into HAL_ADC_MspDeInit() (recommended code location) or with
194 other device clock parameters configuration:
195 (+++) __HAL_RCC_ADC_CLK_DISABLE(); (if not used anymore)
196 RCC_ADCCLKSOURCE_CLKP restore: (optional)
197 (+++) RCC_PeriphClkInitTypeDef RCC_PeriphClkInit;
198 (+++) PeriphClkInit.PeriphClockSelection = RCC_PERIPHCLK_ADC;
199 (+++) PeriphClkInit.AdcClockSelection = RCC_ADCCLKSOURCE_CLKP;
200 (+++) HAL_RCCEx_PeriphCLKConfig(&PeriphClkInit);
202 (#) ADC pins configuration
203 (++) Disable the clock for the ADC GPIOs
204 using macro __HAL_RCC_GPIOx_CLK_DISABLE()
206 (#) Optionally, in case of usage of ADC with interruptions:
207 (++) Disable the NVIC for ADC
208 using function HAL_NVIC_EnableIRQ(ADCx_IRQn)
210 (#) Optionally, in case of usage of DMA:
211 (++) Deinitialize the DMA
212 using function HAL_DMA_Init().
213 (++) Disable the NVIC for DMA
214 using function HAL_NVIC_EnableIRQ(DMAx_Channelx_IRQn)
218 *** Callback registration ***
219 =============================================
222 The compilation flag USE_HAL_ADC_REGISTER_CALLBACKS, when set to 1,
223 allows the user to configure dynamically the driver callbacks.
224 Use Functions @ref HAL_ADC_RegisterCallback()
225 to register an interrupt callback.
228 Function @ref HAL_ADC_RegisterCallback() allows to register following callbacks:
229 (+) ConvCpltCallback : ADC conversion complete callback
230 (+) ConvHalfCpltCallback : ADC conversion DMA half-transfer callback
231 (+) LevelOutOfWindowCallback : ADC analog watchdog 1 callback
232 (+) ErrorCallback : ADC error callback
233 (+) InjectedConvCpltCallback : ADC group injected conversion complete callback
234 (+) InjectedQueueOverflowCallback : ADC group injected context queue overflow callback
235 (+) LevelOutOfWindow2Callback : ADC analog watchdog 2 callback
236 (+) LevelOutOfWindow3Callback : ADC analog watchdog 3 callback
237 (+) EndOfSamplingCallback : ADC end of sampling callback
238 (+) MspInitCallback : ADC Msp Init callback
239 (+) MspDeInitCallback : ADC Msp DeInit callback
240 This function takes as parameters the HAL peripheral handle, the Callback ID
241 and a pointer to the user callback function.
244 Use function @ref HAL_ADC_UnRegisterCallback to reset a callback to the default
248 @ref HAL_ADC_UnRegisterCallback takes as parameters the HAL peripheral handle,
250 This function allows to reset following callbacks:
251 (+) ConvCpltCallback : ADC conversion complete callback
252 (+) ConvHalfCpltCallback : ADC conversion DMA half-transfer callback
253 (+) LevelOutOfWindowCallback : ADC analog watchdog 1 callback
254 (+) ErrorCallback : ADC error callback
255 (+) InjectedConvCpltCallback : ADC group injected conversion complete callback
256 (+) InjectedQueueOverflowCallback : ADC group injected context queue overflow callback
257 (+) LevelOutOfWindow2Callback : ADC analog watchdog 2 callback
258 (+) LevelOutOfWindow3Callback : ADC analog watchdog 3 callback
259 (+) EndOfSamplingCallback : ADC end of sampling callback
260 (+) MspInitCallback : ADC Msp Init callback
261 (+) MspDeInitCallback : ADC Msp DeInit callback
264 By default, after the @ref HAL_ADC_Init() and when the state is @ref HAL_ADC_STATE_RESET
265 all callbacks are set to the corresponding weak functions:
266 examples @ref HAL_ADC_ConvCpltCallback(), @ref HAL_ADC_ErrorCallback().
267 Exception done for MspInit and MspDeInit functions that are
268 reset to the legacy weak functions in the @ref HAL_ADC_Init()/ @ref HAL_ADC_DeInit() only when
269 these callbacks are null (not registered beforehand).
272 If MspInit or MspDeInit are not null, the @ref HAL_ADC_Init()/ @ref HAL_ADC_DeInit()
273 keep and use the user MspInit/MspDeInit callbacks (registered beforehand) whatever the state.
276 Callbacks can be registered/unregistered in @ref HAL_ADC_STATE_READY state only.
277 Exception done MspInit/MspDeInit functions that can be registered/unregistered
278 in @ref HAL_ADC_STATE_READY or @ref HAL_ADC_STATE_RESET state,
279 thus registered (user) MspInit/DeInit callbacks can be used during the Init/DeInit.
282 Then, the user first registers the MspInit/MspDeInit user callbacks
283 using @ref HAL_ADC_RegisterCallback() before calling @ref HAL_ADC_DeInit()
284 or @ref HAL_ADC_Init() function.
287 When the compilation flag USE_HAL_ADC_REGISTER_CALLBACKS is set to 0 or
288 not defined, the callback registration feature is not available and all callbacks
289 are set to the corresponding weak functions.
292 ******************************************************************************
295 * <h2><center>© Copyright (c) 2017 STMicroelectronics.
296 * All rights reserved.</center></h2>
298 * This software component is licensed by ST under BSD 3-Clause license,
299 * the "License"; You may not use this file except in compliance with the
300 * License. You may obtain a copy of the License at:
301 * opensource.org/licenses/BSD-3-Clause
303 ******************************************************************************
306 /* Includes ------------------------------------------------------------------*/
307 #include "stm32h7xx_hal.h"
309 /** @addtogroup STM32H7xx_HAL_Driver
313 /** @defgroup ADC ADC
314 * @brief ADC HAL module driver
318 #ifdef HAL_ADC_MODULE_ENABLED
320 /* Private typedef -----------------------------------------------------------*/
321 /* Private define ------------------------------------------------------------*/
323 /** @defgroup ADC_Private_Constants ADC Private Constants
326 #define ADC_CFGR_FIELDS_1 ((uint32_t)(ADC_CFGR_RES |\
327 ADC_CFGR_CONT | ADC_CFGR_OVRMOD |\
328 ADC_CFGR_DISCEN | ADC_CFGR_DISCNUM |\
329 ADC_CFGR_EXTEN | ADC_CFGR_EXTSEL)) /*!< ADC_CFGR fields of parameters that can be updated
330 when no regular conversion is on-going */
332 #if defined(ADC_VER_V5_V90)
333 #define ADC3_CFGR_FIELDS_1 ((ADC3_CFGR_RES | ADC3_CFGR_ALIGN |\
334 ADC_CFGR_CONT | ADC_CFGR_OVRMOD |\
335 ADC_CFGR_DISCEN | ADC_CFGR_DISCNUM |\
336 ADC_CFGR_EXTEN | ADC_CFGR_EXTSEL)) /*!< ADC_CFGR fields of parameters that can be updated
337 when no regular conversion is on-going */
340 #define ADC_CFGR2_FIELDS ((uint32_t)(ADC_CFGR2_ROVSE | ADC_CFGR2_OVSR |\
341 ADC_CFGR2_OVSS | ADC_CFGR2_TROVS |\
342 ADC_CFGR2_ROVSM)) /*!< ADC_CFGR2 fields of parameters that can be updated when no conversion
343 (neither regular nor injected) is on-going */
345 /* Timeout values for ADC operations (enable settling time, */
346 /* disable settling time, ...). */
347 /* Values defined to be higher than worst cases: low clock frequency, */
348 /* maximum prescalers. */
349 #define ADC_ENABLE_TIMEOUT (2UL) /*!< ADC enable time-out value */
350 #define ADC_DISABLE_TIMEOUT (2UL) /*!< ADC disable time-out value */
352 /* Timeout to wait for current conversion on going to be completed. */
353 /* Timeout fixed to worst case, for 1 channel. */
354 /* - maximum sampling time (830.5 adc_clk) */
355 /* - ADC resolution (Tsar 16 bits= 16.5 adc_clk) */
356 /* - ADC clock with prescaler 256 */
357 /* 823 * 256 = 210688 clock cycles max */
358 /* Unit: cycles of CPU clock. */
359 #define ADC_CONVERSION_TIME_MAX_CPU_CYCLES (210688UL) /*!< ADC conversion completion time-out value */
365 /* Private macro -------------------------------------------------------------*/
366 /* Private variables ---------------------------------------------------------*/
367 /* Private function prototypes -----------------------------------------------*/
368 /* Exported functions --------------------------------------------------------*/
370 /** @defgroup ADC_Exported_Functions ADC Exported Functions
374 /** @defgroup ADC_Exported_Functions_Group1 Initialization and de-initialization functions
375 * @brief ADC Initialization and Configuration functions
378 ===============================================================================
379 ##### Initialization and de-initialization functions #####
380 ===============================================================================
381 [..] This section provides functions allowing to:
382 (+) Initialize and configure the ADC.
383 (+) De-initialize the ADC.
389 * @brief Initialize the ADC peripheral and regular group according to
390 * parameters specified in structure "ADC_InitTypeDef".
391 * @note As prerequisite, ADC clock must be configured at RCC top level
392 * (refer to description of RCC configuration for ADC
393 * in header of this file).
394 * @note Possibility to update parameters on the fly:
395 * This function initializes the ADC MSP (HAL_ADC_MspInit()) only when
396 * coming from ADC state reset. Following calls to this function can
397 * be used to reconfigure some parameters of ADC_InitTypeDef
398 * structure on the fly, without modifying MSP configuration. If ADC
399 * MSP has to be modified again, HAL_ADC_DeInit() must be called
400 * before HAL_ADC_Init().
401 * The setting of these parameters is conditioned to ADC state.
402 * For parameters constraints, see comments of structure
404 * @note This function configures the ADC within 2 scopes: scope of entire
405 * ADC and scope of regular group. For parameters details, see comments
406 * of structure "ADC_InitTypeDef".
407 * @note Parameters related to common ADC registers (ADC clock mode) are set
408 * only if all ADCs are disabled.
409 * If this is not the case, these common parameters setting are
410 * bypassed without error reporting: it can be the intended behaviour in
411 * case of update of a parameter of ADC_InitTypeDef on the fly,
412 * without disabling the other ADCs.
413 * @param hadc ADC handle
416 HAL_StatusTypeDef
HAL_ADC_Init(ADC_HandleTypeDef
*hadc
)
418 HAL_StatusTypeDef tmp_hal_status
= HAL_OK
;
420 uint32_t tmp_adc_reg_is_conversion_on_going
;
421 __IO
uint32_t wait_loop_index
= 0UL;
422 uint32_t tmp_adc_is_conversion_on_going_regular
;
423 uint32_t tmp_adc_is_conversion_on_going_injected
;
425 /* Check ADC handle */
431 /* Check the parameters */
432 assert_param(IS_ADC_ALL_INSTANCE(hadc
->Instance
));
433 assert_param(IS_ADC_CLOCKPRESCALER(hadc
->Init
.ClockPrescaler
));
434 assert_param(IS_ADC_RESOLUTION(hadc
->Init
.Resolution
));
435 assert_param(IS_ADC_SCAN_MODE(hadc
->Init
.ScanConvMode
));
436 assert_param(IS_FUNCTIONAL_STATE(hadc
->Init
.ContinuousConvMode
));
437 assert_param(IS_ADC_EXTTRIG_EDGE(hadc
->Init
.ExternalTrigConvEdge
));
438 assert_param(IS_ADC_EXTTRIG(hadc
->Init
.ExternalTrigConv
));
439 assert_param(IS_ADC_CONVERSIONDATAMGT(hadc
->Init
.ConversionDataManagement
));
440 assert_param(IS_ADC_EOC_SELECTION(hadc
->Init
.EOCSelection
));
441 assert_param(IS_ADC_OVERRUN(hadc
->Init
.Overrun
));
442 assert_param(IS_FUNCTIONAL_STATE(hadc
->Init
.LowPowerAutoWait
));
443 assert_param(IS_FUNCTIONAL_STATE(hadc
->Init
.OversamplingMode
));
445 if (hadc
->Init
.ScanConvMode
!= ADC_SCAN_DISABLE
)
447 assert_param(IS_ADC_REGULAR_NB_CONV(hadc
->Init
.NbrOfConversion
));
448 assert_param(IS_FUNCTIONAL_STATE(hadc
->Init
.DiscontinuousConvMode
));
450 if (hadc
->Init
.DiscontinuousConvMode
== ENABLE
)
452 assert_param(IS_ADC_REGULAR_DISCONT_NUMBER(hadc
->Init
.NbrOfDiscConversion
));
456 /* DISCEN and CONT bits cannot be set at the same time */
457 assert_param(!((hadc
->Init
.DiscontinuousConvMode
== ENABLE
) && (hadc
->Init
.ContinuousConvMode
== ENABLE
)));
459 /* Actions performed only if ADC is coming from state reset: */
460 /* - Initialization of ADC MSP */
461 if (hadc
->State
== HAL_ADC_STATE_RESET
)
463 #if (USE_HAL_ADC_REGISTER_CALLBACKS == 1)
464 /* Init the ADC Callback settings */
465 hadc
->ConvCpltCallback
= HAL_ADC_ConvCpltCallback
; /* Legacy weak callback */
466 hadc
->ConvHalfCpltCallback
= HAL_ADC_ConvHalfCpltCallback
; /* Legacy weak callback */
467 hadc
->LevelOutOfWindowCallback
= HAL_ADC_LevelOutOfWindowCallback
; /* Legacy weak callback */
468 hadc
->ErrorCallback
= HAL_ADC_ErrorCallback
; /* Legacy weak callback */
469 hadc
->InjectedConvCpltCallback
= HAL_ADCEx_InjectedConvCpltCallback
; /* Legacy weak callback */
470 hadc
->InjectedQueueOverflowCallback
= HAL_ADCEx_InjectedQueueOverflowCallback
; /* Legacy weak callback */
471 hadc
->LevelOutOfWindow2Callback
= HAL_ADCEx_LevelOutOfWindow2Callback
; /* Legacy weak callback */
472 hadc
->LevelOutOfWindow3Callback
= HAL_ADCEx_LevelOutOfWindow3Callback
; /* Legacy weak callback */
473 hadc
->EndOfSamplingCallback
= HAL_ADCEx_EndOfSamplingCallback
; /* Legacy weak callback */
475 if (hadc
->MspInitCallback
== NULL
)
477 hadc
->MspInitCallback
= HAL_ADC_MspInit
; /* Legacy weak MspInit */
480 /* Init the low level hardware */
481 hadc
->MspInitCallback(hadc
);
483 /* Init the low level hardware */
484 HAL_ADC_MspInit(hadc
);
485 #endif /* USE_HAL_ADC_REGISTER_CALLBACKS */
487 /* Set ADC error code to none */
488 ADC_CLEAR_ERRORCODE(hadc
);
490 /* Initialize Lock */
491 hadc
->Lock
= HAL_UNLOCKED
;
494 /* - Exit from deep-power-down mode and ADC voltage regulator enable */
495 if (LL_ADC_IsDeepPowerDownEnabled(hadc
->Instance
) != 0UL)
497 /* Disable ADC deep power down mode */
498 LL_ADC_DisableDeepPowerDown(hadc
->Instance
);
500 /* System was in deep power down mode, calibration must
501 be relaunched or a previously saved calibration factor
502 re-applied once the ADC voltage regulator is enabled */
505 if (LL_ADC_IsInternalRegulatorEnabled(hadc
->Instance
) == 0UL)
507 /* Enable ADC internal voltage regulator */
508 LL_ADC_EnableInternalRegulator(hadc
->Instance
);
510 /* Note: Variable divided by 2 to compensate partially */
511 /* CPU processing cycles, scaling in us split to not */
512 /* exceed 32 bits register capacity and handle low frequency. */
513 wait_loop_index
= ((LL_ADC_DELAY_INTERNAL_REGUL_STAB_US
/ 10UL) * (SystemCoreClock
/ (100000UL * 2UL)));
514 while (wait_loop_index
!= 0UL)
520 /* Verification that ADC voltage regulator is correctly enabled, whether */
521 /* or not ADC is coming from state reset (if any potential problem of */
522 /* clocking, voltage regulator would not be enabled). */
523 if (LL_ADC_IsInternalRegulatorEnabled(hadc
->Instance
) == 0UL)
525 /* Update ADC state machine to error */
526 SET_BIT(hadc
->State
, HAL_ADC_STATE_ERROR_INTERNAL
);
528 /* Set ADC error code to ADC peripheral internal error */
529 SET_BIT(hadc
->ErrorCode
, HAL_ADC_ERROR_INTERNAL
);
531 tmp_hal_status
= HAL_ERROR
;
534 /* Configuration of ADC parameters if previous preliminary actions are */
535 /* correctly completed and if there is no conversion on going on regular */
536 /* group (ADC may already be enabled at this point if HAL_ADC_Init() is */
537 /* called to update a parameter on the fly). */
538 tmp_adc_reg_is_conversion_on_going
= LL_ADC_REG_IsConversionOngoing(hadc
->Instance
);
540 if (((hadc
->State
& HAL_ADC_STATE_ERROR_INTERNAL
) == 0UL)
541 && (tmp_adc_reg_is_conversion_on_going
== 0UL)
545 ADC_STATE_CLR_SET(hadc
->State
,
546 HAL_ADC_STATE_REG_BUSY
,
547 HAL_ADC_STATE_BUSY_INTERNAL
);
549 /* Configuration of common ADC parameters */
551 /* Parameters update conditioned to ADC state: */
552 /* Parameters that can be updated only when ADC is disabled: */
553 /* - clock configuration */
554 if (LL_ADC_IsEnabled(hadc
->Instance
) == 0UL)
556 if (__LL_ADC_IS_ENABLED_ALL_COMMON_INSTANCE(__LL_ADC_COMMON_INSTANCE(hadc
->Instance
)) == 0UL)
558 /* Reset configuration of ADC common register CCR: */
560 /* - ADC clock mode and ACC prescaler (CKMODE and PRESC bits)are set */
561 /* according to adc->Init.ClockPrescaler. It selects the clock */
562 /* source and sets the clock division factor. */
564 /* Some parameters of this register are not reset, since they are set */
565 /* by other functions and must be kept in case of usage of this */
566 /* function on the fly (update of a parameter of ADC_InitTypeDef */
567 /* without needing to reconfigure all other ADC groups/channels */
569 /* - when multimode feature is available, multimode-related */
570 /* parameters: MDMA, DMACFG, DELAY, DUAL (set by API */
571 /* HAL_ADCEx_MultiModeConfigChannel() ) */
572 /* - internal measurement paths: Vbat, temperature sensor, Vref */
573 /* (set into HAL_ADC_ConfigChannel() or */
574 /* HAL_ADCEx_InjectedConfigChannel() ) */
575 LL_ADC_SetCommonClock(__LL_ADC_COMMON_INSTANCE(hadc
->Instance
), hadc
->Init
.ClockPrescaler
);
579 /* Configuration of ADC: */
580 /* - resolution Init.Resolution */
581 /* - external trigger to start conversion Init.ExternalTrigConv */
582 /* - external trigger polarity Init.ExternalTrigConvEdge */
583 /* - continuous conversion mode Init.ContinuousConvMode */
584 /* - overrun Init.Overrun */
585 /* - discontinuous mode Init.DiscontinuousConvMode */
586 /* - discontinuous mode channel count Init.NbrOfDiscConversion */
587 #if defined(ADC_VER_V5_3)
589 tmpCFGR
= (ADC_CFGR_CONTINUOUS((uint32_t)hadc
->Init
.ContinuousConvMode
) |
591 hadc
->Init
.Resolution
|
592 ADC_CFGR_REG_DISCONTINUOUS((uint32_t)hadc
->Init
.DiscontinuousConvMode
));
594 #elif defined(ADC_VER_V5_V90)
595 if (hadc
->Instance
== ADC3
)
597 tmpCFGR
= (ADC_CFGR_CONTINUOUS((uint32_t)hadc
->Init
.ContinuousConvMode
) |
599 hadc
->Init
.DataAlign
|
600 ((__LL_ADC12_RESOLUTION_TO_ADC3(hadc
->Init
.Resolution
) & (ADC_CFGR_RES_1
| ADC_CFGR_RES_0
)) << 1UL) |
601 ADC_CFGR_REG_DISCONTINUOUS((uint32_t)hadc
->Init
.DiscontinuousConvMode
));
605 tmpCFGR
= (ADC_CFGR_CONTINUOUS((uint32_t)hadc
->Init
.ContinuousConvMode
) |
607 hadc
->Init
.Resolution
|
608 ADC_CFGR_REG_DISCONTINUOUS((uint32_t)hadc
->Init
.DiscontinuousConvMode
));
613 if ((HAL_GetREVID() > REV_ID_Y
) && (ADC_RESOLUTION_8B
== hadc
->Init
.Resolution
))
615 /* for STM32H7 silicon rev.B and above , ADC_CFGR_RES value for 8bits resolution is : b111 */
616 tmpCFGR
= (ADC_CFGR_CONTINUOUS((uint32_t)hadc
->Init
.ContinuousConvMode
) |
618 hadc
->Init
.Resolution
| (ADC_CFGR_RES_1
| ADC_CFGR_RES_0
) |
619 ADC_CFGR_REG_DISCONTINUOUS((uint32_t)hadc
->Init
.DiscontinuousConvMode
));
624 tmpCFGR
= (ADC_CFGR_CONTINUOUS((uint32_t)hadc
->Init
.ContinuousConvMode
) |
626 hadc
->Init
.Resolution
|
627 ADC_CFGR_REG_DISCONTINUOUS((uint32_t)hadc
->Init
.DiscontinuousConvMode
));
630 #endif /* ADC_VER_V5_3 */
632 if (hadc
->Init
.DiscontinuousConvMode
== ENABLE
)
634 tmpCFGR
|= ADC_CFGR_DISCONTINUOUS_NUM(hadc
->Init
.NbrOfDiscConversion
);
637 /* Enable external trigger if trigger selection is different of software */
639 /* Note: This configuration keeps the hardware feature of parameter */
640 /* ExternalTrigConvEdge "trigger edge none" equivalent to */
641 /* software start. */
642 if (hadc
->Init
.ExternalTrigConv
!= ADC_SOFTWARE_START
)
644 tmpCFGR
|= ((hadc
->Init
.ExternalTrigConv
& ADC_CFGR_EXTSEL
)
645 | hadc
->Init
.ExternalTrigConvEdge
650 #if defined(ADC_VER_V5_V90)
651 if (hadc
->Instance
== ADC3
)
653 /* Update Configuration Register CFGR */
654 MODIFY_REG(hadc
->Instance
->CFGR
, ADC3_CFGR_FIELDS_1
, tmpCFGR
);
655 /* Configuration of sampling mode */
656 MODIFY_REG(hadc
->Instance
->CFGR2
, ADC3_CFGR2_BULB
| ADC3_CFGR2_SMPTRIG
, hadc
->Init
.SamplingMode
);
660 /* Update Configuration Register CFGR */
661 MODIFY_REG(hadc
->Instance
->CFGR
, ADC_CFGR_FIELDS_1
, tmpCFGR
);
664 /* Update Configuration Register CFGR */
665 MODIFY_REG(hadc
->Instance
->CFGR
, ADC_CFGR_FIELDS_1
, tmpCFGR
);
668 /* Parameters update conditioned to ADC state: */
669 /* Parameters that can be updated when ADC is disabled or enabled without */
670 /* conversion on going on regular and injected groups: */
671 /* - Conversion data management Init.ConversionDataManagement */
672 /* - LowPowerAutoWait feature Init.LowPowerAutoWait */
673 /* - Oversampling parameters Init.Oversampling */
674 tmp_adc_is_conversion_on_going_regular
= LL_ADC_REG_IsConversionOngoing(hadc
->Instance
);
675 tmp_adc_is_conversion_on_going_injected
= LL_ADC_INJ_IsConversionOngoing(hadc
->Instance
);
676 if ((tmp_adc_is_conversion_on_going_regular
== 0UL)
677 && (tmp_adc_is_conversion_on_going_injected
== 0UL)
680 #if defined(ADC_VER_V5_V90)
681 if (hadc
->Instance
== ADC3
)
684 ADC_CFGR_AUTOWAIT((uint32_t)hadc
->Init
.LowPowerAutoWait
) |
685 ADC3_CFGR_DMACONTREQ((uint32_t)hadc
->Init
.DMAContinuousRequests
));
690 ADC_CFGR_AUTOWAIT((uint32_t)hadc
->Init
.LowPowerAutoWait
) |
691 ADC_CFGR_DMACONTREQ((uint32_t)hadc
->Init
.ConversionDataManagement
));
695 ADC_CFGR_AUTOWAIT((uint32_t)hadc
->Init
.LowPowerAutoWait
) |
696 ADC_CFGR_DMACONTREQ((uint32_t)hadc
->Init
.ConversionDataManagement
));
699 MODIFY_REG(hadc
->Instance
->CFGR
, ADC_CFGR_FIELDS_2
, tmpCFGR
);
701 if (hadc
->Init
.OversamplingMode
== ENABLE
)
703 #if defined(ADC_VER_V5_V90)
704 if (hadc
->Instance
== ADC3
)
706 assert_param(IS_ADC_OVERSAMPLING_RATIO_ADC3(hadc
->Init
.Oversampling
.Ratio
));
710 assert_param(IS_ADC_OVERSAMPLING_RATIO(hadc
->Init
.Oversampling
.Ratio
));
713 assert_param(IS_ADC_OVERSAMPLING_RATIO(hadc
->Init
.Oversampling
.Ratio
));
715 assert_param(IS_ADC_RIGHT_BIT_SHIFT(hadc
->Init
.Oversampling
.RightBitShift
));
716 assert_param(IS_ADC_TRIGGERED_OVERSAMPLING_MODE(hadc
->Init
.Oversampling
.TriggeredMode
));
717 assert_param(IS_ADC_REGOVERSAMPLING_MODE(hadc
->Init
.Oversampling
.OversamplingStopReset
));
719 if ((hadc
->Init
.ExternalTrigConv
== ADC_SOFTWARE_START
)
720 || (hadc
->Init
.ExternalTrigConvEdge
== ADC_EXTERNALTRIGCONVEDGE_NONE
))
722 /* Multi trigger is not applicable to software-triggered conversions */
723 assert_param((hadc
->Init
.Oversampling
.TriggeredMode
== ADC_TRIGGEREDMODE_SINGLE_TRIGGER
));
726 #if defined(ADC_VER_V5_V90)
727 if (hadc
->Instance
== ADC3
)
729 /* Configuration of Oversampler: */
730 /* - Oversampling Ratio */
731 /* - Right bit shift */
732 /* - Triggered mode */
733 /* - Oversampling mode (continued/resumed) */
734 MODIFY_REG(hadc
->Instance
->CFGR2
,
740 hadc
->Init
.Oversampling
.Ratio
|
741 hadc
->Init
.Oversampling
.RightBitShift
|
742 hadc
->Init
.Oversampling
.TriggeredMode
|
743 hadc
->Init
.Oversampling
.OversamplingStopReset
749 /* Configuration of Oversampler: */
750 /* - Oversampling Ratio */
751 /* - Right bit shift */
752 /* - Left bit shift */
753 /* - Triggered mode */
754 /* - Oversampling mode (continued/resumed) */
755 MODIFY_REG(hadc
->Instance
->CFGR2
, ADC_CFGR2_FIELDS
,
757 ((hadc
->Init
.Oversampling
.Ratio
- 1UL) << ADC_CFGR2_OVSR_Pos
) |
758 hadc
->Init
.Oversampling
.RightBitShift
|
759 hadc
->Init
.Oversampling
.TriggeredMode
|
760 hadc
->Init
.Oversampling
.OversamplingStopReset
);
763 /* Configuration of Oversampler: */
764 /* - Oversampling Ratio */
765 /* - Right bit shift */
766 /* - Left bit shift */
767 /* - Triggered mode */
768 /* - Oversampling mode (continued/resumed) */
769 MODIFY_REG(hadc
->Instance
->CFGR2
, ADC_CFGR2_FIELDS
,
771 ((hadc
->Init
.Oversampling
.Ratio
- 1UL) << ADC_CFGR2_OVSR_Pos
) |
772 hadc
->Init
.Oversampling
.RightBitShift
|
773 hadc
->Init
.Oversampling
.TriggeredMode
|
774 hadc
->Init
.Oversampling
.OversamplingStopReset
);
780 /* Disable ADC oversampling scope on ADC group regular */
781 CLEAR_BIT(hadc
->Instance
->CFGR2
, ADC_CFGR2_ROVSE
);
784 /* Set the LeftShift parameter: it is applied to the final result with or without oversampling */
785 MODIFY_REG(hadc
->Instance
->CFGR2
, ADC_CFGR2_LSHIFT
, hadc
->Init
.LeftBitShift
);
786 #if defined(ADC_VER_V5_V90)
787 if (hadc
->Instance
!= ADC3
)
789 /* Configure the BOOST Mode */
790 ADC_ConfigureBoostMode(hadc
);
793 /* Configure the BOOST Mode */
794 ADC_ConfigureBoostMode(hadc
);
798 /* Configuration of regular group sequencer: */
799 /* - if scan mode is disabled, regular channels sequence length is set to */
800 /* 0x00: 1 channel converted (channel on regular rank 1) */
801 /* Parameter "NbrOfConversion" is discarded. */
802 /* Note: Scan mode is not present by hardware on this device, but */
803 /* emulated by software for alignment over all STM32 devices. */
804 /* - if scan mode is enabled, regular channels sequence length is set to */
805 /* parameter "NbrOfConversion". */
807 if (hadc
->Init
.ScanConvMode
== ADC_SCAN_ENABLE
)
809 /* Set number of ranks in regular group sequencer */
810 MODIFY_REG(hadc
->Instance
->SQR1
, ADC_SQR1_L
, (hadc
->Init
.NbrOfConversion
- (uint8_t)1));
814 CLEAR_BIT(hadc
->Instance
->SQR1
, ADC_SQR1_L
);
817 /* Initialize the ADC state */
818 /* Clear HAL_ADC_STATE_BUSY_INTERNAL bit, set HAL_ADC_STATE_READY bit */
819 ADC_STATE_CLR_SET(hadc
->State
, HAL_ADC_STATE_BUSY_INTERNAL
, HAL_ADC_STATE_READY
);
823 /* Update ADC state machine to error */
824 SET_BIT(hadc
->State
, HAL_ADC_STATE_ERROR_INTERNAL
);
826 tmp_hal_status
= HAL_ERROR
;
829 /* Return function status */
830 return tmp_hal_status
;
834 * @brief Deinitialize the ADC peripheral registers to their default reset
835 * values, with deinitialization of the ADC MSP.
836 * @note For devices with several ADCs: reset of ADC common registers is done
837 * only if all ADCs sharing the same common group are disabled.
838 * (function "HAL_ADC_MspDeInit()" is also called under the same conditions:
839 * all ADC instances use the same core clock at RCC level, disabling
840 * the core clock reset all ADC instances).
841 * If this is not the case, reset of these common parameters reset is
842 * bypassed without error reporting: it can be the intended behavior in
843 * case of reset of a single ADC while the other ADCs sharing the same
844 * common group is still running.
845 * @note By default, HAL_ADC_DeInit() set ADC in mode deep power-down:
846 * this saves more power by reducing leakage currents
847 * and is particularly interesting before entering MCU low-power modes.
848 * @param hadc ADC handle
851 HAL_StatusTypeDef
HAL_ADC_DeInit(ADC_HandleTypeDef
*hadc
)
853 HAL_StatusTypeDef tmp_hal_status
;
855 /* Check ADC handle */
861 /* Check the parameters */
862 assert_param(IS_ADC_ALL_INSTANCE(hadc
->Instance
));
865 SET_BIT(hadc
->State
, HAL_ADC_STATE_BUSY_INTERNAL
);
867 /* Stop potential conversion on going */
868 tmp_hal_status
= ADC_ConversionStop(hadc
, ADC_REGULAR_INJECTED_GROUP
);
870 /* Disable ADC peripheral if conversions are effectively stopped */
871 /* Flush register JSQR: reset the queue sequencer when injected */
872 /* queue sequencer is enabled and ADC disabled. */
873 /* The software and hardware triggers of the injected sequence are both */
874 /* internally disabled just after the completion of the last valid */
875 /* injected sequence. */
876 SET_BIT(hadc
->Instance
->CFGR
, ADC_CFGR_JQM
);
878 /* Disable ADC peripheral if conversions are effectively stopped */
879 if (tmp_hal_status
== HAL_OK
)
881 /* Disable the ADC peripheral */
882 tmp_hal_status
= ADC_Disable(hadc
);
884 /* Check if ADC is effectively disabled */
885 if (tmp_hal_status
== HAL_OK
)
887 /* Change ADC state */
888 hadc
->State
= HAL_ADC_STATE_READY
;
892 /* Note: HAL ADC deInit is done independently of ADC conversion stop */
893 /* and disable return status. In case of status fail, attempt to */
894 /* perform deinitialization anyway and it is up user code in */
895 /* in HAL_ADC_MspDeInit() to reset the ADC peripheral using */
896 /* system RCC hard reset. */
898 /* ========== Reset ADC registers ========== */
899 /* Reset register IER */
900 __HAL_ADC_DISABLE_IT(hadc
, (ADC_IT_AWD3
| ADC_IT_AWD2
| ADC_IT_AWD1
|
901 ADC_IT_JQOVF
| ADC_IT_OVR
|
902 ADC_IT_JEOS
| ADC_IT_JEOC
|
903 ADC_IT_EOS
| ADC_IT_EOC
|
904 ADC_IT_EOSMP
| ADC_IT_RDY
));
906 /* Reset register ISR */
907 __HAL_ADC_CLEAR_FLAG(hadc
, (ADC_FLAG_AWD3
| ADC_FLAG_AWD2
| ADC_FLAG_AWD1
|
908 ADC_FLAG_JQOVF
| ADC_FLAG_OVR
|
909 ADC_FLAG_JEOS
| ADC_FLAG_JEOC
|
910 ADC_FLAG_EOS
| ADC_FLAG_EOC
|
911 ADC_FLAG_EOSMP
| ADC_FLAG_RDY
));
913 /* Reset register CR */
914 /* Bits ADC_CR_JADSTP, ADC_CR_ADSTP, ADC_CR_JADSTART, ADC_CR_ADSTART,
915 ADC_CR_ADCAL, ADC_CR_ADDIS and ADC_CR_ADEN are in access mode "read-set":
916 no direct reset applicable.
917 Update CR register to reset value where doable by software */
918 CLEAR_BIT(hadc
->Instance
->CR
, ADC_CR_ADVREGEN
| ADC_CR_ADCALDIF
);
919 SET_BIT(hadc
->Instance
->CR
, ADC_CR_DEEPPWD
);
921 /* Reset register CFGR */
922 CLEAR_BIT(hadc
->Instance
->CFGR
, ADC_CFGR_AWD1CH
| ADC_CFGR_JAUTO
| ADC_CFGR_JAWD1EN
|
923 ADC_CFGR_AWD1EN
| ADC_CFGR_AWD1SGL
| ADC_CFGR_JQM
|
924 ADC_CFGR_JDISCEN
| ADC_CFGR_DISCNUM
| ADC_CFGR_DISCEN
|
925 ADC_CFGR_AUTDLY
| ADC_CFGR_CONT
| ADC_CFGR_OVRMOD
|
926 ADC_CFGR_EXTEN
| ADC_CFGR_EXTSEL
|
927 ADC_CFGR_RES
| ADC_CFGR_DMNGT
);
928 SET_BIT(hadc
->Instance
->CFGR
, ADC_CFGR_JQDIS
);
930 /* Reset register CFGR2 */
931 CLEAR_BIT(hadc
->Instance
->CFGR2
, ADC_CFGR2_ROVSM
| ADC_CFGR2_TROVS
| ADC_CFGR2_OVSS
|
932 ADC_CFGR2_OVSR
| ADC_CFGR2_JOVSE
| ADC_CFGR2_ROVSE
);
934 /* Reset register SMPR1 */
935 CLEAR_BIT(hadc
->Instance
->SMPR1
, ADC_SMPR1_FIELDS
);
937 /* Reset register SMPR2 */
938 CLEAR_BIT(hadc
->Instance
->SMPR2
, ADC_SMPR2_SMP18
| ADC_SMPR2_SMP17
| ADC_SMPR2_SMP16
|
939 ADC_SMPR2_SMP15
| ADC_SMPR2_SMP14
| ADC_SMPR2_SMP13
|
940 ADC_SMPR2_SMP12
| ADC_SMPR2_SMP11
| ADC_SMPR2_SMP10
);
942 #if defined(ADC_VER_V5_V90)
943 if (hadc
->Instance
== ADC3
)
945 /* Reset register LTR1 and HTR1 */
946 CLEAR_BIT(hadc
->Instance
->LTR1_TR1
, ADC3_TR1_HT1
| ADC3_TR1_LT1
);
947 CLEAR_BIT(hadc
->Instance
->HTR1_TR2
, ADC3_TR2_HT2
| ADC3_TR2_LT2
);
949 /* Reset register LTR3 and HTR3 */
950 CLEAR_BIT(hadc
->Instance
->RES1_TR3
, ADC3_TR3_HT3
| ADC3_TR3_LT3
);
954 CLEAR_BIT(hadc
->Instance
->LTR1_TR1
, ADC_LTR_LT
);
955 CLEAR_BIT(hadc
->Instance
->HTR1_TR2
, ADC_HTR_HT
);
957 /* Reset register LTR2 and HTR2*/
958 CLEAR_BIT(hadc
->Instance
->LTR2_DIFSEL
, ADC_LTR_LT
);
959 CLEAR_BIT(hadc
->Instance
->HTR2_CALFACT
, ADC_HTR_HT
);
961 /* Reset register LTR3 and HTR3 */
962 CLEAR_BIT(hadc
->Instance
->LTR3_RES10
, ADC_LTR_LT
);
963 CLEAR_BIT(hadc
->Instance
->HTR3_RES11
, ADC_HTR_HT
);
966 /* Reset register LTR1 and HTR1 */
967 CLEAR_BIT(hadc
->Instance
->LTR1
, ADC_LTR_LT
);
968 CLEAR_BIT(hadc
->Instance
->HTR1
, ADC_HTR_HT
);
970 /* Reset register LTR2 and HTR2*/
971 CLEAR_BIT(hadc
->Instance
->LTR2
, ADC_LTR_LT
);
972 CLEAR_BIT(hadc
->Instance
->HTR2
, ADC_HTR_HT
);
974 /* Reset register LTR3 and HTR3 */
975 CLEAR_BIT(hadc
->Instance
->LTR3
, ADC_LTR_LT
);
976 CLEAR_BIT(hadc
->Instance
->HTR3
, ADC_HTR_HT
);
977 #endif /* ADC_VER_V5_V90 */
980 /* Reset register SQR1 */
981 CLEAR_BIT(hadc
->Instance
->SQR1
, ADC_SQR1_SQ4
| ADC_SQR1_SQ3
| ADC_SQR1_SQ2
|
982 ADC_SQR1_SQ1
| ADC_SQR1_L
);
984 /* Reset register SQR2 */
985 CLEAR_BIT(hadc
->Instance
->SQR2
, ADC_SQR2_SQ9
| ADC_SQR2_SQ8
| ADC_SQR2_SQ7
|
986 ADC_SQR2_SQ6
| ADC_SQR2_SQ5
);
988 /* Reset register SQR3 */
989 CLEAR_BIT(hadc
->Instance
->SQR3
, ADC_SQR3_SQ14
| ADC_SQR3_SQ13
| ADC_SQR3_SQ12
|
990 ADC_SQR3_SQ11
| ADC_SQR3_SQ10
);
992 /* Reset register SQR4 */
993 CLEAR_BIT(hadc
->Instance
->SQR4
, ADC_SQR4_SQ16
| ADC_SQR4_SQ15
);
995 /* Register JSQR was reset when the ADC was disabled */
997 /* Reset register DR */
998 /* bits in access mode read only, no direct reset applicable*/
1000 /* Reset register OFR1 */
1001 CLEAR_BIT(hadc
->Instance
->OFR1
, ADC_OFR1_SSATE
| ADC_OFR1_OFFSET1_CH
| ADC_OFR1_OFFSET1
);
1002 /* Reset register OFR2 */
1003 CLEAR_BIT(hadc
->Instance
->OFR2
, ADC_OFR2_SSATE
| ADC_OFR2_OFFSET2_CH
| ADC_OFR2_OFFSET2
);
1004 /* Reset register OFR3 */
1005 CLEAR_BIT(hadc
->Instance
->OFR3
, ADC_OFR3_SSATE
| ADC_OFR3_OFFSET3_CH
| ADC_OFR3_OFFSET3
);
1006 /* Reset register OFR4 */
1007 CLEAR_BIT(hadc
->Instance
->OFR4
, ADC_OFR4_SSATE
| ADC_OFR4_OFFSET4_CH
| ADC_OFR4_OFFSET4
);
1009 /* Reset registers JDR1, JDR2, JDR3, JDR4 */
1010 /* bits in access mode read only, no direct reset applicable*/
1012 /* Reset register AWD2CR */
1013 CLEAR_BIT(hadc
->Instance
->AWD2CR
, ADC_AWD2CR_AWD2CH
);
1015 /* Reset register AWD3CR */
1016 CLEAR_BIT(hadc
->Instance
->AWD3CR
, ADC_AWD3CR_AWD3CH
);
1018 #if defined(ADC_VER_V5_V90)
1019 if (hadc
->Instance
== ADC3
)
1021 /* Reset register DIFSEL */
1022 CLEAR_BIT(hadc
->Instance
->LTR2_DIFSEL
, ADC_DIFSEL_DIFSEL
);
1024 /* Reset register CALFACT */
1025 CLEAR_BIT(hadc
->Instance
->HTR2_CALFACT
, ADC_CALFACT_CALFACT_D
| ADC_CALFACT_CALFACT_S
);
1029 /* Reset register DIFSEL */
1030 CLEAR_BIT(hadc
->Instance
->DIFSEL_RES12
, ADC_DIFSEL_DIFSEL
);
1032 /* Reset register CALFACT */
1033 CLEAR_BIT(hadc
->Instance
->CALFACT_RES13
, ADC_CALFACT_CALFACT_D
| ADC_CALFACT_CALFACT_S
);
1036 /* Reset register DIFSEL */
1037 CLEAR_BIT(hadc
->Instance
->DIFSEL
, ADC_DIFSEL_DIFSEL
);
1039 /* Reset register CALFACT */
1040 CLEAR_BIT(hadc
->Instance
->CALFACT
, ADC_CALFACT_CALFACT_D
| ADC_CALFACT_CALFACT_S
);
1041 #endif /* ADC_VER_V5_V90 */
1043 /* ========== Reset common ADC registers ========== */
1045 /* Software is allowed to change common parameters only when all the other
1046 ADCs are disabled. */
1047 if (__LL_ADC_IS_ENABLED_ALL_COMMON_INSTANCE(__LL_ADC_COMMON_INSTANCE(hadc
->Instance
)) == 0UL)
1049 /* Reset configuration of ADC common register CCR:
1050 - clock mode: CKMODE, PRESCEN
1051 - multimode related parameters(when this feature is available): DELAY, DUAL
1052 (set into HAL_ADCEx_MultiModeConfigChannel() API)
1053 - internal measurement paths: Vbat, temperature sensor, Vref (set into
1054 HAL_ADC_ConfigChannel() or HAL_ADCEx_InjectedConfigChannel() )
1056 ADC_CLEAR_COMMON_CONTROL_REGISTER(hadc
);
1059 /* DeInit the low level hardware.
1062 __HAL_RCC_ADC_FORCE_RESET();
1063 __HAL_RCC_ADC_RELEASE_RESET();
1064 __HAL_RCC_ADC_CLK_DISABLE();
1066 Keep in mind that all ADCs use the same clock: disabling
1067 the clock will reset all ADCs.
1070 #if (USE_HAL_ADC_REGISTER_CALLBACKS == 1)
1071 if (hadc
->MspDeInitCallback
== NULL
)
1073 hadc
->MspDeInitCallback
= HAL_ADC_MspDeInit
; /* Legacy weak MspDeInit */
1076 /* DeInit the low level hardware: RCC clock, NVIC */
1077 hadc
->MspDeInitCallback(hadc
);
1079 /* DeInit the low level hardware: RCC clock, NVIC */
1080 HAL_ADC_MspDeInit(hadc
);
1081 #endif /* USE_HAL_ADC_REGISTER_CALLBACKS */
1083 /* Set ADC error code to none */
1084 ADC_CLEAR_ERRORCODE(hadc
);
1086 /* Reset injected channel configuration parameters */
1087 hadc
->InjectionConfig
.ContextQueue
= 0;
1088 hadc
->InjectionConfig
.ChannelCount
= 0;
1091 hadc
->State
= HAL_ADC_STATE_RESET
;
1093 /* Process unlocked */
1096 /* Return function status */
1097 return tmp_hal_status
;
1101 * @brief Initialize the ADC MSP.
1102 * @param hadc ADC handle
1105 __weak
void HAL_ADC_MspInit(ADC_HandleTypeDef
*hadc
)
1107 /* Prevent unused argument(s) compilation warning */
1110 /* NOTE : This function should not be modified. When the callback is needed,
1111 function HAL_ADC_MspInit must be implemented in the user file.
1116 * @brief DeInitialize the ADC MSP.
1117 * @param hadc ADC handle
1118 * @note All ADC instances use the same core clock at RCC level, disabling
1119 * the core clock reset all ADC instances).
1122 __weak
void HAL_ADC_MspDeInit(ADC_HandleTypeDef
*hadc
)
1124 /* Prevent unused argument(s) compilation warning */
1127 /* NOTE : This function should not be modified. When the callback is needed,
1128 function HAL_ADC_MspDeInit must be implemented in the user file.
1132 #if (USE_HAL_ADC_REGISTER_CALLBACKS == 1)
1134 * @brief Register a User ADC Callback
1135 * To be used instead of the weak predefined callback
1136 * @param hadc Pointer to a ADC_HandleTypeDef structure that contains
1137 * the configuration information for the specified ADC.
1138 * @param CallbackID ID of the callback to be registered
1139 * This parameter can be one of the following values:
1140 * @arg @ref HAL_ADC_CONVERSION_COMPLETE_CB_ID ADC conversion complete callback ID
1141 * @arg @ref HAL_ADC_CONVERSION_HALF_CB_ID ADC conversion DMA half-transfer callback ID
1142 * @arg @ref HAL_ADC_LEVEL_OUT_OF_WINDOW_1_CB_ID ADC analog watchdog 1 callback ID
1143 * @arg @ref HAL_ADC_ERROR_CB_ID ADC error callback ID
1144 * @arg @ref HAL_ADC_INJ_CONVERSION_COMPLETE_CB_ID ADC group injected conversion complete callback ID
1145 * @arg @ref HAL_ADC_INJ_QUEUE_OVEFLOW_CB_ID ADC group injected context queue overflow callback ID
1146 * @arg @ref HAL_ADC_LEVEL_OUT_OF_WINDOW_2_CB_ID ADC analog watchdog 2 callback ID
1147 * @arg @ref HAL_ADC_LEVEL_OUT_OF_WINDOW_3_CB_ID ADC analog watchdog 3 callback ID
1148 * @arg @ref HAL_ADC_END_OF_SAMPLING_CB_ID ADC end of sampling callback ID
1149 * @arg @ref HAL_ADC_MSPINIT_CB_ID ADC Msp Init callback ID
1150 * @arg @ref HAL_ADC_MSPDEINIT_CB_ID ADC Msp DeInit callback ID
1151 * @param pCallback pointer to the Callback function
1152 * @retval HAL status
1154 HAL_StatusTypeDef
HAL_ADC_RegisterCallback(ADC_HandleTypeDef
*hadc
, HAL_ADC_CallbackIDTypeDef CallbackID
, pADC_CallbackTypeDef pCallback
)
1156 HAL_StatusTypeDef status
= HAL_OK
;
1158 if (pCallback
== NULL
)
1160 /* Update the error code */
1161 hadc
->ErrorCode
|= HAL_ADC_ERROR_INVALID_CALLBACK
;
1166 if ((hadc
->State
& HAL_ADC_STATE_READY
) != 0UL)
1170 case HAL_ADC_CONVERSION_COMPLETE_CB_ID
:
1171 hadc
->ConvCpltCallback
= pCallback
;
1174 case HAL_ADC_CONVERSION_HALF_CB_ID
:
1175 hadc
->ConvHalfCpltCallback
= pCallback
;
1178 case HAL_ADC_LEVEL_OUT_OF_WINDOW_1_CB_ID
:
1179 hadc
->LevelOutOfWindowCallback
= pCallback
;
1182 case HAL_ADC_ERROR_CB_ID
:
1183 hadc
->ErrorCallback
= pCallback
;
1186 case HAL_ADC_INJ_CONVERSION_COMPLETE_CB_ID
:
1187 hadc
->InjectedConvCpltCallback
= pCallback
;
1190 case HAL_ADC_INJ_QUEUE_OVEFLOW_CB_ID
:
1191 hadc
->InjectedQueueOverflowCallback
= pCallback
;
1194 case HAL_ADC_LEVEL_OUT_OF_WINDOW_2_CB_ID
:
1195 hadc
->LevelOutOfWindow2Callback
= pCallback
;
1198 case HAL_ADC_LEVEL_OUT_OF_WINDOW_3_CB_ID
:
1199 hadc
->LevelOutOfWindow3Callback
= pCallback
;
1202 case HAL_ADC_END_OF_SAMPLING_CB_ID
:
1203 hadc
->EndOfSamplingCallback
= pCallback
;
1206 case HAL_ADC_MSPINIT_CB_ID
:
1207 hadc
->MspInitCallback
= pCallback
;
1210 case HAL_ADC_MSPDEINIT_CB_ID
:
1211 hadc
->MspDeInitCallback
= pCallback
;
1215 /* Update the error code */
1216 hadc
->ErrorCode
|= HAL_ADC_ERROR_INVALID_CALLBACK
;
1218 /* Return error status */
1223 else if (HAL_ADC_STATE_RESET
== hadc
->State
)
1227 case HAL_ADC_MSPINIT_CB_ID
:
1228 hadc
->MspInitCallback
= pCallback
;
1231 case HAL_ADC_MSPDEINIT_CB_ID
:
1232 hadc
->MspDeInitCallback
= pCallback
;
1236 /* Update the error code */
1237 hadc
->ErrorCode
|= HAL_ADC_ERROR_INVALID_CALLBACK
;
1239 /* Return error status */
1246 /* Update the error code */
1247 hadc
->ErrorCode
|= HAL_ADC_ERROR_INVALID_CALLBACK
;
1249 /* Return error status */
1257 * @brief Unregister a ADC Callback
1258 * ADC callback is redirected to the weak predefined callback
1259 * @param hadc Pointer to a ADC_HandleTypeDef structure that contains
1260 * the configuration information for the specified ADC.
1261 * @param CallbackID ID of the callback to be unregistered
1262 * This parameter can be one of the following values:
1263 * @arg @ref HAL_ADC_CONVERSION_COMPLETE_CB_ID ADC conversion complete callback ID
1264 * @arg @ref HAL_ADC_CONVERSION_HALF_CB_ID ADC conversion DMA half-transfer callback ID
1265 * @arg @ref HAL_ADC_LEVEL_OUT_OF_WINDOW_1_CB_ID ADC analog watchdog 1 callback ID
1266 * @arg @ref HAL_ADC_ERROR_CB_ID ADC error callback ID
1267 * @arg @ref HAL_ADC_INJ_CONVERSION_COMPLETE_CB_ID ADC group injected conversion complete callback ID
1268 * @arg @ref HAL_ADC_INJ_QUEUE_OVEFLOW_CB_ID ADC group injected context queue overflow callback ID
1269 * @arg @ref HAL_ADC_LEVEL_OUT_OF_WINDOW_2_CB_ID ADC analog watchdog 2 callback ID
1270 * @arg @ref HAL_ADC_LEVEL_OUT_OF_WINDOW_3_CB_ID ADC analog watchdog 3 callback ID
1271 * @arg @ref HAL_ADC_END_OF_SAMPLING_CB_ID ADC end of sampling callback ID
1272 * @arg @ref HAL_ADC_MSPINIT_CB_ID ADC Msp Init callback ID
1273 * @arg @ref HAL_ADC_MSPDEINIT_CB_ID ADC Msp DeInit callback ID
1274 * @retval HAL status
1276 HAL_StatusTypeDef
HAL_ADC_UnRegisterCallback(ADC_HandleTypeDef
*hadc
, HAL_ADC_CallbackIDTypeDef CallbackID
)
1278 HAL_StatusTypeDef status
= HAL_OK
;
1280 if ((hadc
->State
& HAL_ADC_STATE_READY
) != 0UL)
1284 case HAL_ADC_CONVERSION_COMPLETE_CB_ID
:
1285 hadc
->ConvCpltCallback
= HAL_ADC_ConvCpltCallback
;
1288 case HAL_ADC_CONVERSION_HALF_CB_ID
:
1289 hadc
->ConvHalfCpltCallback
= HAL_ADC_ConvHalfCpltCallback
;
1292 case HAL_ADC_LEVEL_OUT_OF_WINDOW_1_CB_ID
:
1293 hadc
->LevelOutOfWindowCallback
= HAL_ADC_LevelOutOfWindowCallback
;
1296 case HAL_ADC_ERROR_CB_ID
:
1297 hadc
->ErrorCallback
= HAL_ADC_ErrorCallback
;
1300 case HAL_ADC_INJ_CONVERSION_COMPLETE_CB_ID
:
1301 hadc
->InjectedConvCpltCallback
= HAL_ADCEx_InjectedConvCpltCallback
;
1304 case HAL_ADC_INJ_QUEUE_OVEFLOW_CB_ID
:
1305 hadc
->InjectedQueueOverflowCallback
= HAL_ADCEx_InjectedQueueOverflowCallback
;
1308 case HAL_ADC_LEVEL_OUT_OF_WINDOW_2_CB_ID
:
1309 hadc
->LevelOutOfWindow2Callback
= HAL_ADCEx_LevelOutOfWindow2Callback
;
1312 case HAL_ADC_LEVEL_OUT_OF_WINDOW_3_CB_ID
:
1313 hadc
->LevelOutOfWindow3Callback
= HAL_ADCEx_LevelOutOfWindow3Callback
;
1316 case HAL_ADC_END_OF_SAMPLING_CB_ID
:
1317 hadc
->EndOfSamplingCallback
= HAL_ADCEx_EndOfSamplingCallback
;
1320 case HAL_ADC_MSPINIT_CB_ID
:
1321 hadc
->MspInitCallback
= HAL_ADC_MspInit
; /* Legacy weak MspInit */
1324 case HAL_ADC_MSPDEINIT_CB_ID
:
1325 hadc
->MspDeInitCallback
= HAL_ADC_MspDeInit
; /* Legacy weak MspDeInit */
1329 /* Update the error code */
1330 hadc
->ErrorCode
|= HAL_ADC_ERROR_INVALID_CALLBACK
;
1332 /* Return error status */
1337 else if (HAL_ADC_STATE_RESET
== hadc
->State
)
1341 case HAL_ADC_MSPINIT_CB_ID
:
1342 hadc
->MspInitCallback
= HAL_ADC_MspInit
; /* Legacy weak MspInit */
1345 case HAL_ADC_MSPDEINIT_CB_ID
:
1346 hadc
->MspDeInitCallback
= HAL_ADC_MspDeInit
; /* Legacy weak MspDeInit */
1350 /* Update the error code */
1351 hadc
->ErrorCode
|= HAL_ADC_ERROR_INVALID_CALLBACK
;
1353 /* Return error status */
1360 /* Update the error code */
1361 hadc
->ErrorCode
|= HAL_ADC_ERROR_INVALID_CALLBACK
;
1363 /* Return error status */
1370 #endif /* USE_HAL_ADC_REGISTER_CALLBACKS */
1376 /** @defgroup ADC_Exported_Functions_Group2 ADC Input and Output operation functions
1377 * @brief ADC IO operation functions
1380 ===============================================================================
1381 ##### IO operation functions #####
1382 ===============================================================================
1383 [..] This section provides functions allowing to:
1384 (+) Start conversion of regular group.
1385 (+) Stop conversion of regular group.
1386 (+) Poll for conversion complete on regular group.
1387 (+) Poll for conversion event.
1388 (+) Get result of regular channel conversion.
1389 (+) Start conversion of regular group and enable interruptions.
1390 (+) Stop conversion of regular group and disable interruptions.
1391 (+) Handle ADC interrupt request
1392 (+) Start conversion of regular group and enable DMA transfer.
1393 (+) Stop conversion of regular group and disable ADC DMA transfer.
1399 * @brief Enable ADC, start conversion of regular group.
1400 * @note Interruptions enabled in this function: None.
1401 * @note Case of multimode enabled (when multimode feature is available):
1402 * if ADC is Slave, ADC is enabled but conversion is not started,
1403 * if ADC is master, ADC is enabled and multimode conversion is started.
1404 * @param hadc ADC handle
1405 * @retval HAL status
1407 HAL_StatusTypeDef
HAL_ADC_Start(ADC_HandleTypeDef
*hadc
)
1409 HAL_StatusTypeDef tmp_hal_status
;
1410 const ADC_TypeDef
*tmpADC_Master
;
1411 uint32_t tmp_multimode_config
= LL_ADC_GetMultimode(__LL_ADC_COMMON_INSTANCE(hadc
->Instance
));
1413 /* Check the parameters */
1414 assert_param(IS_ADC_ALL_INSTANCE(hadc
->Instance
));
1416 /* Perform ADC enable and conversion start if no conversion is on going */
1417 if (LL_ADC_REG_IsConversionOngoing(hadc
->Instance
) == 0UL)
1419 /* Process locked */
1422 /* Enable the ADC peripheral */
1423 tmp_hal_status
= ADC_Enable(hadc
);
1425 /* Start conversion if ADC is effectively enabled */
1426 if (tmp_hal_status
== HAL_OK
)
1429 /* - Clear state bitfield related to regular group conversion results */
1430 /* - Set state bitfield related to regular operation */
1431 ADC_STATE_CLR_SET(hadc
->State
,
1432 HAL_ADC_STATE_READY
| HAL_ADC_STATE_REG_EOC
| HAL_ADC_STATE_REG_OVR
| HAL_ADC_STATE_REG_EOSMP
,
1433 HAL_ADC_STATE_REG_BUSY
);
1435 /* Reset HAL_ADC_STATE_MULTIMODE_SLAVE bit
1436 - if ADC instance is master or if multimode feature is not available
1437 - if multimode setting is disabled (ADC instance slave in independent mode) */
1438 if ((__LL_ADC_MULTI_INSTANCE_MASTER(hadc
->Instance
) == hadc
->Instance
)
1439 || (tmp_multimode_config
== LL_ADC_MULTI_INDEPENDENT
)
1442 CLEAR_BIT(hadc
->State
, HAL_ADC_STATE_MULTIMODE_SLAVE
);
1445 /* Set ADC error code */
1446 /* Check if a conversion is on going on ADC group injected */
1447 if (HAL_IS_BIT_SET(hadc
->State
, HAL_ADC_STATE_INJ_BUSY
))
1449 /* Reset ADC error code fields related to regular conversions only */
1450 CLEAR_BIT(hadc
->ErrorCode
, (HAL_ADC_ERROR_OVR
| HAL_ADC_ERROR_DMA
));
1454 /* Reset all ADC error code fields */
1455 ADC_CLEAR_ERRORCODE(hadc
);
1458 /* Clear ADC group regular conversion flag and overrun flag */
1459 /* (To ensure of no unknown state from potential previous ADC operations) */
1460 __HAL_ADC_CLEAR_FLAG(hadc
, (ADC_FLAG_EOC
| ADC_FLAG_EOS
| ADC_FLAG_OVR
));
1462 /* Process unlocked */
1463 /* Unlock before starting ADC conversions: in case of potential */
1464 /* interruption, to let the process to ADC IRQ Handler. */
1467 /* Enable conversion of regular group. */
1468 /* If software start has been selected, conversion starts immediately. */
1469 /* If external trigger has been selected, conversion will start at next */
1470 /* trigger event. */
1471 /* Case of multimode enabled (when multimode feature is available): */
1472 /* - if ADC is slave and dual regular conversions are enabled, ADC is */
1473 /* enabled only (conversion is not started), */
1474 /* - if ADC is master, ADC is enabled and conversion is started. */
1475 if ((__LL_ADC_MULTI_INSTANCE_MASTER(hadc
->Instance
) == hadc
->Instance
)
1476 || (tmp_multimode_config
== LL_ADC_MULTI_INDEPENDENT
)
1477 || (tmp_multimode_config
== LL_ADC_MULTI_DUAL_INJ_SIMULT
)
1478 || (tmp_multimode_config
== LL_ADC_MULTI_DUAL_INJ_ALTERN
)
1481 /* ADC instance is not a multimode slave instance with multimode regular conversions enabled */
1482 if (READ_BIT(hadc
->Instance
->CFGR
, ADC_CFGR_JAUTO
) != 0UL)
1484 ADC_STATE_CLR_SET(hadc
->State
, HAL_ADC_STATE_INJ_EOC
, HAL_ADC_STATE_INJ_BUSY
);
1487 /* Start ADC group regular conversion */
1488 LL_ADC_REG_StartConversion(hadc
->Instance
);
1492 /* ADC instance is a multimode slave instance with multimode regular conversions enabled */
1493 SET_BIT(hadc
->State
, HAL_ADC_STATE_MULTIMODE_SLAVE
);
1494 /* if Master ADC JAUTO bit is set, update Slave State in setting
1495 HAL_ADC_STATE_INJ_BUSY bit and in resetting HAL_ADC_STATE_INJ_EOC bit */
1496 tmpADC_Master
= __LL_ADC_MULTI_INSTANCE_MASTER(hadc
->Instance
);
1497 if (READ_BIT(tmpADC_Master
->CFGR
, ADC_CFGR_JAUTO
) != 0UL)
1499 ADC_STATE_CLR_SET(hadc
->State
, HAL_ADC_STATE_INJ_EOC
, HAL_ADC_STATE_INJ_BUSY
);
1506 /* Process unlocked */
1512 tmp_hal_status
= HAL_BUSY
;
1515 /* Return function status */
1516 return tmp_hal_status
;
1520 * @brief Stop ADC conversion of regular group (and injected channels in
1521 * case of auto_injection mode), disable ADC peripheral.
1522 * @note: ADC peripheral disable is forcing stop of potential
1523 * conversion on injected group. If injected group is under use, it
1524 * should be preliminarily stopped using HAL_ADCEx_InjectedStop function.
1525 * @param hadc ADC handle
1526 * @retval HAL status.
1528 HAL_StatusTypeDef
HAL_ADC_Stop(ADC_HandleTypeDef
*hadc
)
1530 HAL_StatusTypeDef tmp_hal_status
;
1532 /* Check the parameters */
1533 assert_param(IS_ADC_ALL_INSTANCE(hadc
->Instance
));
1535 /* Process locked */
1538 /* 1. Stop potential conversion on going, on ADC groups regular and injected */
1539 tmp_hal_status
= ADC_ConversionStop(hadc
, ADC_REGULAR_INJECTED_GROUP
);
1541 /* Disable ADC peripheral if conversions are effectively stopped */
1542 if (tmp_hal_status
== HAL_OK
)
1544 /* 2. Disable the ADC peripheral */
1545 tmp_hal_status
= ADC_Disable(hadc
);
1547 /* Check if ADC is effectively disabled */
1548 if (tmp_hal_status
== HAL_OK
)
1551 ADC_STATE_CLR_SET(hadc
->State
,
1552 HAL_ADC_STATE_REG_BUSY
| HAL_ADC_STATE_INJ_BUSY
,
1553 HAL_ADC_STATE_READY
);
1557 /* Process unlocked */
1560 /* Return function status */
1561 return tmp_hal_status
;
1565 * @brief Wait for regular group conversion to be completed.
1566 * @note ADC conversion flags EOS (end of sequence) and EOC (end of
1567 * conversion) are cleared by this function, with an exception:
1568 * if low power feature "LowPowerAutoWait" is enabled, flags are
1569 * not cleared to not interfere with this feature until data register
1570 * is read using function HAL_ADC_GetValue().
1571 * @note This function cannot be used in a particular setup: ADC configured
1572 * in DMA mode and polling for end of each conversion (ADC init
1573 * parameter "EOCSelection" set to ADC_EOC_SINGLE_CONV).
1574 * In this case, DMA resets the flag EOC and polling cannot be
1575 * performed on each conversion. Nevertheless, polling can still
1576 * be performed on the complete sequence (ADC init
1577 * parameter "EOCSelection" set to ADC_EOC_SEQ_CONV).
1578 * @param hadc ADC handle
1579 * @param Timeout Timeout value in millisecond.
1580 * @retval HAL status
1582 HAL_StatusTypeDef
HAL_ADC_PollForConversion(ADC_HandleTypeDef
*hadc
, uint32_t Timeout
)
1585 uint32_t tmp_Flag_End
;
1587 const ADC_TypeDef
*tmpADC_Master
;
1588 uint32_t tmp_multimode_config
= LL_ADC_GetMultimode(__LL_ADC_COMMON_INSTANCE(hadc
->Instance
));
1590 /* Check the parameters */
1591 assert_param(IS_ADC_ALL_INSTANCE(hadc
->Instance
));
1593 /* If end of conversion selected to end of sequence conversions */
1594 if (hadc
->Init
.EOCSelection
== ADC_EOC_SEQ_CONV
)
1596 tmp_Flag_End
= ADC_FLAG_EOS
;
1598 /* If end of conversion selected to end of unitary conversion */
1599 else /* ADC_EOC_SINGLE_CONV */
1601 /* Verification that ADC configuration is compliant with polling for */
1602 /* each conversion: */
1603 /* Particular case is ADC configured in DMA mode and ADC sequencer with */
1604 /* several ranks and polling for end of each conversion. */
1605 /* For code simplicity sake, this particular case is generalized to */
1606 /* ADC configured in DMA mode and and polling for end of each conversion. */
1607 if ((tmp_multimode_config
== LL_ADC_MULTI_INDEPENDENT
)
1608 || (tmp_multimode_config
== LL_ADC_MULTI_DUAL_INJ_SIMULT
)
1609 || (tmp_multimode_config
== LL_ADC_MULTI_DUAL_INJ_ALTERN
)
1612 /* Check DMNGT bit in handle ADC CFGR register */
1613 if (READ_BIT(hadc
->Instance
->CFGR
, ADC_CFGR_DMNGT_0
) != 0UL)
1615 SET_BIT(hadc
->State
, HAL_ADC_STATE_ERROR_CONFIG
);
1620 tmp_Flag_End
= (ADC_FLAG_EOC
);
1625 /* Check ADC DMA mode in multimode on ADC group regular */
1626 if (LL_ADC_GetMultiDMATransfer(__LL_ADC_COMMON_INSTANCE(hadc
->Instance
)) != LL_ADC_MULTI_REG_DMA_EACH_ADC
)
1628 SET_BIT(hadc
->State
, HAL_ADC_STATE_ERROR_CONFIG
);
1633 tmp_Flag_End
= (ADC_FLAG_EOC
);
1638 /* Get tick count */
1639 tickstart
= HAL_GetTick();
1641 /* Wait until End of unitary conversion or sequence conversions flag is raised */
1642 while ((hadc
->Instance
->ISR
& tmp_Flag_End
) == 0UL)
1644 /* Check if timeout is disabled (set to infinite wait) */
1645 if (Timeout
!= HAL_MAX_DELAY
)
1647 if (((HAL_GetTick() - tickstart
) > Timeout
) || (Timeout
== 0UL))
1649 /* Update ADC state machine to timeout */
1650 SET_BIT(hadc
->State
, HAL_ADC_STATE_TIMEOUT
);
1652 /* Process unlocked */
1660 /* Update ADC state machine */
1661 SET_BIT(hadc
->State
, HAL_ADC_STATE_REG_EOC
);
1663 /* Determine whether any further conversion upcoming on group regular */
1664 /* by external trigger, continuous mode or scan sequence on going. */
1665 if ((LL_ADC_REG_IsTriggerSourceSWStart(hadc
->Instance
) != 0UL)
1666 && (hadc
->Init
.ContinuousConvMode
== DISABLE
)
1669 /* Check whether end of sequence is reached */
1670 if (__HAL_ADC_GET_FLAG(hadc
, ADC_FLAG_EOS
))
1673 CLEAR_BIT(hadc
->State
, HAL_ADC_STATE_REG_BUSY
);
1675 if ((hadc
->State
& HAL_ADC_STATE_INJ_BUSY
) == 0UL)
1677 SET_BIT(hadc
->State
, HAL_ADC_STATE_READY
);
1682 /* Get relevant register CFGR in ADC instance of ADC master or slave */
1683 /* in function of multimode state (for devices with multimode */
1685 if ((__LL_ADC_MULTI_INSTANCE_MASTER(hadc
->Instance
) == hadc
->Instance
)
1686 || (tmp_multimode_config
== LL_ADC_MULTI_INDEPENDENT
)
1687 || (tmp_multimode_config
== LL_ADC_MULTI_DUAL_INJ_SIMULT
)
1688 || (tmp_multimode_config
== LL_ADC_MULTI_DUAL_INJ_ALTERN
)
1691 /* Retrieve handle ADC CFGR register */
1692 tmp_cfgr
= READ_REG(hadc
->Instance
->CFGR
);
1696 /* Retrieve Master ADC CFGR register */
1697 tmpADC_Master
= __LL_ADC_MULTI_INSTANCE_MASTER(hadc
->Instance
);
1698 tmp_cfgr
= READ_REG(tmpADC_Master
->CFGR
);
1701 /* Clear polled flag */
1702 if (tmp_Flag_End
== ADC_FLAG_EOS
)
1704 __HAL_ADC_CLEAR_FLAG(hadc
, ADC_FLAG_EOS
);
1708 /* Clear end of conversion EOC flag of regular group if low power feature */
1709 /* "LowPowerAutoWait " is disabled, to not interfere with this feature */
1710 /* until data register is read using function HAL_ADC_GetValue(). */
1711 if (READ_BIT(tmp_cfgr
, ADC_CFGR_AUTDLY
) == 0UL)
1713 __HAL_ADC_CLEAR_FLAG(hadc
, (ADC_FLAG_EOC
| ADC_FLAG_EOS
));
1717 /* Return function status */
1722 * @brief Poll for ADC event.
1723 * @param hadc ADC handle
1724 * @param EventType the ADC event type.
1725 * This parameter can be one of the following values:
1726 * @arg @ref ADC_EOSMP_EVENT ADC End of Sampling event
1727 * @arg @ref ADC_AWD1_EVENT ADC Analog watchdog 1 event (main analog watchdog, present on all STM32 devices)
1728 * @arg @ref ADC_AWD2_EVENT ADC Analog watchdog 2 event (additional analog watchdog, not present on all STM32 families)
1729 * @arg @ref ADC_AWD3_EVENT ADC Analog watchdog 3 event (additional analog watchdog, not present on all STM32 families)
1730 * @arg @ref ADC_OVR_EVENT ADC Overrun event
1731 * @arg @ref ADC_JQOVF_EVENT ADC Injected context queue overflow event
1732 * @param Timeout Timeout value in millisecond.
1733 * @note The relevant flag is cleared if found to be set, except for ADC_FLAG_OVR.
1734 * Indeed, the latter is reset only if hadc->Init.Overrun field is set
1735 * to ADC_OVR_DATA_OVERWRITTEN. Otherwise, data register may be potentially overwritten
1736 * by a new converted data as soon as OVR is cleared.
1737 * To reset OVR flag once the preserved data is retrieved, the user can resort
1738 * to macro __HAL_ADC_CLEAR_FLAG(hadc, ADC_FLAG_OVR);
1739 * @retval HAL status
1741 HAL_StatusTypeDef
HAL_ADC_PollForEvent(ADC_HandleTypeDef
*hadc
, uint32_t EventType
, uint32_t Timeout
)
1745 /* Check the parameters */
1746 assert_param(IS_ADC_ALL_INSTANCE(hadc
->Instance
));
1747 assert_param(IS_ADC_EVENT_TYPE(EventType
));
1749 /* Get tick count */
1750 tickstart
= HAL_GetTick();
1752 /* Check selected event flag */
1753 while (__HAL_ADC_GET_FLAG(hadc
, EventType
) == 0UL)
1755 /* Check if timeout is disabled (set to infinite wait) */
1756 if (Timeout
!= HAL_MAX_DELAY
)
1758 if (((HAL_GetTick() - tickstart
) > Timeout
) || (Timeout
== 0UL))
1760 /* Update ADC state machine to timeout */
1761 SET_BIT(hadc
->State
, HAL_ADC_STATE_TIMEOUT
);
1763 /* Process unlocked */
1773 /* End Of Sampling event */
1774 case ADC_EOSMP_EVENT
:
1776 SET_BIT(hadc
->State
, HAL_ADC_STATE_REG_EOSMP
);
1778 /* Clear the End Of Sampling flag */
1779 __HAL_ADC_CLEAR_FLAG(hadc
, ADC_FLAG_EOSMP
);
1783 /* Analog watchdog (level out of window) event */
1784 /* Note: In case of several analog watchdog enabled, if needed to know */
1785 /* which one triggered and on which ADCx, test ADC state of analog watchdog */
1786 /* flags HAL_ADC_STATE_AWD1/2/3 using function "HAL_ADC_GetState()". */
1788 /* " if ((HAL_ADC_GetState(hadc1) & HAL_ADC_STATE_AWD1) != 0UL) " */
1789 /* " if ((HAL_ADC_GetState(hadc1) & HAL_ADC_STATE_AWD2) != 0UL) " */
1790 /* " if ((HAL_ADC_GetState(hadc1) & HAL_ADC_STATE_AWD3) != 0UL) " */
1792 /* Check analog watchdog 1 flag */
1795 SET_BIT(hadc
->State
, HAL_ADC_STATE_AWD1
);
1797 /* Clear ADC analog watchdog flag */
1798 __HAL_ADC_CLEAR_FLAG(hadc
, ADC_FLAG_AWD1
);
1802 /* Check analog watchdog 2 flag */
1803 case ADC_AWD2_EVENT
:
1805 SET_BIT(hadc
->State
, HAL_ADC_STATE_AWD2
);
1807 /* Clear ADC analog watchdog flag */
1808 __HAL_ADC_CLEAR_FLAG(hadc
, ADC_FLAG_AWD2
);
1812 /* Check analog watchdog 3 flag */
1813 case ADC_AWD3_EVENT
:
1815 SET_BIT(hadc
->State
, HAL_ADC_STATE_AWD3
);
1817 /* Clear ADC analog watchdog flag */
1818 __HAL_ADC_CLEAR_FLAG(hadc
, ADC_FLAG_AWD3
);
1822 /* Injected context queue overflow event */
1823 case ADC_JQOVF_EVENT
:
1825 SET_BIT(hadc
->State
, HAL_ADC_STATE_INJ_JQOVF
);
1827 /* Set ADC error code to Injected context queue overflow */
1828 SET_BIT(hadc
->ErrorCode
, HAL_ADC_ERROR_JQOVF
);
1830 /* Clear ADC Injected context queue overflow flag */
1831 __HAL_ADC_CLEAR_FLAG(hadc
, ADC_FLAG_JQOVF
);
1836 default: /* Case ADC_OVR_EVENT */
1837 /* If overrun is set to overwrite previous data, overrun event is not */
1838 /* considered as an error. */
1839 /* (cf ref manual "Managing conversions without using the DMA and without */
1841 if (hadc
->Init
.Overrun
== ADC_OVR_DATA_PRESERVED
)
1844 SET_BIT(hadc
->State
, HAL_ADC_STATE_REG_OVR
);
1846 /* Set ADC error code to overrun */
1847 SET_BIT(hadc
->ErrorCode
, HAL_ADC_ERROR_OVR
);
1851 /* Clear ADC Overrun flag only if Overrun is set to ADC_OVR_DATA_OVERWRITTEN
1852 otherwise, data register is potentially overwritten by new converted data as soon
1853 as OVR is cleared. */
1854 __HAL_ADC_CLEAR_FLAG(hadc
, ADC_FLAG_OVR
);
1859 /* Return function status */
1864 * @brief Enable ADC, start conversion of regular group with interruption.
1865 * @note Interruptions enabled in this function according to initialization
1866 * setting : EOC (end of conversion), EOS (end of sequence),
1868 * Each of these interruptions has its dedicated callback function.
1869 * @note Case of multimode enabled (when multimode feature is available):
1870 * HAL_ADC_Start_IT() must be called for ADC Slave first, then for
1872 * For ADC Slave, ADC is enabled only (conversion is not started).
1873 * For ADC Master, ADC is enabled and multimode conversion is started.
1874 * @note To guarantee a proper reset of all interruptions once all the needed
1875 * conversions are obtained, HAL_ADC_Stop_IT() must be called to ensure
1876 * a correct stop of the IT-based conversions.
1877 * @note By default, HAL_ADC_Start_IT() does not enable the End Of Sampling
1878 * interruption. If required (e.g. in case of oversampling with trigger
1879 * mode), the user must:
1880 * 1. first clear the EOSMP flag if set with macro __HAL_ADC_CLEAR_FLAG(hadc, ADC_FLAG_EOSMP)
1881 * 2. then enable the EOSMP interrupt with macro __HAL_ADC_ENABLE_IT(hadc, ADC_IT_EOSMP)
1882 * before calling HAL_ADC_Start_IT().
1883 * @param hadc ADC handle
1884 * @retval HAL status
1886 HAL_StatusTypeDef
HAL_ADC_Start_IT(ADC_HandleTypeDef
*hadc
)
1888 HAL_StatusTypeDef tmp_hal_status
;
1889 const ADC_TypeDef
*tmpADC_Master
;
1890 uint32_t tmp_multimode_config
= LL_ADC_GetMultimode(__LL_ADC_COMMON_INSTANCE(hadc
->Instance
));
1892 /* Check the parameters */
1893 assert_param(IS_ADC_ALL_INSTANCE(hadc
->Instance
));
1895 /* Perform ADC enable and conversion start if no conversion is on going */
1896 if (LL_ADC_REG_IsConversionOngoing(hadc
->Instance
) == 0UL)
1898 /* Process locked */
1901 /* Enable the ADC peripheral */
1902 tmp_hal_status
= ADC_Enable(hadc
);
1904 /* Start conversion if ADC is effectively enabled */
1905 if (tmp_hal_status
== HAL_OK
)
1908 /* - Clear state bitfield related to regular group conversion results */
1909 /* - Set state bitfield related to regular operation */
1910 ADC_STATE_CLR_SET(hadc
->State
,
1911 HAL_ADC_STATE_READY
| HAL_ADC_STATE_REG_EOC
| HAL_ADC_STATE_REG_OVR
| HAL_ADC_STATE_REG_EOSMP
,
1912 HAL_ADC_STATE_REG_BUSY
);
1914 /* Reset HAL_ADC_STATE_MULTIMODE_SLAVE bit
1915 - if ADC instance is master or if multimode feature is not available
1916 - if multimode setting is disabled (ADC instance slave in independent mode) */
1917 if ((__LL_ADC_MULTI_INSTANCE_MASTER(hadc
->Instance
) == hadc
->Instance
)
1918 || (tmp_multimode_config
== LL_ADC_MULTI_INDEPENDENT
)
1921 CLEAR_BIT(hadc
->State
, HAL_ADC_STATE_MULTIMODE_SLAVE
);
1924 /* Set ADC error code */
1925 /* Check if a conversion is on going on ADC group injected */
1926 if ((hadc
->State
& HAL_ADC_STATE_INJ_BUSY
) != 0UL)
1928 /* Reset ADC error code fields related to regular conversions only */
1929 CLEAR_BIT(hadc
->ErrorCode
, (HAL_ADC_ERROR_OVR
| HAL_ADC_ERROR_DMA
));
1933 /* Reset all ADC error code fields */
1934 ADC_CLEAR_ERRORCODE(hadc
);
1937 /* Clear ADC group regular conversion flag and overrun flag */
1938 /* (To ensure of no unknown state from potential previous ADC operations) */
1939 __HAL_ADC_CLEAR_FLAG(hadc
, (ADC_FLAG_EOC
| ADC_FLAG_EOS
| ADC_FLAG_OVR
));
1941 /* Process unlocked */
1942 /* Unlock before starting ADC conversions: in case of potential */
1943 /* interruption, to let the process to ADC IRQ Handler. */
1946 /* Disable all interruptions before enabling the desired ones */
1947 __HAL_ADC_DISABLE_IT(hadc
, (ADC_IT_EOC
| ADC_IT_EOS
| ADC_IT_OVR
));
1949 /* Enable ADC end of conversion interrupt */
1950 switch (hadc
->Init
.EOCSelection
)
1952 case ADC_EOC_SEQ_CONV
:
1953 __HAL_ADC_ENABLE_IT(hadc
, ADC_IT_EOS
);
1955 /* case ADC_EOC_SINGLE_CONV */
1957 __HAL_ADC_ENABLE_IT(hadc
, ADC_IT_EOC
);
1961 /* Enable ADC overrun interrupt */
1962 /* If hadc->Init.Overrun is set to ADC_OVR_DATA_PRESERVED, only then is
1963 ADC_IT_OVR enabled; otherwise data overwrite is considered as normal
1964 behavior and no CPU time is lost for a non-processed interruption */
1965 if (hadc
->Init
.Overrun
== ADC_OVR_DATA_PRESERVED
)
1967 __HAL_ADC_ENABLE_IT(hadc
, ADC_IT_OVR
);
1970 /* Enable conversion of regular group. */
1971 /* If software start has been selected, conversion starts immediately. */
1972 /* If external trigger has been selected, conversion will start at next */
1973 /* trigger event. */
1974 /* Case of multimode enabled (when multimode feature is available): */
1975 /* - if ADC is slave and dual regular conversions are enabled, ADC is */
1976 /* enabled only (conversion is not started), */
1977 /* - if ADC is master, ADC is enabled and conversion is started. */
1978 if ((__LL_ADC_MULTI_INSTANCE_MASTER(hadc
->Instance
) == hadc
->Instance
)
1979 || (tmp_multimode_config
== LL_ADC_MULTI_INDEPENDENT
)
1980 || (tmp_multimode_config
== LL_ADC_MULTI_DUAL_INJ_SIMULT
)
1981 || (tmp_multimode_config
== LL_ADC_MULTI_DUAL_INJ_ALTERN
)
1984 /* ADC instance is not a multimode slave instance with multimode regular conversions enabled */
1985 if (READ_BIT(hadc
->Instance
->CFGR
, ADC_CFGR_JAUTO
) != 0UL)
1987 ADC_STATE_CLR_SET(hadc
->State
, HAL_ADC_STATE_INJ_EOC
, HAL_ADC_STATE_INJ_BUSY
);
1989 /* Enable as well injected interruptions in case
1990 HAL_ADCEx_InjectedStart_IT() has not been called beforehand. This
1991 allows to start regular and injected conversions when JAUTO is
1992 set with a single call to HAL_ADC_Start_IT() */
1993 switch (hadc
->Init
.EOCSelection
)
1995 case ADC_EOC_SEQ_CONV
:
1996 __HAL_ADC_DISABLE_IT(hadc
, ADC_IT_JEOC
);
1997 __HAL_ADC_ENABLE_IT(hadc
, ADC_IT_JEOS
);
1999 /* case ADC_EOC_SINGLE_CONV */
2001 __HAL_ADC_DISABLE_IT(hadc
, ADC_IT_JEOS
);
2002 __HAL_ADC_ENABLE_IT(hadc
, ADC_IT_JEOC
);
2007 /* Start ADC group regular conversion */
2008 LL_ADC_REG_StartConversion(hadc
->Instance
);
2012 /* ADC instance is a multimode slave instance with multimode regular conversions enabled */
2013 SET_BIT(hadc
->State
, HAL_ADC_STATE_MULTIMODE_SLAVE
);
2014 /* if Master ADC JAUTO bit is set, Slave injected interruptions
2015 are enabled nevertheless (for same reason as above) */
2016 tmpADC_Master
= __LL_ADC_MULTI_INSTANCE_MASTER(hadc
->Instance
);
2017 if (READ_BIT(tmpADC_Master
->CFGR
, ADC_CFGR_JAUTO
) != 0UL)
2019 /* First, update Slave State in setting HAL_ADC_STATE_INJ_BUSY bit
2020 and in resetting HAL_ADC_STATE_INJ_EOC bit */
2021 ADC_STATE_CLR_SET(hadc
->State
, HAL_ADC_STATE_INJ_EOC
, HAL_ADC_STATE_INJ_BUSY
);
2022 /* Next, set Slave injected interruptions */
2023 switch (hadc
->Init
.EOCSelection
)
2025 case ADC_EOC_SEQ_CONV
:
2026 __HAL_ADC_DISABLE_IT(hadc
, ADC_IT_JEOC
);
2027 __HAL_ADC_ENABLE_IT(hadc
, ADC_IT_JEOS
);
2029 /* case ADC_EOC_SINGLE_CONV */
2031 __HAL_ADC_DISABLE_IT(hadc
, ADC_IT_JEOS
);
2032 __HAL_ADC_ENABLE_IT(hadc
, ADC_IT_JEOC
);
2040 /* Process unlocked */
2047 tmp_hal_status
= HAL_BUSY
;
2050 /* Return function status */
2051 return tmp_hal_status
;
2055 * @brief Stop ADC conversion of regular group (and injected group in
2056 * case of auto_injection mode), disable interrution of
2057 * end-of-conversion, disable ADC peripheral.
2058 * @param hadc ADC handle
2059 * @retval HAL status.
2061 HAL_StatusTypeDef
HAL_ADC_Stop_IT(ADC_HandleTypeDef
*hadc
)
2063 HAL_StatusTypeDef tmp_hal_status
;
2065 /* Check the parameters */
2066 assert_param(IS_ADC_ALL_INSTANCE(hadc
->Instance
));
2068 /* Process locked */
2071 /* 1. Stop potential conversion on going, on ADC groups regular and injected */
2072 tmp_hal_status
= ADC_ConversionStop(hadc
, ADC_REGULAR_INJECTED_GROUP
);
2074 /* Disable ADC peripheral if conversions are effectively stopped */
2075 if (tmp_hal_status
== HAL_OK
)
2077 /* Disable ADC end of conversion interrupt for regular group */
2078 /* Disable ADC overrun interrupt */
2079 __HAL_ADC_DISABLE_IT(hadc
, (ADC_IT_EOC
| ADC_IT_EOS
| ADC_IT_OVR
));
2081 /* 2. Disable the ADC peripheral */
2082 tmp_hal_status
= ADC_Disable(hadc
);
2084 /* Check if ADC is effectively disabled */
2085 if (tmp_hal_status
== HAL_OK
)
2088 ADC_STATE_CLR_SET(hadc
->State
,
2089 HAL_ADC_STATE_REG_BUSY
| HAL_ADC_STATE_INJ_BUSY
,
2090 HAL_ADC_STATE_READY
);
2094 /* Process unlocked */
2097 /* Return function status */
2098 return tmp_hal_status
;
2102 * @brief Enable ADC, start conversion of regular group and transfer result through DMA.
2103 * @note Interruptions enabled in this function:
2104 * overrun (if applicable), DMA half transfer, DMA transfer complete.
2105 * Each of these interruptions has its dedicated callback function.
2106 * @note Case of multimode enabled (when multimode feature is available): HAL_ADC_Start_DMA()
2107 * is designed for single-ADC mode only. For multimode, the dedicated
2108 * HAL_ADCEx_MultiModeStart_DMA() function must be used.
2109 * @param hadc ADC handle
2110 * @param pData Destination Buffer address.
2111 * @param Length Number of data to be transferred from ADC peripheral to memory
2112 * @retval HAL status.
2114 HAL_StatusTypeDef
HAL_ADC_Start_DMA(ADC_HandleTypeDef
*hadc
, uint32_t *pData
, uint32_t Length
)
2116 HAL_StatusTypeDef tmp_hal_status
;
2117 uint32_t tmp_multimode_config
= LL_ADC_GetMultimode(__LL_ADC_COMMON_INSTANCE(hadc
->Instance
));
2119 /* Check the parameters */
2120 assert_param(IS_ADC_ALL_INSTANCE(hadc
->Instance
));
2122 /* Perform ADC enable and conversion start if no conversion is on going */
2123 if (LL_ADC_REG_IsConversionOngoing(hadc
->Instance
) == 0UL)
2125 /* Process locked */
2128 /* Ensure that multimode regular conversions are not enabled. */
2129 /* Otherwise, dedicated API HAL_ADCEx_MultiModeStart_DMA() must be used. */
2130 if ((tmp_multimode_config
== LL_ADC_MULTI_INDEPENDENT
)
2131 || (tmp_multimode_config
== LL_ADC_MULTI_DUAL_INJ_SIMULT
)
2132 || (tmp_multimode_config
== LL_ADC_MULTI_DUAL_INJ_ALTERN
)
2135 /* Enable the ADC peripheral */
2136 tmp_hal_status
= ADC_Enable(hadc
);
2138 /* Start conversion if ADC is effectively enabled */
2139 if (tmp_hal_status
== HAL_OK
)
2142 /* - Clear state bitfield related to regular group conversion results */
2143 /* - Set state bitfield related to regular operation */
2144 ADC_STATE_CLR_SET(hadc
->State
,
2145 HAL_ADC_STATE_READY
| HAL_ADC_STATE_REG_EOC
| HAL_ADC_STATE_REG_OVR
| HAL_ADC_STATE_REG_EOSMP
,
2146 HAL_ADC_STATE_REG_BUSY
);
2148 /* Reset HAL_ADC_STATE_MULTIMODE_SLAVE bit
2149 - if ADC instance is master or if multimode feature is not available
2150 - if multimode setting is disabled (ADC instance slave in independent mode) */
2151 if ((__LL_ADC_MULTI_INSTANCE_MASTER(hadc
->Instance
) == hadc
->Instance
)
2152 || (tmp_multimode_config
== LL_ADC_MULTI_INDEPENDENT
)
2155 CLEAR_BIT(hadc
->State
, HAL_ADC_STATE_MULTIMODE_SLAVE
);
2158 /* Check if a conversion is on going on ADC group injected */
2159 if ((hadc
->State
& HAL_ADC_STATE_INJ_BUSY
) != 0UL)
2161 /* Reset ADC error code fields related to regular conversions only */
2162 CLEAR_BIT(hadc
->ErrorCode
, (HAL_ADC_ERROR_OVR
| HAL_ADC_ERROR_DMA
));
2166 /* Reset all ADC error code fields */
2167 ADC_CLEAR_ERRORCODE(hadc
);
2170 /* Set the DMA transfer complete callback */
2171 hadc
->DMA_Handle
->XferCpltCallback
= ADC_DMAConvCplt
;
2173 /* Set the DMA half transfer complete callback */
2174 hadc
->DMA_Handle
->XferHalfCpltCallback
= ADC_DMAHalfConvCplt
;
2176 /* Set the DMA error callback */
2177 hadc
->DMA_Handle
->XferErrorCallback
= ADC_DMAError
;
2180 /* Manage ADC and DMA start: ADC overrun interruption, DMA start, */
2181 /* ADC start (in case of SW start): */
2183 /* Clear regular group conversion flag and overrun flag */
2184 /* (To ensure of no unknown state from potential previous ADC */
2186 __HAL_ADC_CLEAR_FLAG(hadc
, (ADC_FLAG_EOC
| ADC_FLAG_EOS
| ADC_FLAG_OVR
));
2188 /* Process unlocked */
2189 /* Unlock before starting ADC conversions: in case of potential */
2190 /* interruption, to let the process to ADC IRQ Handler. */
2193 /* With DMA, overrun event is always considered as an error even if
2194 hadc->Init.Overrun is set to ADC_OVR_DATA_OVERWRITTEN. Therefore,
2195 ADC_IT_OVR is enabled. */
2196 __HAL_ADC_ENABLE_IT(hadc
, ADC_IT_OVR
);
2198 /* Enable ADC DMA mode*/
2199 #if defined(ADC_VER_V5_V90)
2200 if (hadc
->Instance
== ADC3
)
2202 LL_ADC_REG_SetDMATransferMode(hadc
->Instance
, ADC3_CFGR_DMACONTREQ((uint32_t)hadc
->Init
.DMAContinuousRequests
));
2203 LL_ADC_EnableDMAReq(hadc
->Instance
);
2207 LL_ADC_REG_SetDataTransferMode(hadc
->Instance
, ADC_CFGR_DMACONTREQ((uint32_t)hadc
->Init
.ConversionDataManagement
));
2211 LL_ADC_REG_SetDataTransferMode(hadc
->Instance
, (uint32_t)hadc
->Init
.ConversionDataManagement
);
2215 /* Start the DMA channel */
2216 tmp_hal_status
= HAL_DMA_Start_IT(hadc
->DMA_Handle
, (uint32_t)&hadc
->Instance
->DR
, (uint32_t)pData
, Length
);
2218 /* Enable conversion of regular group. */
2219 /* If software start has been selected, conversion starts immediately. */
2220 /* If external trigger has been selected, conversion will start at next */
2221 /* trigger event. */
2222 /* Start ADC group regular conversion */
2223 LL_ADC_REG_StartConversion(hadc
->Instance
);
2227 /* Process unlocked */
2234 tmp_hal_status
= HAL_ERROR
;
2235 /* Process unlocked */
2241 tmp_hal_status
= HAL_BUSY
;
2244 /* Return function status */
2245 return tmp_hal_status
;
2249 * @brief Stop ADC conversion of regular group (and injected group in
2250 * case of auto_injection mode), disable ADC DMA transfer, disable
2252 * @note: ADC peripheral disable is forcing stop of potential
2253 * conversion on ADC group injected. If ADC group injected is under use, it
2254 * should be preliminarily stopped using HAL_ADCEx_InjectedStop function.
2255 * @note Case of multimode enabled (when multimode feature is available):
2256 * HAL_ADC_Stop_DMA() function is dedicated to single-ADC mode only.
2257 * For multimode, the dedicated HAL_ADCEx_MultiModeStop_DMA() API must be used.
2258 * @param hadc ADC handle
2259 * @retval HAL status.
2261 HAL_StatusTypeDef
HAL_ADC_Stop_DMA(ADC_HandleTypeDef
*hadc
)
2263 HAL_StatusTypeDef tmp_hal_status
;
2265 /* Check the parameters */
2266 assert_param(IS_ADC_ALL_INSTANCE(hadc
->Instance
));
2268 /* Process locked */
2271 /* 1. Stop potential ADC group regular conversion on going */
2272 tmp_hal_status
= ADC_ConversionStop(hadc
, ADC_REGULAR_INJECTED_GROUP
);
2274 /* Disable ADC peripheral if conversions are effectively stopped */
2275 if (tmp_hal_status
== HAL_OK
)
2277 /* Disable ADC DMA (ADC DMA configuration of continous requests is kept) */
2278 MODIFY_REG(hadc
->Instance
->CFGR
, ADC_CFGR_DMNGT_0
| ADC_CFGR_DMNGT_1
, 0UL);
2280 /* Disable the DMA channel (in case of DMA in circular mode or stop */
2281 /* while DMA transfer is on going) */
2282 if (hadc
->DMA_Handle
->State
== HAL_DMA_STATE_BUSY
)
2284 tmp_hal_status
= HAL_DMA_Abort(hadc
->DMA_Handle
);
2286 /* Check if DMA channel effectively disabled */
2287 if (tmp_hal_status
!= HAL_OK
)
2289 /* Update ADC state machine to error */
2290 SET_BIT(hadc
->State
, HAL_ADC_STATE_ERROR_DMA
);
2294 /* Disable ADC overrun interrupt */
2295 __HAL_ADC_DISABLE_IT(hadc
, ADC_IT_OVR
);
2297 /* 2. Disable the ADC peripheral */
2298 /* Update "tmp_hal_status" only if DMA channel disabling passed, */
2299 /* to keep in memory a potential failing status. */
2300 if (tmp_hal_status
== HAL_OK
)
2302 tmp_hal_status
= ADC_Disable(hadc
);
2306 (void)ADC_Disable(hadc
);
2309 /* Check if ADC is effectively disabled */
2310 if (tmp_hal_status
== HAL_OK
)
2313 ADC_STATE_CLR_SET(hadc
->State
,
2314 HAL_ADC_STATE_REG_BUSY
| HAL_ADC_STATE_INJ_BUSY
,
2315 HAL_ADC_STATE_READY
);
2320 /* Process unlocked */
2323 /* Return function status */
2324 return tmp_hal_status
;
2328 * @brief Get ADC regular group conversion result.
2329 * @note Reading register DR automatically clears ADC flag EOC
2330 * (ADC group regular end of unitary conversion).
2331 * @note This function does not clear ADC flag EOS
2332 * (ADC group regular end of sequence conversion).
2333 * Occurrence of flag EOS rising:
2334 * - If sequencer is composed of 1 rank, flag EOS is equivalent
2336 * - If sequencer is composed of several ranks, during the scan
2337 * sequence flag EOC only is raised, at the end of the scan sequence
2338 * both flags EOC and EOS are raised.
2339 * To clear this flag, either use function:
2340 * in programming model IT: @ref HAL_ADC_IRQHandler(), in programming
2341 * model polling: @ref HAL_ADC_PollForConversion()
2342 * or @ref __HAL_ADC_CLEAR_FLAG(&hadc, ADC_FLAG_EOS).
2343 * @param hadc ADC handle
2344 * @retval ADC group regular conversion data
2346 uint32_t HAL_ADC_GetValue(ADC_HandleTypeDef
*hadc
)
2348 /* Check the parameters */
2349 assert_param(IS_ADC_ALL_INSTANCE(hadc
->Instance
));
2351 /* Note: EOC flag is not cleared here by software because automatically */
2352 /* cleared by hardware when reading register DR. */
2354 /* Return ADC converted value */
2355 return hadc
->Instance
->DR
;
2359 * @brief Handle ADC interrupt request.
2360 * @param hadc ADC handle
2363 void HAL_ADC_IRQHandler(ADC_HandleTypeDef
*hadc
)
2365 uint32_t overrun_error
= 0UL; /* flag set if overrun occurrence has to be considered as an error */
2366 uint32_t tmp_isr
= hadc
->Instance
->ISR
;
2367 uint32_t tmp_ier
= hadc
->Instance
->IER
;
2368 uint32_t tmp_adc_inj_is_trigger_source_sw_start
;
2369 uint32_t tmp_adc_reg_is_trigger_source_sw_start
;
2371 const ADC_TypeDef
*tmpADC_Master
;
2372 uint32_t tmp_multimode_config
= LL_ADC_GetMultimode(__LL_ADC_COMMON_INSTANCE(hadc
->Instance
));
2374 /* Check the parameters */
2375 assert_param(IS_ADC_ALL_INSTANCE(hadc
->Instance
));
2376 assert_param(IS_ADC_EOC_SELECTION(hadc
->Init
.EOCSelection
));
2378 /* ========== Check End of Sampling flag for ADC group regular ========== */
2379 if (((tmp_isr
& ADC_FLAG_EOSMP
) == ADC_FLAG_EOSMP
) && ((tmp_ier
& ADC_IT_EOSMP
) == ADC_IT_EOSMP
))
2381 /* Update state machine on end of sampling status if not in error state */
2382 if ((hadc
->State
& HAL_ADC_STATE_ERROR_INTERNAL
) == 0UL)
2385 SET_BIT(hadc
->State
, HAL_ADC_STATE_REG_EOSMP
);
2388 /* End Of Sampling callback */
2389 #if (USE_HAL_ADC_REGISTER_CALLBACKS == 1)
2390 hadc
->EndOfSamplingCallback(hadc
);
2392 HAL_ADCEx_EndOfSamplingCallback(hadc
);
2393 #endif /* USE_HAL_ADC_REGISTER_CALLBACKS */
2395 /* Clear regular group conversion flag */
2396 __HAL_ADC_CLEAR_FLAG(hadc
, ADC_FLAG_EOSMP
);
2399 /* ====== Check ADC group regular end of unitary conversion sequence conversions ===== */
2400 if ((((tmp_isr
& ADC_FLAG_EOC
) == ADC_FLAG_EOC
) && ((tmp_ier
& ADC_IT_EOC
) == ADC_IT_EOC
)) ||
2401 (((tmp_isr
& ADC_FLAG_EOS
) == ADC_FLAG_EOS
) && ((tmp_ier
& ADC_IT_EOS
) == ADC_IT_EOS
)))
2403 /* Update state machine on conversion status if not in error state */
2404 if ((hadc
->State
& HAL_ADC_STATE_ERROR_INTERNAL
) == 0UL)
2407 SET_BIT(hadc
->State
, HAL_ADC_STATE_REG_EOC
);
2410 /* Determine whether any further conversion upcoming on group regular */
2411 /* by external trigger, continuous mode or scan sequence on going */
2412 /* to disable interruption. */
2413 if (LL_ADC_REG_IsTriggerSourceSWStart(hadc
->Instance
) != 0UL)
2415 /* Get relevant register CFGR in ADC instance of ADC master or slave */
2416 /* in function of multimode state (for devices with multimode */
2418 if ((__LL_ADC_MULTI_INSTANCE_MASTER(hadc
->Instance
) == hadc
->Instance
)
2419 || (tmp_multimode_config
== LL_ADC_MULTI_INDEPENDENT
)
2420 || (tmp_multimode_config
== LL_ADC_MULTI_DUAL_INJ_SIMULT
)
2421 || (tmp_multimode_config
== LL_ADC_MULTI_DUAL_INJ_ALTERN
)
2424 /* check CONT bit directly in handle ADC CFGR register */
2425 tmp_cfgr
= READ_REG(hadc
->Instance
->CFGR
);
2429 /* else need to check Master ADC CONT bit */
2430 tmpADC_Master
= __LL_ADC_MULTI_INSTANCE_MASTER(hadc
->Instance
);
2431 tmp_cfgr
= READ_REG(tmpADC_Master
->CFGR
);
2434 /* Carry on if continuous mode is disabled */
2435 if (READ_BIT(tmp_cfgr
, ADC_CFGR_CONT
) != ADC_CFGR_CONT
)
2437 /* If End of Sequence is reached, disable interrupts */
2438 if (__HAL_ADC_GET_FLAG(hadc
, ADC_FLAG_EOS
))
2440 /* Allowed to modify bits ADC_IT_EOC/ADC_IT_EOS only if bit */
2441 /* ADSTART==0 (no conversion on going) */
2442 if (LL_ADC_REG_IsConversionOngoing(hadc
->Instance
) == 0UL)
2444 /* Disable ADC end of sequence conversion interrupt */
2445 /* Note: Overrun interrupt was enabled with EOC interrupt in */
2446 /* HAL_Start_IT(), but is not disabled here because can be used */
2447 /* by overrun IRQ process below. */
2448 __HAL_ADC_DISABLE_IT(hadc
, ADC_IT_EOC
| ADC_IT_EOS
);
2451 CLEAR_BIT(hadc
->State
, HAL_ADC_STATE_REG_BUSY
);
2453 if ((hadc
->State
& HAL_ADC_STATE_INJ_BUSY
) == 0UL)
2455 SET_BIT(hadc
->State
, HAL_ADC_STATE_READY
);
2460 /* Change ADC state to error state */
2461 SET_BIT(hadc
->State
, HAL_ADC_STATE_ERROR_INTERNAL
);
2463 /* Set ADC error code to ADC peripheral internal error */
2464 SET_BIT(hadc
->ErrorCode
, HAL_ADC_ERROR_INTERNAL
);
2470 /* Conversion complete callback */
2471 /* Note: Into callback function "HAL_ADC_ConvCpltCallback()", */
2472 /* to determine if conversion has been triggered from EOC or EOS, */
2473 /* possibility to use: */
2474 /* " if( __HAL_ADC_GET_FLAG(&hadc, ADC_FLAG_EOS)) " */
2475 #if (USE_HAL_ADC_REGISTER_CALLBACKS == 1)
2476 hadc
->ConvCpltCallback(hadc
);
2478 HAL_ADC_ConvCpltCallback(hadc
);
2479 #endif /* USE_HAL_ADC_REGISTER_CALLBACKS */
2481 /* Clear regular group conversion flag */
2482 /* Note: in case of overrun set to ADC_OVR_DATA_PRESERVED, end of */
2483 /* conversion flags clear induces the release of the preserved data.*/
2484 /* Therefore, if the preserved data value is needed, it must be */
2485 /* read preliminarily into HAL_ADC_ConvCpltCallback(). */
2486 __HAL_ADC_CLEAR_FLAG(hadc
, (ADC_FLAG_EOC
| ADC_FLAG_EOS
));
2489 /* ====== Check ADC group injected end of unitary conversion sequence conversions ===== */
2490 if ((((tmp_isr
& ADC_FLAG_JEOC
) == ADC_FLAG_JEOC
) && ((tmp_ier
& ADC_IT_JEOC
) == ADC_IT_JEOC
)) ||
2491 (((tmp_isr
& ADC_FLAG_JEOS
) == ADC_FLAG_JEOS
) && ((tmp_ier
& ADC_IT_JEOS
) == ADC_IT_JEOS
)))
2493 /* Update state machine on conversion status if not in error state */
2494 if ((hadc
->State
& HAL_ADC_STATE_ERROR_INTERNAL
) == 0UL)
2497 SET_BIT(hadc
->State
, HAL_ADC_STATE_INJ_EOC
);
2500 /* Retrieve ADC configuration */
2501 tmp_adc_inj_is_trigger_source_sw_start
= LL_ADC_INJ_IsTriggerSourceSWStart(hadc
->Instance
);
2502 tmp_adc_reg_is_trigger_source_sw_start
= LL_ADC_REG_IsTriggerSourceSWStart(hadc
->Instance
);
2503 /* Get relevant register CFGR in ADC instance of ADC master or slave */
2504 /* in function of multimode state (for devices with multimode */
2506 if ((__LL_ADC_MULTI_INSTANCE_MASTER(hadc
->Instance
) == hadc
->Instance
)
2507 || (tmp_multimode_config
== LL_ADC_MULTI_INDEPENDENT
)
2508 || (tmp_multimode_config
== LL_ADC_MULTI_DUAL_REG_SIMULT
)
2509 || (tmp_multimode_config
== LL_ADC_MULTI_DUAL_REG_INTERL
)
2512 tmp_cfgr
= READ_REG(hadc
->Instance
->CFGR
);
2516 tmpADC_Master
= __LL_ADC_MULTI_INSTANCE_MASTER(hadc
->Instance
);
2517 tmp_cfgr
= READ_REG(tmpADC_Master
->CFGR
);
2520 /* Disable interruption if no further conversion upcoming by injected */
2521 /* external trigger or by automatic injected conversion with regular */
2522 /* group having no further conversion upcoming (same conditions as */
2523 /* regular group interruption disabling above), */
2524 /* and if injected scan sequence is completed. */
2525 if ((tmp_adc_inj_is_trigger_source_sw_start
!= 0UL) ||
2526 ((READ_BIT(tmp_cfgr
, ADC_CFGR_JAUTO
) == 0UL) &&
2527 ((tmp_adc_reg_is_trigger_source_sw_start
!= 0UL) &&
2528 (READ_BIT(tmp_cfgr
, ADC_CFGR_CONT
) == 0UL))))
2530 /* If End of Sequence is reached, disable interrupts */
2531 if (__HAL_ADC_GET_FLAG(hadc
, ADC_FLAG_JEOS
))
2533 /* Particular case if injected contexts queue is enabled: */
2534 /* when the last context has been fully processed, JSQR is reset */
2535 /* by the hardware. Even if no injected conversion is planned to come */
2536 /* (queue empty, triggers are ignored), it can start again */
2537 /* immediately after setting a new context (JADSTART is still set). */
2538 /* Therefore, state of HAL ADC injected group is kept to busy. */
2539 if (READ_BIT(tmp_cfgr
, ADC_CFGR_JQM
) == 0UL)
2541 /* Allowed to modify bits ADC_IT_JEOC/ADC_IT_JEOS only if bit */
2542 /* JADSTART==0 (no conversion on going) */
2543 if (LL_ADC_INJ_IsConversionOngoing(hadc
->Instance
) == 0UL)
2545 /* Disable ADC end of sequence conversion interrupt */
2546 __HAL_ADC_DISABLE_IT(hadc
, ADC_IT_JEOC
| ADC_IT_JEOS
);
2549 CLEAR_BIT(hadc
->State
, HAL_ADC_STATE_INJ_BUSY
);
2551 if ((hadc
->State
& HAL_ADC_STATE_REG_BUSY
) == 0UL)
2553 SET_BIT(hadc
->State
, HAL_ADC_STATE_READY
);
2558 /* Update ADC state machine to error */
2559 SET_BIT(hadc
->State
, HAL_ADC_STATE_ERROR_INTERNAL
);
2561 /* Set ADC error code to ADC peripheral internal error */
2562 SET_BIT(hadc
->ErrorCode
, HAL_ADC_ERROR_INTERNAL
);
2568 /* Injected Conversion complete callback */
2569 /* Note: HAL_ADCEx_InjectedConvCpltCallback can resort to
2570 if( __HAL_ADC_GET_FLAG(&hadc, ADC_FLAG_JEOS)) or
2571 if( __HAL_ADC_GET_FLAG(&hadc, ADC_FLAG_JEOC)) to determine whether
2572 interruption has been triggered by end of conversion or end of
2574 #if (USE_HAL_ADC_REGISTER_CALLBACKS == 1)
2575 hadc
->InjectedConvCpltCallback(hadc
);
2577 HAL_ADCEx_InjectedConvCpltCallback(hadc
);
2578 #endif /* USE_HAL_ADC_REGISTER_CALLBACKS */
2580 /* Clear injected group conversion flag */
2581 __HAL_ADC_CLEAR_FLAG(hadc
, ADC_FLAG_JEOC
| ADC_FLAG_JEOS
);
2584 /* ========== Check Analog watchdog 1 flag ========== */
2585 if (((tmp_isr
& ADC_FLAG_AWD1
) == ADC_FLAG_AWD1
) && ((tmp_ier
& ADC_IT_AWD1
) == ADC_IT_AWD1
))
2588 SET_BIT(hadc
->State
, HAL_ADC_STATE_AWD1
);
2590 /* Level out of window 1 callback */
2591 #if (USE_HAL_ADC_REGISTER_CALLBACKS == 1)
2592 hadc
->LevelOutOfWindowCallback(hadc
);
2594 HAL_ADC_LevelOutOfWindowCallback(hadc
);
2595 #endif /* USE_HAL_ADC_REGISTER_CALLBACKS */
2597 /* Clear ADC analog watchdog flag */
2598 __HAL_ADC_CLEAR_FLAG(hadc
, ADC_FLAG_AWD1
);
2601 /* ========== Check analog watchdog 2 flag ========== */
2602 if (((tmp_isr
& ADC_FLAG_AWD2
) == ADC_FLAG_AWD2
) && ((tmp_ier
& ADC_IT_AWD2
) == ADC_IT_AWD2
))
2605 SET_BIT(hadc
->State
, HAL_ADC_STATE_AWD2
);
2607 /* Level out of window 2 callback */
2608 #if (USE_HAL_ADC_REGISTER_CALLBACKS == 1)
2609 hadc
->LevelOutOfWindow2Callback(hadc
);
2611 HAL_ADCEx_LevelOutOfWindow2Callback(hadc
);
2612 #endif /* USE_HAL_ADC_REGISTER_CALLBACKS */
2614 /* Clear ADC analog watchdog flag */
2615 __HAL_ADC_CLEAR_FLAG(hadc
, ADC_FLAG_AWD2
);
2618 /* ========== Check analog watchdog 3 flag ========== */
2619 if (((tmp_isr
& ADC_FLAG_AWD3
) == ADC_FLAG_AWD3
) && ((tmp_ier
& ADC_IT_AWD3
) == ADC_IT_AWD3
))
2622 SET_BIT(hadc
->State
, HAL_ADC_STATE_AWD3
);
2624 /* Level out of window 3 callback */
2625 #if (USE_HAL_ADC_REGISTER_CALLBACKS == 1)
2626 hadc
->LevelOutOfWindow3Callback(hadc
);
2628 HAL_ADCEx_LevelOutOfWindow3Callback(hadc
);
2629 #endif /* USE_HAL_ADC_REGISTER_CALLBACKS */
2631 /* Clear ADC analog watchdog flag */
2632 __HAL_ADC_CLEAR_FLAG(hadc
, ADC_FLAG_AWD3
);
2635 /* ========== Check Overrun flag ========== */
2636 if (((tmp_isr
& ADC_FLAG_OVR
) == ADC_FLAG_OVR
) && ((tmp_ier
& ADC_IT_OVR
) == ADC_IT_OVR
))
2638 /* If overrun is set to overwrite previous data (default setting), */
2639 /* overrun event is not considered as an error. */
2640 /* (cf ref manual "Managing conversions without using the DMA and without */
2642 /* Exception for usage with DMA overrun event always considered as an */
2644 if (hadc
->Init
.Overrun
== ADC_OVR_DATA_PRESERVED
)
2646 overrun_error
= 1UL;
2650 /* Check DMA configuration */
2651 if (tmp_multimode_config
!= LL_ADC_MULTI_INDEPENDENT
)
2653 /* Multimode (when feature is available) is enabled,
2654 Common Control Register MDMA bits must be checked. */
2655 if (LL_ADC_GetMultiDMATransfer(__LL_ADC_COMMON_INSTANCE(hadc
->Instance
)) != LL_ADC_MULTI_REG_DMA_EACH_ADC
)
2657 overrun_error
= 1UL;
2662 /* Multimode not set or feature not available or ADC independent */
2663 if ((hadc
->Instance
->CFGR
& ADC_CFGR_DMNGT
) != 0UL)
2665 overrun_error
= 1UL;
2670 if (overrun_error
== 1UL)
2672 /* Change ADC state to error state */
2673 SET_BIT(hadc
->State
, HAL_ADC_STATE_REG_OVR
);
2675 /* Set ADC error code to overrun */
2676 SET_BIT(hadc
->ErrorCode
, HAL_ADC_ERROR_OVR
);
2678 /* Error callback */
2679 /* Note: In case of overrun, ADC conversion data is preserved until */
2680 /* flag OVR is reset. */
2681 /* Therefore, old ADC conversion data can be retrieved in */
2682 /* function "HAL_ADC_ErrorCallback()". */
2683 #if (USE_HAL_ADC_REGISTER_CALLBACKS == 1)
2684 hadc
->ErrorCallback(hadc
);
2686 HAL_ADC_ErrorCallback(hadc
);
2687 #endif /* USE_HAL_ADC_REGISTER_CALLBACKS */
2690 /* Clear ADC overrun flag */
2691 __HAL_ADC_CLEAR_FLAG(hadc
, ADC_FLAG_OVR
);
2694 /* ========== Check Injected context queue overflow flag ========== */
2695 if (((tmp_isr
& ADC_FLAG_JQOVF
) == ADC_FLAG_JQOVF
) && ((tmp_ier
& ADC_IT_JQOVF
) == ADC_IT_JQOVF
))
2697 /* Change ADC state to overrun state */
2698 SET_BIT(hadc
->State
, HAL_ADC_STATE_INJ_JQOVF
);
2700 /* Set ADC error code to Injected context queue overflow */
2701 SET_BIT(hadc
->ErrorCode
, HAL_ADC_ERROR_JQOVF
);
2703 /* Clear the Injected context queue overflow flag */
2704 __HAL_ADC_CLEAR_FLAG(hadc
, ADC_FLAG_JQOVF
);
2706 /* Injected context queue overflow callback */
2707 #if (USE_HAL_ADC_REGISTER_CALLBACKS == 1)
2708 hadc
->InjectedQueueOverflowCallback(hadc
);
2710 HAL_ADCEx_InjectedQueueOverflowCallback(hadc
);
2711 #endif /* USE_HAL_ADC_REGISTER_CALLBACKS */
2717 * @brief Conversion complete callback in non-blocking mode.
2718 * @param hadc ADC handle
2721 __weak
void HAL_ADC_ConvCpltCallback(ADC_HandleTypeDef
*hadc
)
2723 /* Prevent unused argument(s) compilation warning */
2726 /* NOTE : This function should not be modified. When the callback is needed,
2727 function HAL_ADC_ConvCpltCallback must be implemented in the user file.
2732 * @brief Conversion DMA half-transfer callback in non-blocking mode.
2733 * @param hadc ADC handle
2736 __weak
void HAL_ADC_ConvHalfCpltCallback(ADC_HandleTypeDef
*hadc
)
2738 /* Prevent unused argument(s) compilation warning */
2741 /* NOTE : This function should not be modified. When the callback is needed,
2742 function HAL_ADC_ConvHalfCpltCallback must be implemented in the user file.
2747 * @brief Analog watchdog 1 callback in non-blocking mode.
2748 * @param hadc ADC handle
2751 __weak
void HAL_ADC_LevelOutOfWindowCallback(ADC_HandleTypeDef
*hadc
)
2753 /* Prevent unused argument(s) compilation warning */
2756 /* NOTE : This function should not be modified. When the callback is needed,
2757 function HAL_ADC_LevelOutOfWindowCallback must be implemented in the user file.
2762 * @brief ADC error callback in non-blocking mode
2763 * (ADC conversion with interruption or transfer by DMA).
2764 * @note In case of error due to overrun when using ADC with DMA transfer
2765 * (HAL ADC handle parameter "ErrorCode" to state "HAL_ADC_ERROR_OVR"):
2766 * - Reinitialize the DMA using function "HAL_ADC_Stop_DMA()".
2767 * - If needed, restart a new ADC conversion using function
2768 * "HAL_ADC_Start_DMA()"
2769 * (this function is also clearing overrun flag)
2770 * @param hadc ADC handle
2773 __weak
void HAL_ADC_ErrorCallback(ADC_HandleTypeDef
*hadc
)
2775 /* Prevent unused argument(s) compilation warning */
2778 /* NOTE : This function should not be modified. When the callback is needed,
2779 function HAL_ADC_ErrorCallback must be implemented in the user file.
2787 /** @defgroup ADC_Exported_Functions_Group3 Peripheral Control functions
2788 * @brief Peripheral Control functions
2791 ===============================================================================
2792 ##### Peripheral Control functions #####
2793 ===============================================================================
2794 [..] This section provides functions allowing to:
2795 (+) Configure channels on regular group
2796 (+) Configure the analog watchdog
2803 * @brief Configure a channel to be assigned to ADC group regular.
2804 * @note In case of usage of internal measurement channels:
2805 * Vbat/VrefInt/TempSensor.
2806 * These internal paths can be disabled using function
2808 * @note Possibility to update parameters on the fly:
2809 * This function initializes channel into ADC group regular,
2810 * following calls to this function can be used to reconfigure
2811 * some parameters of structure "ADC_ChannelConfTypeDef" on the fly,
2812 * without resetting the ADC.
2813 * The setting of these parameters is conditioned to ADC state:
2814 * Refer to comments of structure "ADC_ChannelConfTypeDef".
2815 * @param hadc ADC handle
2816 * @param sConfig Structure of ADC channel assigned to ADC group regular.
2817 * @retval HAL status
2819 HAL_StatusTypeDef
HAL_ADC_ConfigChannel(ADC_HandleTypeDef
*hadc
, ADC_ChannelConfTypeDef
*sConfig
)
2821 HAL_StatusTypeDef tmp_hal_status
= HAL_OK
;
2822 uint32_t tmpOffsetShifted
;
2823 uint32_t tmp_config_internal_channel
;
2824 __IO
uint32_t wait_loop_index
= 0;
2825 uint32_t tmp_adc_is_conversion_on_going_regular
;
2826 uint32_t tmp_adc_is_conversion_on_going_injected
;
2828 /* Check the parameters */
2829 assert_param(IS_ADC_ALL_INSTANCE(hadc
->Instance
));
2830 assert_param(IS_ADC_REGULAR_RANK(sConfig
->Rank
));
2831 assert_param(IS_ADC_SAMPLE_TIME(sConfig
->SamplingTime
));
2832 assert_param(IS_ADC_SINGLE_DIFFERENTIAL(sConfig
->SingleDiff
));
2833 assert_param(IS_ADC_OFFSET_NUMBER(sConfig
->OffsetNumber
));
2834 /* Check offset range according to oversampling setting */
2835 if (hadc
->Init
.OversamplingMode
== ENABLE
)
2837 assert_param(IS_ADC_RANGE(ADC_GET_RESOLUTION(hadc
), sConfig
->Offset
/ (hadc
->Init
.Oversampling
.Ratio
+ 1U)));
2841 #if defined(ADC_VER_V5_V90)
2842 if (hadc
->Instance
== ADC3
)
2844 assert_param(IS_ADC3_RANGE(ADC_GET_RESOLUTION(hadc
), sConfig
->Offset
));
2847 #endif /* ADC_VER_V5_V90 */
2849 assert_param(IS_ADC_RANGE(ADC_GET_RESOLUTION(hadc
), sConfig
->Offset
));
2853 /* if ROVSE is set, the value of the OFFSETy_EN bit in ADCx_OFRy register is
2854 ignored (considered as reset) */
2855 assert_param(!((sConfig
->OffsetNumber
!= ADC_OFFSET_NONE
) && (hadc
->Init
.OversamplingMode
== ENABLE
)));
2857 /* Verification of channel number */
2858 if (sConfig
->SingleDiff
!= ADC_DIFFERENTIAL_ENDED
)
2860 assert_param(IS_ADC_CHANNEL(sConfig
->Channel
));
2864 if (hadc
->Instance
== ADC1
)
2866 assert_param(IS_ADC1_DIFF_CHANNEL(sConfig
->Channel
));
2868 if (hadc
->Instance
== ADC2
)
2870 assert_param(IS_ADC2_DIFF_CHANNEL(sConfig
->Channel
));
2873 /* ADC3 is not available on some STM32H7 products */
2874 if (hadc
->Instance
== ADC3
)
2876 assert_param(IS_ADC3_DIFF_CHANNEL(sConfig
->Channel
));
2881 /* Process locked */
2884 /* Parameters update conditioned to ADC state: */
2885 /* Parameters that can be updated when ADC is disabled or enabled without */
2886 /* conversion on going on regular group: */
2887 /* - Channel number */
2888 /* - Channel rank */
2889 if (LL_ADC_REG_IsConversionOngoing(hadc
->Instance
) == 0UL)
2892 #if defined(ADC_VER_V5_V90)
2893 if (hadc
->Instance
!= ADC3
)
2895 /* ADC channels preselection */
2896 hadc
->Instance
->PCSEL_RES0
|= (1UL << (__LL_ADC_CHANNEL_TO_DECIMAL_NB((uint32_t)sConfig
->Channel
) & 0x1FUL
));
2899 /* ADC channels preselection */
2900 hadc
->Instance
->PCSEL
|= (1UL << (__LL_ADC_CHANNEL_TO_DECIMAL_NB((uint32_t)sConfig
->Channel
) & 0x1FUL
));
2901 #endif /* ADC_VER_V5_V90 */
2903 /* Set ADC group regular sequence: channel on the selected scan sequence rank */
2904 LL_ADC_REG_SetSequencerRanks(hadc
->Instance
, sConfig
->Rank
, sConfig
->Channel
);
2906 /* Parameters update conditioned to ADC state: */
2907 /* Parameters that can be updated when ADC is disabled or enabled without */
2908 /* conversion on going on regular group: */
2909 /* - Channel sampling time */
2910 /* - Channel offset */
2911 tmp_adc_is_conversion_on_going_regular
= LL_ADC_REG_IsConversionOngoing(hadc
->Instance
);
2912 tmp_adc_is_conversion_on_going_injected
= LL_ADC_INJ_IsConversionOngoing(hadc
->Instance
);
2913 if ((tmp_adc_is_conversion_on_going_regular
== 0UL)
2914 && (tmp_adc_is_conversion_on_going_injected
== 0UL)
2917 /* Set sampling time of the selected ADC channel */
2918 LL_ADC_SetChannelSamplingTime(hadc
->Instance
, sConfig
->Channel
, sConfig
->SamplingTime
);
2920 /* Configure the offset: offset enable/disable, channel, offset value */
2922 /* Shift the offset with respect to the selected ADC resolution. */
2923 /* Offset has to be left-aligned on bit 11, the LSB (right bits) are set to 0 */
2924 #if defined(ADC_VER_V5_V90)
2925 if (hadc
->Instance
== ADC3
)
2927 tmpOffsetShifted
= ADC3_OFFSET_SHIFT_RESOLUTION(hadc
, (uint32_t)sConfig
->Offset
);
2930 #endif /* ADC_VER_V5_V90 */
2932 tmpOffsetShifted
= ADC_OFFSET_SHIFT_RESOLUTION(hadc
, (uint32_t)sConfig
->Offset
);
2935 if (sConfig
->OffsetNumber
!= ADC_OFFSET_NONE
)
2937 /* Set ADC selected offset number */
2938 LL_ADC_SetOffset(hadc
->Instance
, sConfig
->OffsetNumber
, sConfig
->Channel
, tmpOffsetShifted
);
2940 #if defined(ADC_VER_V5_V90)
2941 if (hadc
->Instance
== ADC3
)
2943 assert_param(IS_ADC3_OFFSET_SIGN(sConfig
->OffsetSign
));
2944 assert_param(IS_FUNCTIONAL_STATE(sConfig
->OffsetSaturation
));
2945 /* Set ADC selected offset sign & saturation */
2946 LL_ADC_SetOffsetSign(hadc
->Instance
, sConfig
->OffsetNumber
, sConfig
->OffsetSign
);
2947 LL_ADC_SetOffsetSaturation(hadc
->Instance
, sConfig
->OffsetNumber
, (sConfig
->OffsetSaturation
== ENABLE
) ? LL_ADC_OFFSET_SATURATION_ENABLE
: LL_ADC_OFFSET_SATURATION_DISABLE
);
2950 #endif /* ADC_VER_V5_V90 */
2952 assert_param(IS_FUNCTIONAL_STATE(sConfig
->OffsetSignedSaturation
));
2953 /* Set ADC selected offset signed saturation */
2954 LL_ADC_SetOffsetSignedSaturation(hadc
->Instance
, sConfig
->OffsetNumber
, (sConfig
->OffsetSignedSaturation
== ENABLE
) ? LL_ADC_OFFSET_SIGNED_SATURATION_ENABLE
: LL_ADC_OFFSET_SIGNED_SATURATION_DISABLE
);
2956 assert_param(IS_FUNCTIONAL_STATE(sConfig
->OffsetRightShift
));
2957 /* Set ADC selected offset right shift */
2958 LL_ADC_SetDataRightShift(hadc
->Instance
, sConfig
->OffsetNumber
, (sConfig
->OffsetRightShift
== ENABLE
) ? LL_ADC_OFFSET_RSHIFT_ENABLE
: LL_ADC_OFFSET_RSHIFT_DISABLE
);
2964 /* Scan OFR1, OFR2, OFR3, OFR4 to check if the selected channel is enabled.
2965 If this is the case, offset OFRx is disabled since
2966 sConfig->OffsetNumber = ADC_OFFSET_NONE. */
2967 #if defined(ADC_VER_V5_V90)
2968 if (hadc
->Instance
== ADC3
)
2970 if (__LL_ADC_CHANNEL_TO_DECIMAL_NB(LL_ADC_GetOffsetChannel(hadc
->Instance
, LL_ADC_OFFSET_1
)) == __LL_ADC_CHANNEL_TO_DECIMAL_NB(sConfig
->Channel
))
2972 LL_ADC_SetOffsetState(hadc
->Instance
, LL_ADC_OFFSET_1
, LL_ADC_OFFSET_DISABLE
);
2974 if (__LL_ADC_CHANNEL_TO_DECIMAL_NB(LL_ADC_GetOffsetChannel(hadc
->Instance
, LL_ADC_OFFSET_2
)) == __LL_ADC_CHANNEL_TO_DECIMAL_NB(sConfig
->Channel
))
2976 LL_ADC_SetOffsetState(hadc
->Instance
, LL_ADC_OFFSET_2
, LL_ADC_OFFSET_DISABLE
);
2978 if (__LL_ADC_CHANNEL_TO_DECIMAL_NB(LL_ADC_GetOffsetChannel(hadc
->Instance
, LL_ADC_OFFSET_3
)) == __LL_ADC_CHANNEL_TO_DECIMAL_NB(sConfig
->Channel
))
2980 LL_ADC_SetOffsetState(hadc
->Instance
, LL_ADC_OFFSET_3
, LL_ADC_OFFSET_DISABLE
);
2982 if (__LL_ADC_CHANNEL_TO_DECIMAL_NB(LL_ADC_GetOffsetChannel(hadc
->Instance
, LL_ADC_OFFSET_4
)) == __LL_ADC_CHANNEL_TO_DECIMAL_NB(sConfig
->Channel
))
2984 LL_ADC_SetOffsetState(hadc
->Instance
, LL_ADC_OFFSET_4
, LL_ADC_OFFSET_DISABLE
);
2988 #endif /* ADC_VER_V5_V90 */
2990 if (((hadc
->Instance
->OFR1
) & ADC_OFR1_OFFSET1_CH
) == ADC_OFR_CHANNEL(sConfig
->Channel
))
2992 CLEAR_BIT(hadc
->Instance
->OFR1
, ADC_OFR1_SSATE
);
2994 if (((hadc
->Instance
->OFR2
) & ADC_OFR2_OFFSET2_CH
) == ADC_OFR_CHANNEL(sConfig
->Channel
))
2996 CLEAR_BIT(hadc
->Instance
->OFR2
, ADC_OFR2_SSATE
);
2998 if (((hadc
->Instance
->OFR3
) & ADC_OFR3_OFFSET3_CH
) == ADC_OFR_CHANNEL(sConfig
->Channel
))
3000 CLEAR_BIT(hadc
->Instance
->OFR3
, ADC_OFR3_SSATE
);
3002 if (((hadc
->Instance
->OFR4
) & ADC_OFR4_OFFSET4_CH
) == ADC_OFR_CHANNEL(sConfig
->Channel
))
3004 CLEAR_BIT(hadc
->Instance
->OFR4
, ADC_OFR4_SSATE
);
3011 /* Parameters update conditioned to ADC state: */
3012 /* Parameters that can be updated only when ADC is disabled: */
3013 /* - Single or differential mode */
3014 /* - Internal measurement channels: Vbat/VrefInt/TempSensor */
3015 if (LL_ADC_IsEnabled(hadc
->Instance
) == 0UL)
3017 /* Set mode single-ended or differential input of the selected ADC channel */
3018 LL_ADC_SetChannelSingleDiff(hadc
->Instance
, sConfig
->Channel
, sConfig
->SingleDiff
);
3020 /* Configuration of differential mode */
3021 if (sConfig
->SingleDiff
== ADC_DIFFERENTIAL_ENDED
)
3023 /* Set sampling time of the selected ADC channel */
3024 /* Note: ADC channel number masked with value "0x1F" to ensure shift value within 32 bits range */
3025 LL_ADC_SetChannelSamplingTime(hadc
->Instance
,
3026 (uint32_t)(__LL_ADC_DECIMAL_NB_TO_CHANNEL((__LL_ADC_CHANNEL_TO_DECIMAL_NB((uint32_t)sConfig
->Channel
) + 1UL) & 0x1FUL
)),
3027 sConfig
->SamplingTime
);
3030 /* Management of internal measurement channels: Vbat/VrefInt/TempSensor. */
3031 /* If internal channel selected, enable dedicated internal buffers and */
3033 /* Note: these internal measurement paths can be disabled using */
3034 /* HAL_ADC_DeInit(). */
3036 if (__LL_ADC_IS_CHANNEL_INTERNAL(sConfig
->Channel
))
3038 /* Configuration of common ADC parameters */
3040 tmp_config_internal_channel
= LL_ADC_GetCommonPathInternalCh(__LL_ADC_COMMON_INSTANCE(hadc
->Instance
));
3042 /* Software is allowed to change common parameters only when all ADCs */
3043 /* of the common group are disabled. */
3044 if (__LL_ADC_IS_ENABLED_ALL_COMMON_INSTANCE(__LL_ADC_COMMON_INSTANCE(hadc
->Instance
)) == 0UL)
3046 /* If the requested internal measurement path has already been enabled, */
3047 /* bypass the configuration processing. */
3048 if ((sConfig
->Channel
== ADC_CHANNEL_TEMPSENSOR
) && ((tmp_config_internal_channel
& LL_ADC_PATH_INTERNAL_TEMPSENSOR
) == 0UL))
3050 if (ADC_TEMPERATURE_SENSOR_INSTANCE(hadc
))
3052 LL_ADC_SetCommonPathInternalCh(__LL_ADC_COMMON_INSTANCE(hadc
->Instance
), LL_ADC_PATH_INTERNAL_TEMPSENSOR
| tmp_config_internal_channel
);
3054 /* Delay for temperature sensor stabilization time */
3055 /* Wait loop initialization and execution */
3056 /* Note: Variable divided by 2 to compensate partially */
3057 /* CPU processing cycles, scaling in us split to not */
3058 /* exceed 32 bits register capacity and handle low frequency. */
3059 wait_loop_index
= ((LL_ADC_DELAY_TEMPSENSOR_STAB_US
/ 10UL) * (SystemCoreClock
/ (100000UL * 2UL)));
3060 while (wait_loop_index
!= 0UL)
3066 else if ((sConfig
->Channel
== ADC_CHANNEL_VBAT
) && ((tmp_config_internal_channel
& LL_ADC_PATH_INTERNAL_VBAT
) == 0UL))
3068 if (ADC_BATTERY_VOLTAGE_INSTANCE(hadc
))
3070 LL_ADC_SetCommonPathInternalCh(__LL_ADC_COMMON_INSTANCE(hadc
->Instance
), LL_ADC_PATH_INTERNAL_VBAT
| tmp_config_internal_channel
);
3073 else if ((sConfig
->Channel
== ADC_CHANNEL_VREFINT
) && ((tmp_config_internal_channel
& LL_ADC_PATH_INTERNAL_VREFINT
) == 0UL))
3075 if (ADC_VREFINT_INSTANCE(hadc
))
3077 LL_ADC_SetCommonPathInternalCh(__LL_ADC_COMMON_INSTANCE(hadc
->Instance
), LL_ADC_PATH_INTERNAL_VREFINT
| tmp_config_internal_channel
);
3085 /* If the requested internal measurement path has already been */
3086 /* enabled and other ADC of the common group are enabled, internal */
3087 /* measurement paths cannot be enabled. */
3090 /* Update ADC state machine to error */
3091 SET_BIT(hadc
->State
, HAL_ADC_STATE_ERROR_CONFIG
);
3093 tmp_hal_status
= HAL_ERROR
;
3099 /* If a conversion is on going on regular group, no update on regular */
3100 /* channel could be done on neither of the channel configuration structure */
3104 /* Update ADC state machine to error */
3105 SET_BIT(hadc
->State
, HAL_ADC_STATE_ERROR_CONFIG
);
3107 tmp_hal_status
= HAL_ERROR
;
3110 /* Process unlocked */
3113 /* Return function status */
3114 return tmp_hal_status
;
3118 * @brief Configure the analog watchdog.
3119 * @note Possibility to update parameters on the fly:
3120 * This function initializes the selected analog watchdog, successive
3121 * calls to this function can be used to reconfigure some parameters
3122 * of structure "ADC_AnalogWDGConfTypeDef" on the fly, without resetting
3124 * The setting of these parameters is conditioned to ADC state.
3125 * For parameters constraints, see comments of structure
3126 * "ADC_AnalogWDGConfTypeDef".
3127 * @note On this STM32 serie, analog watchdog thresholds cannot be modified
3128 * while ADC conversion is on going.
3129 * @param hadc ADC handle
3130 * @param AnalogWDGConfig Structure of ADC analog watchdog configuration
3131 * @retval HAL status
3133 HAL_StatusTypeDef
HAL_ADC_AnalogWDGConfig(ADC_HandleTypeDef
*hadc
, ADC_AnalogWDGConfTypeDef
*AnalogWDGConfig
)
3135 HAL_StatusTypeDef tmp_hal_status
= HAL_OK
;
3136 uint32_t tmpAWDHighThresholdShifted
;
3137 uint32_t tmpAWDLowThresholdShifted
;
3138 uint32_t tmp_adc_is_conversion_on_going_regular
;
3139 uint32_t tmp_adc_is_conversion_on_going_injected
;
3141 /* Check the parameters */
3142 assert_param(IS_ADC_ALL_INSTANCE(hadc
->Instance
));
3143 assert_param(IS_ADC_ANALOG_WATCHDOG_NUMBER(AnalogWDGConfig
->WatchdogNumber
));
3144 assert_param(IS_ADC_ANALOG_WATCHDOG_MODE(AnalogWDGConfig
->WatchdogMode
));
3145 assert_param(IS_FUNCTIONAL_STATE(AnalogWDGConfig
->ITMode
));
3147 if ((AnalogWDGConfig
->WatchdogMode
== ADC_ANALOGWATCHDOG_SINGLE_REG
) ||
3148 (AnalogWDGConfig
->WatchdogMode
== ADC_ANALOGWATCHDOG_SINGLE_INJEC
) ||
3149 (AnalogWDGConfig
->WatchdogMode
== ADC_ANALOGWATCHDOG_SINGLE_REGINJEC
))
3151 assert_param(IS_ADC_CHANNEL(AnalogWDGConfig
->Channel
));
3154 #if defined(ADC_VER_V5_V90)
3156 if (hadc
->Instance
== ADC3
)
3158 /* Verify thresholds range */
3159 if (hadc
->Init
.OversamplingMode
== ENABLE
)
3161 /* Case of oversampling enabled: thresholds are compared to oversampling
3162 intermediate computation (after ratio, before shift application) */
3163 assert_param(IS_ADC3_RANGE(ADC_GET_RESOLUTION(hadc
), AnalogWDGConfig
->HighThreshold
/ (hadc
->Init
.Oversampling
.Ratio
+ 1UL)));
3164 assert_param(IS_ADC3_RANGE(ADC_GET_RESOLUTION(hadc
), AnalogWDGConfig
->LowThreshold
/ (hadc
->Init
.Oversampling
.Ratio
+ 1UL)));
3168 /* Verify if thresholds are within the selected ADC resolution */
3169 assert_param(IS_ADC3_RANGE(ADC_GET_RESOLUTION(hadc
), AnalogWDGConfig
->HighThreshold
));
3170 assert_param(IS_ADC3_RANGE(ADC_GET_RESOLUTION(hadc
), AnalogWDGConfig
->LowThreshold
));
3174 #endif /* ADC_VER_V5_V90 */
3176 /* Verify thresholds range */
3177 if (hadc
->Init
.OversamplingMode
== ENABLE
)
3179 /* Case of oversampling enabled: thresholds are compared to oversampling
3180 intermediate computation (after ratio, before shift application) */
3181 assert_param(IS_ADC_RANGE(ADC_GET_RESOLUTION(hadc
), AnalogWDGConfig
->HighThreshold
/ (hadc
->Init
.Oversampling
.Ratio
+ 1UL)));
3182 assert_param(IS_ADC_RANGE(ADC_GET_RESOLUTION(hadc
), AnalogWDGConfig
->LowThreshold
/ (hadc
->Init
.Oversampling
.Ratio
+ 1UL)));
3186 /* Verify if thresholds are within the selected ADC resolution */
3187 assert_param(IS_ADC_RANGE(ADC_GET_RESOLUTION(hadc
), AnalogWDGConfig
->HighThreshold
));
3188 assert_param(IS_ADC_RANGE(ADC_GET_RESOLUTION(hadc
), AnalogWDGConfig
->LowThreshold
));
3192 /* Process locked */
3195 /* Parameters update conditioned to ADC state: */
3196 /* Parameters that can be updated when ADC is disabled or enabled without */
3197 /* conversion on going on ADC groups regular and injected: */
3198 /* - Analog watchdog channels */
3199 /* - Analog watchdog thresholds */
3200 tmp_adc_is_conversion_on_going_regular
= LL_ADC_REG_IsConversionOngoing(hadc
->Instance
);
3201 tmp_adc_is_conversion_on_going_injected
= LL_ADC_INJ_IsConversionOngoing(hadc
->Instance
);
3202 if ((tmp_adc_is_conversion_on_going_regular
== 0UL)
3203 && (tmp_adc_is_conversion_on_going_injected
== 0UL)
3206 /* Analog watchdog configuration */
3207 if (AnalogWDGConfig
->WatchdogNumber
== ADC_ANALOGWATCHDOG_1
)
3209 /* Configuration of analog watchdog: */
3210 /* - Set the analog watchdog enable mode: one or overall group of */
3211 /* channels, on groups regular and-or injected. */
3212 switch (AnalogWDGConfig
->WatchdogMode
)
3214 case ADC_ANALOGWATCHDOG_SINGLE_REG
:
3215 LL_ADC_SetAnalogWDMonitChannels(hadc
->Instance
, LL_ADC_AWD1
, __LL_ADC_ANALOGWD_CHANNEL_GROUP(AnalogWDGConfig
->Channel
,
3216 LL_ADC_GROUP_REGULAR
));
3219 case ADC_ANALOGWATCHDOG_SINGLE_INJEC
:
3220 LL_ADC_SetAnalogWDMonitChannels(hadc
->Instance
, LL_ADC_AWD1
, __LL_ADC_ANALOGWD_CHANNEL_GROUP(AnalogWDGConfig
->Channel
,
3221 LL_ADC_GROUP_INJECTED
));
3224 case ADC_ANALOGWATCHDOG_SINGLE_REGINJEC
:
3225 LL_ADC_SetAnalogWDMonitChannels(hadc
->Instance
, LL_ADC_AWD1
, __LL_ADC_ANALOGWD_CHANNEL_GROUP(AnalogWDGConfig
->Channel
,
3226 LL_ADC_GROUP_REGULAR_INJECTED
));
3229 case ADC_ANALOGWATCHDOG_ALL_REG
:
3230 LL_ADC_SetAnalogWDMonitChannels(hadc
->Instance
, LL_ADC_AWD1
, LL_ADC_AWD_ALL_CHANNELS_REG
);
3233 case ADC_ANALOGWATCHDOG_ALL_INJEC
:
3234 LL_ADC_SetAnalogWDMonitChannels(hadc
->Instance
, LL_ADC_AWD1
, LL_ADC_AWD_ALL_CHANNELS_INJ
);
3237 case ADC_ANALOGWATCHDOG_ALL_REGINJEC
:
3238 LL_ADC_SetAnalogWDMonitChannels(hadc
->Instance
, LL_ADC_AWD1
, LL_ADC_AWD_ALL_CHANNELS_REG_INJ
);
3241 default: /* ADC_ANALOGWATCHDOG_NONE */
3242 LL_ADC_SetAnalogWDMonitChannels(hadc
->Instance
, LL_ADC_AWD1
, LL_ADC_AWD_DISABLE
);
3246 /* Shift the offset in function of the selected ADC resolution: */
3247 /* Thresholds have to be left-aligned on bit 11, the LSB (right bits) */
3249 tmpAWDHighThresholdShifted
= ADC_AWD1THRESHOLD_SHIFT_RESOLUTION(hadc
, AnalogWDGConfig
->HighThreshold
);
3250 tmpAWDLowThresholdShifted
= ADC_AWD1THRESHOLD_SHIFT_RESOLUTION(hadc
, AnalogWDGConfig
->LowThreshold
);
3252 /* Set the high and low thresholds */
3253 #if defined(ADC_VER_V5_V90)
3254 if (hadc
->Instance
== ADC3
)
3256 MODIFY_REG(hadc
->Instance
->LTR1_TR1
,
3258 AnalogWDGConfig
->FilteringConfig
);
3259 MODIFY_REG(hadc
->Instance
->LTR1_TR1
, ADC3_TR1_LT1
, tmpAWDLowThresholdShifted
);
3260 MODIFY_REG(hadc
->Instance
->LTR1_TR1
, ADC3_TR1_HT1
, (tmpAWDHighThresholdShifted
<< ADC3_TR1_HT1_Pos
));
3265 MODIFY_REG(hadc
->Instance
->LTR1_TR1
, ADC_LTR_LT
, tmpAWDLowThresholdShifted
);
3266 MODIFY_REG(hadc
->Instance
->HTR1_TR2
, ADC_HTR_HT
, tmpAWDHighThresholdShifted
);
3269 MODIFY_REG(hadc
->Instance
->LTR1
, ADC_LTR_LT
, tmpAWDLowThresholdShifted
);
3270 MODIFY_REG(hadc
->Instance
->HTR1
, ADC_HTR_HT
, tmpAWDHighThresholdShifted
);
3273 /* Update state, clear previous result related to AWD1 */
3274 CLEAR_BIT(hadc
->State
, HAL_ADC_STATE_AWD1
);
3276 /* Clear flag ADC analog watchdog */
3277 /* Note: Flag cleared Clear the ADC Analog watchdog flag to be ready */
3278 /* to use for HAL_ADC_IRQHandler() or HAL_ADC_PollForEvent() */
3279 /* (in case left enabled by previous ADC operations). */
3280 LL_ADC_ClearFlag_AWD1(hadc
->Instance
);
3282 /* Configure ADC analog watchdog interrupt */
3283 if (AnalogWDGConfig
->ITMode
== ENABLE
)
3285 LL_ADC_EnableIT_AWD1(hadc
->Instance
);
3289 LL_ADC_DisableIT_AWD1(hadc
->Instance
);
3292 /* Case of ADC_ANALOGWATCHDOG_2 or ADC_ANALOGWATCHDOG_3 */
3295 switch (AnalogWDGConfig
->WatchdogMode
)
3297 case ADC_ANALOGWATCHDOG_SINGLE_REG
:
3298 case ADC_ANALOGWATCHDOG_SINGLE_INJEC
:
3299 case ADC_ANALOGWATCHDOG_SINGLE_REGINJEC
:
3300 /* Update AWD by bitfield to keep the possibility to monitor */
3301 /* several channels by successive calls of this function. */
3302 if (AnalogWDGConfig
->WatchdogNumber
== ADC_ANALOGWATCHDOG_2
)
3304 SET_BIT(hadc
->Instance
->AWD2CR
, (1UL << (__LL_ADC_CHANNEL_TO_DECIMAL_NB(AnalogWDGConfig
->Channel
) & 0x1FUL
)));
3308 SET_BIT(hadc
->Instance
->AWD3CR
, (1UL << (__LL_ADC_CHANNEL_TO_DECIMAL_NB(AnalogWDGConfig
->Channel
) & 0x1FUL
)));
3312 case ADC_ANALOGWATCHDOG_ALL_REG
:
3313 case ADC_ANALOGWATCHDOG_ALL_INJEC
:
3314 case ADC_ANALOGWATCHDOG_ALL_REGINJEC
:
3316 #if defined(ADC_VER_V5_V90)
3317 if (hadc
->Instance
== ADC3
)
3320 LL_ADC_SetAnalogWDMonitChannels(hadc
->Instance
, AnalogWDGConfig
->WatchdogNumber
, LL_ADC_AWD_ALL_CHANNELS_REG_INJ
);
3325 #endif /*ADC_VER_V5_V90*/
3326 /* Update AWD by bitfield to keep the possibility to monitor */
3327 /* several channels by successive calls of this function. */
3328 if (AnalogWDGConfig
->WatchdogNumber
== ADC_ANALOGWATCHDOG_2
)
3330 SET_BIT(hadc
->Instance
->AWD2CR
, (1UL << (__LL_ADC_CHANNEL_TO_DECIMAL_NB(AnalogWDGConfig
->Channel
) & 0x1FUL
)));
3334 SET_BIT(hadc
->Instance
->AWD3CR
, (1UL << (__LL_ADC_CHANNEL_TO_DECIMAL_NB(AnalogWDGConfig
->Channel
) & 0x1FUL
)));
3336 #if defined(ADC_VER_V5_V90)
3338 #endif /*ADC_VER_V5_V90*/
3341 default: /* ADC_ANALOGWATCHDOG_NONE */
3342 LL_ADC_SetAnalogWDMonitChannels(hadc
->Instance
, AnalogWDGConfig
->WatchdogNumber
, LL_ADC_AWD_DISABLE
);
3346 /* Shift the thresholds in function of the selected ADC resolution */
3347 /* have to be left-aligned on bit 15, the LSB (right bits) are set to 0 */
3348 tmpAWDHighThresholdShifted
= ADC_AWD23THRESHOLD_SHIFT_RESOLUTION(hadc
, AnalogWDGConfig
->HighThreshold
);
3349 tmpAWDLowThresholdShifted
= ADC_AWD23THRESHOLD_SHIFT_RESOLUTION(hadc
, AnalogWDGConfig
->LowThreshold
);
3351 #if defined(ADC_VER_V5_V90)
3352 if (hadc
->Instance
== ADC3
)
3355 /* Analog watchdog thresholds configuration */
3356 if (AnalogWDGConfig
->WatchdogNumber
!= ADC_ANALOGWATCHDOG_1
)
3358 /* Shift the offset with respect to the selected ADC resolution: */
3359 /* Thresholds have to be left-aligned on bit 7, the LSB (right bits) */
3361 tmpAWDHighThresholdShifted
= ADC_AWD23THRESHOLD_SHIFT_RESOLUTION(hadc
, AnalogWDGConfig
->HighThreshold
);
3362 tmpAWDLowThresholdShifted
= ADC_AWD23THRESHOLD_SHIFT_RESOLUTION(hadc
, AnalogWDGConfig
->LowThreshold
);
3365 /* Set ADC analog watchdog thresholds value of both thresholds high and low */
3366 LL_ADC_ConfigAnalogWDThresholds(hadc
->Instance
, AnalogWDGConfig
->WatchdogNumber
, tmpAWDHighThresholdShifted
, tmpAWDLowThresholdShifted
);
3373 if (AnalogWDGConfig
->WatchdogNumber
== ADC_ANALOGWATCHDOG_2
)
3375 /* Set ADC analog watchdog thresholds value of both thresholds high and low */
3376 MODIFY_REG(hadc
->Instance
->LTR2_DIFSEL
, ADC_LTR_LT
, tmpAWDLowThresholdShifted
);
3377 MODIFY_REG(hadc
->Instance
->HTR2_CALFACT
, ADC_HTR_HT
, tmpAWDHighThresholdShifted
);
3381 /* Set ADC analog watchdog thresholds value of both thresholds high and low */
3382 MODIFY_REG(hadc
->Instance
->LTR3_RES10
, ADC_LTR_LT
, tmpAWDLowThresholdShifted
);
3383 MODIFY_REG(hadc
->Instance
->HTR3_RES11
, ADC_HTR_HT
, tmpAWDHighThresholdShifted
);
3387 if (AnalogWDGConfig
->WatchdogNumber
== ADC_ANALOGWATCHDOG_2
)
3389 /* Set ADC analog watchdog thresholds value of both thresholds high and low */
3390 MODIFY_REG(hadc
->Instance
->LTR2
, ADC_LTR_LT
, tmpAWDLowThresholdShifted
);
3391 MODIFY_REG(hadc
->Instance
->HTR2
, ADC_HTR_HT
, tmpAWDHighThresholdShifted
);
3395 /* Set ADC analog watchdog thresholds value of both thresholds high and low */
3396 MODIFY_REG(hadc
->Instance
->LTR3
, ADC_LTR_LT
, tmpAWDLowThresholdShifted
);
3397 MODIFY_REG(hadc
->Instance
->HTR3
, ADC_HTR_HT
, tmpAWDHighThresholdShifted
);
3401 if (AnalogWDGConfig
->WatchdogNumber
== ADC_ANALOGWATCHDOG_2
)
3403 /* Update state, clear previous result related to AWD2 */
3404 CLEAR_BIT(hadc
->State
, HAL_ADC_STATE_AWD2
);
3406 /* Clear flag ADC analog watchdog */
3407 /* Note: Flag cleared Clear the ADC Analog watchdog flag to be ready */
3408 /* to use for HAL_ADC_IRQHandler() or HAL_ADC_PollForEvent() */
3409 /* (in case left enabled by previous ADC operations). */
3410 LL_ADC_ClearFlag_AWD2(hadc
->Instance
);
3412 /* Configure ADC analog watchdog interrupt */
3413 if (AnalogWDGConfig
->ITMode
== ENABLE
)
3415 LL_ADC_EnableIT_AWD2(hadc
->Instance
);
3419 LL_ADC_DisableIT_AWD2(hadc
->Instance
);
3422 /* (AnalogWDGConfig->WatchdogNumber == ADC_ANALOGWATCHDOG_3) */
3425 /* Update state, clear previous result related to AWD3 */
3426 CLEAR_BIT(hadc
->State
, HAL_ADC_STATE_AWD3
);
3428 /* Clear flag ADC analog watchdog */
3429 /* Note: Flag cleared Clear the ADC Analog watchdog flag to be ready */
3430 /* to use for HAL_ADC_IRQHandler() or HAL_ADC_PollForEvent() */
3431 /* (in case left enabled by previous ADC operations). */
3432 LL_ADC_ClearFlag_AWD3(hadc
->Instance
);
3434 /* Configure ADC analog watchdog interrupt */
3435 if (AnalogWDGConfig
->ITMode
== ENABLE
)
3437 LL_ADC_EnableIT_AWD3(hadc
->Instance
);
3441 LL_ADC_DisableIT_AWD3(hadc
->Instance
);
3447 /* If a conversion is on going on ADC group regular or injected, no update */
3448 /* could be done on neither of the AWD configuration structure parameters. */
3451 /* Update ADC state machine to error */
3452 SET_BIT(hadc
->State
, HAL_ADC_STATE_ERROR_CONFIG
);
3454 tmp_hal_status
= HAL_ERROR
;
3456 /* Process unlocked */
3459 /* Return function status */
3460 return tmp_hal_status
;
3468 /** @defgroup ADC_Exported_Functions_Group4 Peripheral State functions
3469 * @brief ADC Peripheral State functions
3472 ===============================================================================
3473 ##### Peripheral state and errors functions #####
3474 ===============================================================================
3476 This subsection provides functions to get in run-time the status of the
3478 (+) Check the ADC state
3479 (+) Check the ADC error code
3486 * @brief Return the ADC handle state.
3487 * @note ADC state machine is managed by bitfields, ADC status must be
3488 * compared with states bits.
3490 * " if ((HAL_ADC_GetState(hadc1) & HAL_ADC_STATE_REG_BUSY) != 0UL) "
3491 * " if ((HAL_ADC_GetState(hadc1) & HAL_ADC_STATE_AWD1) != 0UL) "
3492 * @param hadc ADC handle
3493 * @retval ADC handle state (bitfield on 32 bits)
3495 uint32_t HAL_ADC_GetState(ADC_HandleTypeDef
*hadc
)
3497 /* Check the parameters */
3498 assert_param(IS_ADC_ALL_INSTANCE(hadc
->Instance
));
3500 /* Return ADC handle state */
3505 * @brief Return the ADC error code.
3506 * @param hadc ADC handle
3507 * @retval ADC error code (bitfield on 32 bits)
3509 uint32_t HAL_ADC_GetError(ADC_HandleTypeDef
*hadc
)
3511 /* Check the parameters */
3512 assert_param(IS_ADC_ALL_INSTANCE(hadc
->Instance
));
3514 return hadc
->ErrorCode
;
3525 /** @defgroup ADC_Private_Functions ADC Private Functions
3530 * @brief Stop ADC conversion.
3531 * @param hadc ADC handle
3532 * @param ConversionGroup ADC group regular and/or injected.
3533 * This parameter can be one of the following values:
3534 * @arg @ref ADC_REGULAR_GROUP ADC regular conversion type.
3535 * @arg @ref ADC_INJECTED_GROUP ADC injected conversion type.
3536 * @arg @ref ADC_REGULAR_INJECTED_GROUP ADC regular and injected conversion type.
3537 * @retval HAL status.
3539 HAL_StatusTypeDef
ADC_ConversionStop(ADC_HandleTypeDef
*hadc
, uint32_t ConversionGroup
)
3542 uint32_t Conversion_Timeout_CPU_cycles
= 0UL;
3543 uint32_t conversion_group_reassigned
= ConversionGroup
;
3544 uint32_t tmp_ADC_CR_ADSTART_JADSTART
;
3545 uint32_t tmp_adc_is_conversion_on_going_regular
;
3546 uint32_t tmp_adc_is_conversion_on_going_injected
;
3548 /* Check the parameters */
3549 assert_param(IS_ADC_ALL_INSTANCE(hadc
->Instance
));
3550 assert_param(IS_ADC_CONVERSION_GROUP(ConversionGroup
));
3552 /* Verification if ADC is not already stopped (on regular and injected */
3553 /* groups) to bypass this function if not needed. */
3554 tmp_adc_is_conversion_on_going_regular
= LL_ADC_REG_IsConversionOngoing(hadc
->Instance
);
3555 tmp_adc_is_conversion_on_going_injected
= LL_ADC_INJ_IsConversionOngoing(hadc
->Instance
);
3556 if ((tmp_adc_is_conversion_on_going_regular
!= 0UL)
3557 || (tmp_adc_is_conversion_on_going_injected
!= 0UL)
3560 /* Particular case of continuous auto-injection mode combined with */
3561 /* auto-delay mode. */
3562 /* In auto-injection mode, regular group stop ADC_CR_ADSTP is used (not */
3563 /* injected group stop ADC_CR_JADSTP). */
3564 /* Procedure to be followed: Wait until JEOS=1, clear JEOS, set ADSTP=1 */
3565 /* (see reference manual). */
3566 if (((hadc
->Instance
->CFGR
& ADC_CFGR_JAUTO
) != 0UL)
3567 && (hadc
->Init
.ContinuousConvMode
== ENABLE
)
3568 && (hadc
->Init
.LowPowerAutoWait
== ENABLE
)
3571 /* Use stop of regular group */
3572 conversion_group_reassigned
= ADC_REGULAR_GROUP
;
3574 /* Wait until JEOS=1 (maximum Timeout: 4 injected conversions) */
3575 while (__HAL_ADC_GET_FLAG(hadc
, ADC_FLAG_JEOS
) == 0UL)
3577 if (Conversion_Timeout_CPU_cycles
>= (ADC_CONVERSION_TIME_MAX_CPU_CYCLES
* 4UL))
3579 /* Update ADC state machine to error */
3580 SET_BIT(hadc
->State
, HAL_ADC_STATE_ERROR_INTERNAL
);
3582 /* Set ADC error code to ADC peripheral internal error */
3583 SET_BIT(hadc
->ErrorCode
, HAL_ADC_ERROR_INTERNAL
);
3587 Conversion_Timeout_CPU_cycles
++;
3591 __HAL_ADC_CLEAR_FLAG(hadc
, ADC_FLAG_JEOS
);
3594 /* Stop potential conversion on going on ADC group regular */
3595 if (conversion_group_reassigned
!= ADC_INJECTED_GROUP
)
3597 /* Software is allowed to set ADSTP only when ADSTART=1 and ADDIS=0 */
3598 if (LL_ADC_REG_IsConversionOngoing(hadc
->Instance
) != 0UL)
3600 if (LL_ADC_IsDisableOngoing(hadc
->Instance
) == 0UL)
3602 /* Stop ADC group regular conversion */
3603 LL_ADC_REG_StopConversion(hadc
->Instance
);
3608 /* Stop potential conversion on going on ADC group injected */
3609 if (conversion_group_reassigned
!= ADC_REGULAR_GROUP
)
3611 /* Software is allowed to set JADSTP only when JADSTART=1 and ADDIS=0 */
3612 if (LL_ADC_INJ_IsConversionOngoing(hadc
->Instance
) != 0UL)
3614 if (LL_ADC_IsDisableOngoing(hadc
->Instance
) == 0UL)
3616 /* Stop ADC group injected conversion */
3617 LL_ADC_INJ_StopConversion(hadc
->Instance
);
3622 /* Selection of start and stop bits with respect to the regular or injected group */
3623 switch (conversion_group_reassigned
)
3625 case ADC_REGULAR_INJECTED_GROUP
:
3626 tmp_ADC_CR_ADSTART_JADSTART
= (ADC_CR_ADSTART
| ADC_CR_JADSTART
);
3628 case ADC_INJECTED_GROUP
:
3629 tmp_ADC_CR_ADSTART_JADSTART
= ADC_CR_JADSTART
;
3631 /* Case ADC_REGULAR_GROUP only*/
3633 tmp_ADC_CR_ADSTART_JADSTART
= ADC_CR_ADSTART
;
3637 /* Wait for conversion effectively stopped */
3638 tickstart
= HAL_GetTick();
3640 while ((hadc
->Instance
->CR
& tmp_ADC_CR_ADSTART_JADSTART
) != 0UL)
3642 if ((HAL_GetTick() - tickstart
) > ADC_STOP_CONVERSION_TIMEOUT
)
3644 /* Update ADC state machine to error */
3645 SET_BIT(hadc
->State
, HAL_ADC_STATE_ERROR_INTERNAL
);
3647 /* Set ADC error code to ADC peripheral internal error */
3648 SET_BIT(hadc
->ErrorCode
, HAL_ADC_ERROR_INTERNAL
);
3656 /* Return HAL status */
3663 * @brief Enable the selected ADC.
3664 * @note Prerequisite condition to use this function: ADC must be disabled
3665 * and voltage regulator must be enabled (done into HAL_ADC_Init()).
3666 * @param hadc ADC handle
3667 * @retval HAL status.
3669 HAL_StatusTypeDef
ADC_Enable(ADC_HandleTypeDef
*hadc
)
3673 /* ADC enable and wait for ADC ready (in case of ADC is disabled or */
3674 /* enabling phase not yet completed: flag ADC ready not yet set). */
3675 /* Timeout implemented to not be stuck if ADC cannot be enabled (possible */
3676 /* causes: ADC clock not running, ...). */
3677 if (LL_ADC_IsEnabled(hadc
->Instance
) == 0UL)
3679 /* Check if conditions to enable the ADC are fulfilled */
3680 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)
3682 /* Update ADC state machine to error */
3683 SET_BIT(hadc
->State
, HAL_ADC_STATE_ERROR_INTERNAL
);
3685 /* Set ADC error code to ADC peripheral internal error */
3686 SET_BIT(hadc
->ErrorCode
, HAL_ADC_ERROR_INTERNAL
);
3691 /* Enable the ADC peripheral */
3692 LL_ADC_Enable(hadc
->Instance
);
3694 /* Wait for ADC effectively enabled */
3695 tickstart
= HAL_GetTick();
3697 /* Poll for ADC ready flag raised except case of multimode enabled
3698 and ADC slave selected. */
3699 uint32_t tmp_multimode_config
= LL_ADC_GetMultimode(__LL_ADC_COMMON_INSTANCE(hadc
->Instance
));
3700 if ((__LL_ADC_MULTI_INSTANCE_MASTER(hadc
->Instance
) == hadc
->Instance
)
3701 || (tmp_multimode_config
== LL_ADC_MULTI_INDEPENDENT
)
3704 while (__HAL_ADC_GET_FLAG(hadc
, ADC_FLAG_RDY
) == 0UL)
3706 /* If ADEN bit is set less than 4 ADC clock cycles after the ADCAL bit
3707 has been cleared (after a calibration), ADEN bit is reset by the
3709 The workaround is to continue setting ADEN until ADRDY is becomes 1.
3710 Additionally, ADC_ENABLE_TIMEOUT is defined to encompass this
3711 4 ADC clock cycle duration */
3712 /* Note: Test of ADC enabled required due to hardware constraint to */
3713 /* not enable ADC if already enabled. */
3714 if (LL_ADC_IsEnabled(hadc
->Instance
) == 0UL)
3716 LL_ADC_Enable(hadc
->Instance
);
3719 if ((HAL_GetTick() - tickstart
) > ADC_ENABLE_TIMEOUT
)
3721 /* Update ADC state machine to error */
3722 SET_BIT(hadc
->State
, HAL_ADC_STATE_ERROR_INTERNAL
);
3724 /* Set ADC error code to ADC peripheral internal error */
3725 SET_BIT(hadc
->ErrorCode
, HAL_ADC_ERROR_INTERNAL
);
3733 /* Return HAL status */
3738 * @brief Disable the selected ADC.
3739 * @note Prerequisite condition to use this function: ADC conversions must be
3741 * @param hadc ADC handle
3742 * @retval HAL status.
3744 HAL_StatusTypeDef
ADC_Disable(ADC_HandleTypeDef
*hadc
)
3747 const uint32_t tmp_adc_is_disable_on_going
= LL_ADC_IsDisableOngoing(hadc
->Instance
);
3749 /* Verification if ADC is not already disabled: */
3750 /* Note: forbidden to disable ADC (set bit ADC_CR_ADDIS) if ADC is already */
3752 if ((LL_ADC_IsEnabled(hadc
->Instance
) != 0UL)
3753 && (tmp_adc_is_disable_on_going
== 0UL)
3756 /* Check if conditions to disable the ADC are fulfilled */
3757 if ((hadc
->Instance
->CR
& (ADC_CR_JADSTART
| ADC_CR_ADSTART
| ADC_CR_ADEN
)) == ADC_CR_ADEN
)
3759 /* Disable the ADC peripheral */
3760 LL_ADC_Disable(hadc
->Instance
);
3761 __HAL_ADC_CLEAR_FLAG(hadc
, (ADC_FLAG_EOSMP
| ADC_FLAG_RDY
));
3765 /* Update ADC state machine to error */
3766 SET_BIT(hadc
->State
, HAL_ADC_STATE_ERROR_INTERNAL
);
3768 /* Set ADC error code to ADC peripheral internal error */
3769 SET_BIT(hadc
->ErrorCode
, HAL_ADC_ERROR_INTERNAL
);
3774 /* Wait for ADC effectively disabled */
3775 /* Get tick count */
3776 tickstart
= HAL_GetTick();
3778 while ((hadc
->Instance
->CR
& ADC_CR_ADEN
) != 0UL)
3780 if ((HAL_GetTick() - tickstart
) > ADC_DISABLE_TIMEOUT
)
3782 /* Update ADC state machine to error */
3783 SET_BIT(hadc
->State
, HAL_ADC_STATE_ERROR_INTERNAL
);
3785 /* Set ADC error code to ADC peripheral internal error */
3786 SET_BIT(hadc
->ErrorCode
, HAL_ADC_ERROR_INTERNAL
);
3793 /* Return HAL status */
3798 * @brief DMA transfer complete callback.
3799 * @param hdma pointer to DMA handle.
3802 void ADC_DMAConvCplt(DMA_HandleTypeDef
*hdma
)
3804 /* Retrieve ADC handle corresponding to current DMA handle */
3805 ADC_HandleTypeDef
*hadc
= (ADC_HandleTypeDef
*)((DMA_HandleTypeDef
*)hdma
)->Parent
;
3807 /* Update state machine on conversion status if not in error state */
3808 if ((hadc
->State
& (HAL_ADC_STATE_ERROR_INTERNAL
| HAL_ADC_STATE_ERROR_DMA
)) == 0UL)
3811 SET_BIT(hadc
->State
, HAL_ADC_STATE_REG_EOC
);
3813 /* Determine whether any further conversion upcoming on group regular */
3814 /* by external trigger, continuous mode or scan sequence on going */
3815 /* to disable interruption. */
3816 /* Is it the end of the regular sequence ? */
3817 if ((hadc
->Instance
->ISR
& ADC_FLAG_EOS
) != 0UL)
3819 /* Are conversions software-triggered ? */
3820 if (LL_ADC_REG_IsTriggerSourceSWStart(hadc
->Instance
) != 0UL)
3822 /* Is CONT bit set ? */
3823 if (READ_BIT(hadc
->Instance
->CFGR
, ADC_CFGR_CONT
) == 0UL)
3825 /* CONT bit is not set, no more conversions expected */
3826 CLEAR_BIT(hadc
->State
, HAL_ADC_STATE_REG_BUSY
);
3827 if ((hadc
->State
& HAL_ADC_STATE_INJ_BUSY
) == 0UL)
3829 SET_BIT(hadc
->State
, HAL_ADC_STATE_READY
);
3836 /* DMA End of Transfer interrupt was triggered but conversions sequence
3837 is not over. If DMACFG is set to 0, conversions are stopped. */
3838 if (READ_BIT(hadc
->Instance
->CFGR
, ADC_CFGR_DMNGT
) == 0UL)
3840 /* DMACFG bit is not set, conversions are stopped. */
3841 CLEAR_BIT(hadc
->State
, HAL_ADC_STATE_REG_BUSY
);
3842 if ((hadc
->State
& HAL_ADC_STATE_INJ_BUSY
) == 0UL)
3844 SET_BIT(hadc
->State
, HAL_ADC_STATE_READY
);
3849 /* Conversion complete callback */
3850 #if (USE_HAL_ADC_REGISTER_CALLBACKS == 1)
3851 hadc
->ConvCpltCallback(hadc
);
3853 HAL_ADC_ConvCpltCallback(hadc
);
3854 #endif /* USE_HAL_ADC_REGISTER_CALLBACKS */
3856 else /* DMA and-or internal error occurred */
3858 if ((hadc
->State
& HAL_ADC_STATE_ERROR_INTERNAL
) != 0UL)
3860 /* Call HAL ADC Error Callback function */
3861 #if (USE_HAL_ADC_REGISTER_CALLBACKS == 1)
3862 hadc
->ErrorCallback(hadc
);
3864 HAL_ADC_ErrorCallback(hadc
);
3865 #endif /* USE_HAL_ADC_REGISTER_CALLBACKS */
3869 /* Call ADC DMA error callback */
3870 hadc
->DMA_Handle
->XferErrorCallback(hdma
);
3876 * @brief DMA half transfer complete callback.
3877 * @param hdma pointer to DMA handle.
3880 void ADC_DMAHalfConvCplt(DMA_HandleTypeDef
*hdma
)
3882 /* Retrieve ADC handle corresponding to current DMA handle */
3883 ADC_HandleTypeDef
*hadc
= (ADC_HandleTypeDef
*)((DMA_HandleTypeDef
*)hdma
)->Parent
;
3885 /* Half conversion callback */
3886 #if (USE_HAL_ADC_REGISTER_CALLBACKS == 1)
3887 hadc
->ConvHalfCpltCallback(hadc
);
3889 HAL_ADC_ConvHalfCpltCallback(hadc
);
3890 #endif /* USE_HAL_ADC_REGISTER_CALLBACKS */
3894 * @brief DMA error callback.
3895 * @param hdma pointer to DMA handle.
3898 void ADC_DMAError(DMA_HandleTypeDef
*hdma
)
3900 /* Retrieve ADC handle corresponding to current DMA handle */
3901 ADC_HandleTypeDef
*hadc
= (ADC_HandleTypeDef
*)((DMA_HandleTypeDef
*)hdma
)->Parent
;
3904 SET_BIT(hadc
->State
, HAL_ADC_STATE_ERROR_DMA
);
3906 /* Set ADC error code to DMA error */
3907 SET_BIT(hadc
->ErrorCode
, HAL_ADC_ERROR_DMA
);
3909 /* Error callback */
3910 #if (USE_HAL_ADC_REGISTER_CALLBACKS == 1)
3911 hadc
->ErrorCallback(hadc
);
3913 HAL_ADC_ErrorCallback(hadc
);
3914 #endif /* USE_HAL_ADC_REGISTER_CALLBACKS */
3918 * @brief Configure boost mode of selected ADC.
3919 * @note Prerequisite condition to use this function: ADC conversions must be
3921 * @param hadc ADC handle
3924 void ADC_ConfigureBoostMode(ADC_HandleTypeDef
*hadc
)
3927 if (ADC_IS_SYNCHRONOUS_CLOCK_MODE(hadc
))
3929 freq
= HAL_RCC_GetHCLKFreq();
3930 switch (hadc
->Init
.ClockPrescaler
)
3932 case ADC_CLOCK_SYNC_PCLK_DIV1
:
3933 case ADC_CLOCK_SYNC_PCLK_DIV2
:
3934 freq
/= (hadc
->Init
.ClockPrescaler
>> ADC_CCR_CKMODE_Pos
);
3936 case ADC_CLOCK_SYNC_PCLK_DIV4
:
3945 freq
= HAL_RCCEx_GetPeriphCLKFreq(RCC_PERIPHCLK_ADC
);
3946 switch (hadc
->Init
.ClockPrescaler
)
3948 case ADC_CLOCK_ASYNC_DIV2
:
3949 case ADC_CLOCK_ASYNC_DIV4
:
3950 case ADC_CLOCK_ASYNC_DIV6
:
3951 case ADC_CLOCK_ASYNC_DIV8
:
3952 case ADC_CLOCK_ASYNC_DIV10
:
3953 case ADC_CLOCK_ASYNC_DIV12
:
3954 freq
/= ((hadc
->Init
.ClockPrescaler
>> ADC_CCR_PRESC_Pos
) << 1UL);
3956 case ADC_CLOCK_ASYNC_DIV16
:
3959 case ADC_CLOCK_ASYNC_DIV32
:
3962 case ADC_CLOCK_ASYNC_DIV64
:
3965 case ADC_CLOCK_ASYNC_DIV128
:
3968 case ADC_CLOCK_ASYNC_DIV256
:
3976 #if defined(ADC_VER_V5_3) || defined(ADC_VER_V5_V90)
3978 if (freq
<= 6250000UL)
3980 MODIFY_REG(hadc
->Instance
->CR
, ADC_CR_BOOST
, 0UL);
3982 else if (freq
<= 12500000UL)
3984 MODIFY_REG(hadc
->Instance
->CR
, ADC_CR_BOOST
, ADC_CR_BOOST_0
);
3986 else if (freq
<= 25000000UL)
3988 MODIFY_REG(hadc
->Instance
->CR
, ADC_CR_BOOST
, ADC_CR_BOOST_1
);
3990 else /* if(freq > 25000000UL) */
3992 MODIFY_REG(hadc
->Instance
->CR
, ADC_CR_BOOST
, ADC_CR_BOOST_1
| ADC_CR_BOOST_0
);
3995 if (HAL_GetREVID() <= REV_ID_Y
) /* STM32H7 silicon Rev.Y */
3997 if (freq
> 20000000UL)
3999 SET_BIT(hadc
->Instance
->CR
, ADC_CR_BOOST_0
);
4003 CLEAR_BIT(hadc
->Instance
->CR
, ADC_CR_BOOST_0
);
4006 else /* STM32H7 silicon Rev.V */
4008 freq
/= 2U; /* divider by 2 for Rev.V */
4010 if (freq
<= 6250000UL)
4012 MODIFY_REG(hadc
->Instance
->CR
, ADC_CR_BOOST
, 0UL);
4014 else if (freq
<= 12500000UL)
4016 MODIFY_REG(hadc
->Instance
->CR
, ADC_CR_BOOST
, ADC_CR_BOOST_0
);
4018 else if (freq
<= 25000000UL)
4020 MODIFY_REG(hadc
->Instance
->CR
, ADC_CR_BOOST
, ADC_CR_BOOST_1
);
4022 else /* if(freq > 25000000UL) */
4024 MODIFY_REG(hadc
->Instance
->CR
, ADC_CR_BOOST
, ADC_CR_BOOST_1
| ADC_CR_BOOST_0
);
4027 #endif /* ADC_VER_V5_3 */
4034 #endif /* HAL_ADC_MODULE_ENABLED */
4043 /************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/