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.
29 (+) Interrupt generation at the end of regular conversion and in case of
30 analog watchdog or overrun events.
32 (+) Single and continuous conversion modes.
34 (+) Scan mode for conversion of several channels sequentially.
36 (+) Data alignment with in-built data coherency.
38 (+) Programmable sampling time (channel wise)
40 (+) External trigger (timer or EXTI) with configurable polarity
42 (+) DMA request generation for transfer of conversions data of regular group.
44 (+) Configurable delay between conversions in Dual interleaved mode.
46 (+) ADC channels selectable single/differential input.
48 (+) ADC offset shared on 4 offset instances.
51 (+) ADC conversion of regular group.
53 (+) ADC supply requirements: 1.62 V to 3.6 V.
55 (+) ADC input range: from Vref- (connected to Vssa) to Vref+ (connected to
56 Vdda or to an external voltage reference).
59 ##### How to use this driver #####
60 ==============================================================================
63 *** Configuration of top level parameters related to ADC ***
64 ============================================================
67 (#) Enable the ADC interface
68 (++) As prerequisite, ADC clock must be configured at RCC top level.
70 (++) Two clock settings are mandatory:
71 (+++) ADC clock (core clock, also possibly conversion clock).
73 (+++) ADC clock (conversions clock).
74 Two possible clock sources: synchronous clock derived from AHB clock
75 or asynchronous clock derived from system clock, the PLL2 or the PLL3 running up to 400MHz.
78 Into HAL_ADC_MspInit() (recommended code location) or with
79 other device clock parameters configuration:
80 (+++) __HAL_RCC_ADC_CLK_ENABLE(); (mandatory)
82 RCC_ADCCLKSOURCE_PLL2 enable: (optional: if asynchronous clock selected)
83 (+++) RCC_PeriphClkInitTypeDef RCC_PeriphClkInit;
84 (+++) PeriphClkInit.PeriphClockSelection = RCC_PERIPHCLK_ADC;
85 (+++) PeriphClkInit.AdcClockSelection = RCC_ADCCLKSOURCE_PLL2;
86 (+++) HAL_RCCEx_PeriphCLKConfig(&PeriphClkInit);
88 (++) ADC clock source and clock prescaler are configured at ADC level with
89 parameter "ClockPrescaler" using function HAL_ADC_Init().
91 (#) ADC pins configuration
92 (++) Enable the clock for the ADC GPIOs
93 using macro __HAL_RCC_GPIOx_CLK_ENABLE()
94 (++) Configure these ADC pins in analog mode
95 using function HAL_GPIO_Init()
97 (#) Optionally, in case of usage of ADC with interruptions:
98 (++) Configure the NVIC for ADC
99 using function HAL_NVIC_EnableIRQ(ADCx_IRQn)
100 (++) Insert the ADC interruption handler function HAL_ADC_IRQHandler()
101 into the function of corresponding ADC interruption vector
104 (#) Optionally, in case of usage of DMA:
105 (++) Configure the DMA (DMA channel, mode normal or circular, ...)
106 using function HAL_DMA_Init().
107 (++) Configure the NVIC for DMA
108 using function HAL_NVIC_EnableIRQ(DMAx_Channelx_IRQn)
109 (++) Insert the ADC interruption handler function HAL_ADC_IRQHandler()
110 into the function of corresponding DMA interruption vector
111 DMAx_Channelx_IRQHandler().
113 *** Configuration of ADC, group regular, channels parameters ***
114 ================================================================
117 (#) Configure the ADC parameters (resolution, data alignment, ...)
118 and regular group parameters (conversion trigger, sequencer, ...)
119 using function HAL_ADC_Init().
121 (#) Configure the channels for regular group parameters (channel number,
122 channel rank into sequencer, ..., into regular group)
123 using function HAL_ADC_ConfigChannel().
125 (#) Optionally, configure the analog watchdog parameters (channels
126 monitored, thresholds, ...)
127 using function HAL_ADC_AnalogWDGConfig().
129 *** Execution of ADC conversions ***
130 ====================================
133 (#) Optionally, perform an automatic ADC calibration to improve the
135 using function HAL_ADCEx_Calibration_Start().
137 (#) ADC driver can be used among three modes: polling, interruption,
140 (++) ADC conversion by polling:
141 (+++) Activate the ADC peripheral and start conversions
142 using function HAL_ADC_Start()
143 (+++) Wait for ADC conversion completion
144 using function HAL_ADC_PollForConversion()
145 (+++) Retrieve conversion results
146 using function HAL_ADC_GetValue()
147 (+++) Stop conversion and disable the ADC peripheral
148 using function HAL_ADC_Stop()
150 (++) ADC conversion by interruption:
151 (+++) Activate the ADC peripheral and start conversions
152 using function HAL_ADC_Start_IT()
153 (+++) Wait for ADC conversion completion by call of function
154 HAL_ADC_ConvCpltCallback()
155 (this function must be implemented in user program)
156 (+++) Retrieve conversion results
157 using function HAL_ADC_GetValue()
158 (+++) Stop conversion and disable the ADC peripheral
159 using function HAL_ADC_Stop_IT()
161 (++) ADC conversion with transfer by DMA:
162 (+++) Activate the ADC peripheral and start conversions
163 using function HAL_ADC_Start_DMA()
164 (+++) Wait for ADC conversion completion by call of function
165 HAL_ADC_ConvCpltCallback() or HAL_ADC_ConvHalfCpltCallback()
166 (these functions must be implemented in user program)
167 (+++) Conversion results are automatically transferred by DMA into
168 destination variable address.
169 (+++) Stop conversion and disable the ADC peripheral
170 using function HAL_ADC_Stop_DMA()
174 (@) Callback functions must be implemented in user program:
175 (+@) HAL_ADC_ErrorCallback()
176 (+@) HAL_ADC_LevelOutOfWindowCallback() (callback of analog watchdog)
177 (+@) HAL_ADC_ConvCpltCallback()
178 (+@) HAL_ADC_ConvHalfCpltCallback
180 *** Deinitialization of ADC ***
181 ============================================================
184 (#) Disable the ADC interface
185 (++) ADC clock can be hard reset and disabled at RCC top level.
186 (++) Hard reset of ADC peripherals
187 using macro __HAL_RCC_ADCx_FORCE_RESET(), __HAL_RCC_ADCx_RELEASE_RESET().
188 (++) ADC clock disable
189 using the equivalent macro/functions as configuration step.
191 Into HAL_ADC_MspDeInit() (recommended code location) or with
192 other device clock parameters configuration:
193 (+++) __HAL_RCC_ADC_CLK_DISABLE(); (if not used anymore)
194 RCC_ADCCLKSOURCE_CLKP restore: (optional)
195 (+++) RCC_PeriphClkInitTypeDef RCC_PeriphClkInit;
196 (+++) PeriphClkInit.PeriphClockSelection = RCC_PERIPHCLK_ADC;
197 (+++) PeriphClkInit.AdcClockSelection = RCC_ADCCLKSOURCE_CLKP;
198 (+++) HAL_RCCEx_PeriphCLKConfig(&PeriphClkInit);
200 (#) ADC pins configuration
201 (++) Disable the clock for the ADC GPIOs
202 using macro __HAL_RCC_GPIOx_CLK_DISABLE()
204 (#) Optionally, in case of usage of ADC with interruptions:
205 (++) Disable the NVIC for ADC
206 using function HAL_NVIC_EnableIRQ(ADCx_IRQn)
208 (#) Optionally, in case of usage of DMA:
209 (++) Deinitialize the DMA
210 using function HAL_DMA_Init().
211 (++) Disable the NVIC for DMA
212 using function HAL_NVIC_EnableIRQ(DMAx_Channelx_IRQn)
216 *** Callback registration ***
217 =============================================
220 The compilation flag USE_HAL_ADC_REGISTER_CALLBACKS, when set to 1,
221 allows the user to configure dynamically the driver callbacks.
222 Use Functions @ref HAL_ADC_RegisterCallback()
223 to register an interrupt callback.
226 Function @ref HAL_ADC_RegisterCallback() allows to register following callbacks:
227 (+) ConvCpltCallback : ADC conversion complete callback
228 (+) ConvHalfCpltCallback : ADC conversion DMA half-transfer callback
229 (+) LevelOutOfWindowCallback : ADC analog watchdog 1 callback
230 (+) ErrorCallback : ADC error callback
231 (+) InjectedConvCpltCallback : ADC group injected conversion complete callback
232 (+) InjectedQueueOverflowCallback : ADC group injected context queue overflow callback
233 (+) LevelOutOfWindow2Callback : ADC analog watchdog 2 callback
234 (+) LevelOutOfWindow3Callback : ADC analog watchdog 3 callback
235 (+) EndOfSamplingCallback : ADC end of sampling callback
236 (+) MspInitCallback : ADC Msp Init callback
237 (+) MspDeInitCallback : ADC Msp DeInit callback
238 This function takes as parameters the HAL peripheral handle, the Callback ID
239 and a pointer to the user callback function.
242 Use function @ref HAL_ADC_UnRegisterCallback to reset a callback to the default
246 @ref HAL_ADC_UnRegisterCallback takes as parameters the HAL peripheral handle,
248 This function allows to reset following callbacks:
249 (+) ConvCpltCallback : ADC conversion complete callback
250 (+) ConvHalfCpltCallback : ADC conversion DMA half-transfer callback
251 (+) LevelOutOfWindowCallback : ADC analog watchdog 1 callback
252 (+) ErrorCallback : ADC error callback
253 (+) InjectedConvCpltCallback : ADC group injected conversion complete callback
254 (+) InjectedQueueOverflowCallback : ADC group injected context queue overflow callback
255 (+) LevelOutOfWindow2Callback : ADC analog watchdog 2 callback
256 (+) LevelOutOfWindow3Callback : ADC analog watchdog 3 callback
257 (+) EndOfSamplingCallback : ADC end of sampling callback
258 (+) MspInitCallback : ADC Msp Init callback
259 (+) MspDeInitCallback : ADC Msp DeInit callback
262 By default, after the @ref HAL_ADC_Init() and when the state is @ref HAL_ADC_STATE_RESET
263 all callbacks are set to the corresponding weak functions:
264 examples @ref HAL_ADC_ConvCpltCallback(), @ref HAL_ADC_ErrorCallback().
265 Exception done for MspInit and MspDeInit functions that are
266 reset to the legacy weak functions in the @ref HAL_ADC_Init()/ @ref HAL_ADC_DeInit() only when
267 these callbacks are null (not registered beforehand).
270 If MspInit or MspDeInit are not null, the @ref HAL_ADC_Init()/ @ref HAL_ADC_DeInit()
271 keep and use the user MspInit/MspDeInit callbacks (registered beforehand) whatever the state.
274 Callbacks can be registered/unregistered in @ref HAL_ADC_STATE_READY state only.
275 Exception done MspInit/MspDeInit functions that can be registered/unregistered
276 in @ref HAL_ADC_STATE_READY or @ref HAL_ADC_STATE_RESET state,
277 thus registered (user) MspInit/DeInit callbacks can be used during the Init/DeInit.
280 Then, the user first registers the MspInit/MspDeInit user callbacks
281 using @ref HAL_ADC_RegisterCallback() before calling @ref HAL_ADC_DeInit()
282 or @ref HAL_ADC_Init() function.
285 When the compilation flag USE_HAL_ADC_REGISTER_CALLBACKS is set to 0 or
286 not defined, the callback registration feature is not available and all callbacks
287 are set to the corresponding weak functions.
290 ******************************************************************************
293 * <h2><center>© Copyright (c) 2017 STMicroelectronics.
294 * All rights reserved.</center></h2>
296 * This software component is licensed by ST under BSD 3-Clause license,
297 * the "License"; You may not use this file except in compliance with the
298 * License. You may obtain a copy of the License at:
299 * opensource.org/licenses/BSD-3-Clause
301 ******************************************************************************
304 /* Includes ------------------------------------------------------------------*/
305 #include "stm32h7xx_hal.h"
307 /** @addtogroup STM32H7xx_HAL_Driver
311 /** @defgroup ADC ADC
312 * @brief ADC HAL module driver
316 #ifdef HAL_ADC_MODULE_ENABLED
318 /* Private typedef -----------------------------------------------------------*/
319 /* Private define ------------------------------------------------------------*/
321 /** @defgroup ADC_Private_Constants ADC Private Constants
324 #define ADC_CFGR_FIELDS_1 ((uint32_t)(ADC_CFGR_RES |\
325 ADC_CFGR_CONT | ADC_CFGR_OVRMOD |\
326 ADC_CFGR_DISCEN | ADC_CFGR_DISCNUM |\
327 ADC_CFGR_EXTEN | ADC_CFGR_EXTSEL)) /*!< ADC_CFGR fields of parameters that can be updated
328 when no regular conversion is on-going */
330 #define ADC_CFGR2_FIELDS ((uint32_t)(ADC_CFGR2_ROVSE | ADC_CFGR2_OVSR |\
331 ADC_CFGR2_OVSS | ADC_CFGR2_TROVS |\
332 ADC_CFGR2_ROVSM)) /*!< ADC_CFGR2 fields of parameters that can be updated when no conversion
333 (neither regular nor injected) is on-going */
335 /* Timeout values for ADC operations (enable settling time, */
336 /* disable settling time, ...). */
337 /* Values defined to be higher than worst cases: low clock frequency, */
338 /* maximum prescalers. */
339 #define ADC_ENABLE_TIMEOUT (2UL) /*!< ADC enable time-out value */
340 #define ADC_DISABLE_TIMEOUT (2UL) /*!< ADC disable time-out value */
342 /* Timeout to wait for current conversion on going to be completed. */
343 /* Timeout fixed to worst case, for 1 channel. */
344 /* - maximum sampling time (830.5 adc_clk) */
345 /* - ADC resolution (Tsar 16 bits= 16.5 adc_clk) */
346 /* - ADC clock with prescaler 256 */
347 /* 823 * 256 = 210688 clock cycles max */
348 /* Unit: cycles of CPU clock. */
349 #define ADC_CONVERSION_TIME_MAX_CPU_CYCLES ((uint32_t) 210688) /*!< ADC conversion completion time-out value */
355 /* Private macro -------------------------------------------------------------*/
356 /* Private variables ---------------------------------------------------------*/
357 /* Private function prototypes -----------------------------------------------*/
358 /* Exported functions --------------------------------------------------------*/
360 /** @defgroup ADC_Exported_Functions ADC Exported Functions
364 /** @defgroup ADC_Exported_Functions_Group1 Initialization and de-initialization functions
365 * @brief ADC Initialization and Configuration functions
368 ===============================================================================
369 ##### Initialization and de-initialization functions #####
370 ===============================================================================
371 [..] This section provides functions allowing to:
372 (+) Initialize and configure the ADC.
373 (+) De-initialize the ADC.
379 * @brief Initialize the ADC peripheral and regular group according to
380 * parameters specified in structure "ADC_InitTypeDef".
381 * @note As prerequisite, ADC clock must be configured at RCC top level
382 * (refer to description of RCC configuration for ADC
383 * in header of this file).
384 * @note Possibility to update parameters on the fly:
385 * This function initializes the ADC MSP (HAL_ADC_MspInit()) only when
386 * coming from ADC state reset. Following calls to this function can
387 * be used to reconfigure some parameters of ADC_InitTypeDef
388 * structure on the fly, without modifying MSP configuration. If ADC
389 * MSP has to be modified again, HAL_ADC_DeInit() must be called
390 * before HAL_ADC_Init().
391 * The setting of these parameters is conditioned to ADC state.
392 * For parameters constraints, see comments of structure
394 * @note This function configures the ADC within 2 scopes: scope of entire
395 * ADC and scope of regular group. For parameters details, see comments
396 * of structure "ADC_InitTypeDef".
397 * @note Parameters related to common ADC registers (ADC clock mode) are set
398 * only if all ADCs are disabled.
399 * If this is not the case, these common parameters setting are
400 * bypassed without error reporting: it can be the intended behaviour in
401 * case of update of a parameter of ADC_InitTypeDef on the fly,
402 * without disabling the other ADCs.
403 * @param hadc ADC handle
406 HAL_StatusTypeDef
HAL_ADC_Init(ADC_HandleTypeDef
*hadc
)
408 HAL_StatusTypeDef tmp_hal_status
= HAL_OK
;
410 uint32_t tmp_adc_reg_is_conversion_on_going
;
411 __IO
uint32_t wait_loop_index
= 0UL;
412 uint32_t tmp_adc_is_conversion_on_going_regular
;
413 uint32_t tmp_adc_is_conversion_on_going_injected
;
415 /* Check ADC handle */
421 /* Check the parameters */
422 assert_param(IS_ADC_ALL_INSTANCE(hadc
->Instance
));
423 assert_param(IS_ADC_CLOCKPRESCALER(hadc
->Init
.ClockPrescaler
));
424 assert_param(IS_ADC_RESOLUTION(hadc
->Init
.Resolution
));
425 assert_param(IS_ADC_SCAN_MODE(hadc
->Init
.ScanConvMode
));
426 assert_param(IS_FUNCTIONAL_STATE(hadc
->Init
.ContinuousConvMode
));
427 assert_param(IS_ADC_EXTTRIG_EDGE(hadc
->Init
.ExternalTrigConvEdge
));
428 assert_param(IS_ADC_EXTTRIG(hadc
->Init
.ExternalTrigConv
));
429 assert_param(IS_ADC_CONVERSIONDATAMGT(hadc
->Init
.ConversionDataManagement
));
430 assert_param(IS_ADC_EOC_SELECTION(hadc
->Init
.EOCSelection
));
431 assert_param(IS_ADC_OVERRUN(hadc
->Init
.Overrun
));
432 assert_param(IS_FUNCTIONAL_STATE(hadc
->Init
.LowPowerAutoWait
));
433 assert_param(IS_FUNCTIONAL_STATE(hadc
->Init
.OversamplingMode
));
435 if (hadc
->Init
.ScanConvMode
!= ADC_SCAN_DISABLE
)
437 assert_param(IS_ADC_REGULAR_NB_CONV(hadc
->Init
.NbrOfConversion
));
438 assert_param(IS_FUNCTIONAL_STATE(hadc
->Init
.DiscontinuousConvMode
));
440 if (hadc
->Init
.DiscontinuousConvMode
== ENABLE
)
442 assert_param(IS_ADC_REGULAR_DISCONT_NUMBER(hadc
->Init
.NbrOfDiscConversion
));
446 /* DISCEN and CONT bits cannot be set at the same time */
447 assert_param(!((hadc
->Init
.DiscontinuousConvMode
== ENABLE
) && (hadc
->Init
.ContinuousConvMode
== ENABLE
)));
449 /* Actions performed only if ADC is coming from state reset: */
450 /* - Initialization of ADC MSP */
451 if (hadc
->State
== HAL_ADC_STATE_RESET
)
453 #if (USE_HAL_ADC_REGISTER_CALLBACKS == 1)
454 /* Init the ADC Callback settings */
455 hadc
->ConvCpltCallback
= HAL_ADC_ConvCpltCallback
; /* Legacy weak callback */
456 hadc
->ConvHalfCpltCallback
= HAL_ADC_ConvHalfCpltCallback
; /* Legacy weak callback */
457 hadc
->LevelOutOfWindowCallback
= HAL_ADC_LevelOutOfWindowCallback
; /* Legacy weak callback */
458 hadc
->ErrorCallback
= HAL_ADC_ErrorCallback
; /* Legacy weak callback */
459 hadc
->InjectedConvCpltCallback
= HAL_ADCEx_InjectedConvCpltCallback
; /* Legacy weak callback */
460 hadc
->InjectedQueueOverflowCallback
= HAL_ADCEx_InjectedQueueOverflowCallback
; /* Legacy weak callback */
461 hadc
->LevelOutOfWindow2Callback
= HAL_ADCEx_LevelOutOfWindow2Callback
; /* Legacy weak callback */
462 hadc
->LevelOutOfWindow3Callback
= HAL_ADCEx_LevelOutOfWindow3Callback
; /* Legacy weak callback */
463 hadc
->EndOfSamplingCallback
= HAL_ADCEx_EndOfSamplingCallback
; /* Legacy weak callback */
465 if (hadc
->MspInitCallback
== NULL
)
467 hadc
->MspInitCallback
= HAL_ADC_MspInit
; /* Legacy weak MspInit */
470 /* Init the low level hardware */
471 hadc
->MspInitCallback(hadc
);
473 /* Init the low level hardware */
474 HAL_ADC_MspInit(hadc
);
475 #endif /* USE_HAL_ADC_REGISTER_CALLBACKS */
477 /* Set ADC error code to none */
478 ADC_CLEAR_ERRORCODE(hadc
);
480 /* Initialize Lock */
481 hadc
->Lock
= HAL_UNLOCKED
;
484 /* - Exit from deep-power-down mode and ADC voltage regulator enable */
485 if (LL_ADC_IsDeepPowerDownEnabled(hadc
->Instance
) != 0UL)
487 /* Disable ADC deep power down mode */
488 LL_ADC_DisableDeepPowerDown(hadc
->Instance
);
490 /* System was in deep power down mode, calibration must
491 be relaunched or a previously saved calibration factor
492 re-applied once the ADC voltage regulator is enabled */
495 if (LL_ADC_IsInternalRegulatorEnabled(hadc
->Instance
) == 0UL)
497 /* Enable ADC internal voltage regulator */
498 LL_ADC_EnableInternalRegulator(hadc
->Instance
);
500 /* Note: Variable divided by 2 to compensate partially */
501 /* CPU processing cycles, scaling in us split to not */
502 /* exceed 32 bits register capacity and handle low frequency. */
503 wait_loop_index
= ((LL_ADC_DELAY_INTERNAL_REGUL_STAB_US
/ 10UL) * (SystemCoreClock
/ (100000UL * 2UL)));
504 while (wait_loop_index
!= 0UL)
510 /* Verification that ADC voltage regulator is correctly enabled, whether */
511 /* or not ADC is coming from state reset (if any potential problem of */
512 /* clocking, voltage regulator would not be enabled). */
513 if (LL_ADC_IsInternalRegulatorEnabled(hadc
->Instance
) == 0UL)
515 /* Update ADC state machine to error */
516 SET_BIT(hadc
->State
, HAL_ADC_STATE_ERROR_INTERNAL
);
518 /* Set ADC error code to ADC peripheral internal error */
519 SET_BIT(hadc
->ErrorCode
, HAL_ADC_ERROR_INTERNAL
);
521 tmp_hal_status
= HAL_ERROR
;
524 /* Configuration of ADC parameters if previous preliminary actions are */
525 /* correctly completed and if there is no conversion on going on regular */
526 /* group (ADC may already be enabled at this point if HAL_ADC_Init() is */
527 /* called to update a parameter on the fly). */
528 tmp_adc_reg_is_conversion_on_going
= LL_ADC_REG_IsConversionOngoing(hadc
->Instance
);
530 if (((hadc
->State
& HAL_ADC_STATE_ERROR_INTERNAL
) == 0UL)
531 && (tmp_adc_reg_is_conversion_on_going
== 0UL)
535 ADC_STATE_CLR_SET(hadc
->State
,
536 HAL_ADC_STATE_REG_BUSY
,
537 HAL_ADC_STATE_BUSY_INTERNAL
);
539 /* Configuration of common ADC parameters */
541 /* Parameters update conditioned to ADC state: */
542 /* Parameters that can be updated only when ADC is disabled: */
543 /* - clock configuration */
544 if (LL_ADC_IsEnabled(hadc
->Instance
) == 0UL)
546 if (__LL_ADC_IS_ENABLED_ALL_COMMON_INSTANCE(__LL_ADC_COMMON_INSTANCE(hadc
->Instance
)) == 0UL)
548 /* Reset configuration of ADC common register CCR: */
550 /* - ADC clock mode and ACC prescaler (CKMODE and PRESC bits)are set */
551 /* according to adc->Init.ClockPrescaler. It selects the clock */
552 /* source and sets the clock division factor. */
554 /* Some parameters of this register are not reset, since they are set */
555 /* by other functions and must be kept in case of usage of this */
556 /* function on the fly (update of a parameter of ADC_InitTypeDef */
557 /* without needing to reconfigure all other ADC groups/channels */
559 /* - when multimode feature is available, multimode-related */
560 /* parameters: MDMA, DMACFG, DELAY, DUAL (set by API */
561 /* HAL_ADCEx_MultiModeConfigChannel() ) */
562 /* - internal measurement paths: Vbat, temperature sensor, Vref */
563 /* (set into HAL_ADC_ConfigChannel() or */
564 /* HAL_ADCEx_InjectedConfigChannel() ) */
565 LL_ADC_SetCommonClock(__LL_ADC_COMMON_INSTANCE(hadc
->Instance
), hadc
->Init
.ClockPrescaler
);
569 /* Configuration of ADC: */
570 /* - resolution Init.Resolution */
571 /* - external trigger to start conversion Init.ExternalTrigConv */
572 /* - external trigger polarity Init.ExternalTrigConvEdge */
573 /* - continuous conversion mode Init.ContinuousConvMode */
574 /* - overrun Init.Overrun */
575 /* - discontinuous mode Init.DiscontinuousConvMode */
576 /* - discontinuous mode channel count Init.NbrOfDiscConversion */
577 #if defined(ADC_VER_V5_3)
578 tmpCFGR
= (ADC_CFGR_CONTINUOUS((uint32_t)hadc
->Init
.ContinuousConvMode
) |
580 hadc
->Init
.Resolution
|
581 ADC_CFGR_REG_DISCONTINUOUS((uint32_t)hadc
->Init
.DiscontinuousConvMode
) );
584 if((HAL_GetREVID() > REV_ID_Y
) && (ADC_RESOLUTION_8B
== hadc
->Init
.Resolution
))
586 /* for STM32H7 silicon rev.B and above , ADC_CFGR_RES value for 8bits resolution is : b111 */
587 tmpCFGR
= (ADC_CFGR_CONTINUOUS((uint32_t)hadc
->Init
.ContinuousConvMode
) |
589 hadc
->Init
.Resolution
|(ADC_CFGR_RES_1
|ADC_CFGR_RES_0
) |
590 ADC_CFGR_REG_DISCONTINUOUS((uint32_t)hadc
->Init
.DiscontinuousConvMode
) );
594 tmpCFGR
= (ADC_CFGR_CONTINUOUS((uint32_t)hadc
->Init
.ContinuousConvMode
) |
596 hadc
->Init
.Resolution
|
597 ADC_CFGR_REG_DISCONTINUOUS((uint32_t)hadc
->Init
.DiscontinuousConvMode
) );
600 #endif /* ADC_VER_V5_3 */
602 if (hadc
->Init
.DiscontinuousConvMode
== ENABLE
)
604 tmpCFGR
|= ADC_CFGR_DISCONTINUOUS_NUM(hadc
->Init
.NbrOfDiscConversion
);
607 /* Enable external trigger if trigger selection is different of software */
609 /* Note: This configuration keeps the hardware feature of parameter */
610 /* ExternalTrigConvEdge "trigger edge none" equivalent to */
611 /* software start. */
612 if (hadc
->Init
.ExternalTrigConv
!= ADC_SOFTWARE_START
)
614 tmpCFGR
|= ((hadc
->Init
.ExternalTrigConv
& ADC_CFGR_EXTSEL
)
615 | hadc
->Init
.ExternalTrigConvEdge
619 /* Update Configuration Register CFGR */
620 MODIFY_REG(hadc
->Instance
->CFGR
, ADC_CFGR_FIELDS_1
, tmpCFGR
);
622 /* Parameters update conditioned to ADC state: */
623 /* Parameters that can be updated when ADC is disabled or enabled without */
624 /* conversion on going on regular and injected groups: */
625 /* - Conversion data management Init.ConversionDataManagement */
626 /* - LowPowerAutoWait feature Init.LowPowerAutoWait */
627 /* - Oversampling parameters Init.Oversampling */
628 tmp_adc_is_conversion_on_going_regular
= LL_ADC_REG_IsConversionOngoing(hadc
->Instance
);
629 tmp_adc_is_conversion_on_going_injected
= LL_ADC_INJ_IsConversionOngoing(hadc
->Instance
);
630 if ((tmp_adc_is_conversion_on_going_regular
== 0UL)
631 && (tmp_adc_is_conversion_on_going_injected
== 0UL)
635 ADC_CFGR_AUTOWAIT((uint32_t)hadc
->Init
.LowPowerAutoWait
) |
636 ADC_CFGR_DMACONTREQ((uint32_t)hadc
->Init
.ConversionDataManagement
));
638 MODIFY_REG(hadc
->Instance
->CFGR
, ADC_CFGR_FIELDS_2
, tmpCFGR
);
640 if (hadc
->Init
.OversamplingMode
== ENABLE
)
642 assert_param(IS_ADC_OVERSAMPLING_RATIO(hadc
->Init
.Oversampling
.Ratio
));
643 assert_param(IS_ADC_RIGHT_BIT_SHIFT(hadc
->Init
.Oversampling
.RightBitShift
));
644 assert_param(IS_ADC_TRIGGERED_OVERSAMPLING_MODE(hadc
->Init
.Oversampling
.TriggeredMode
));
645 assert_param(IS_ADC_REGOVERSAMPLING_MODE(hadc
->Init
.Oversampling
.OversamplingStopReset
));
647 if ((hadc
->Init
.ExternalTrigConv
== ADC_SOFTWARE_START
)
648 || (hadc
->Init
.ExternalTrigConvEdge
== ADC_EXTERNALTRIGCONVEDGE_NONE
))
650 /* Multi trigger is not applicable to software-triggered conversions */
651 assert_param((hadc
->Init
.Oversampling
.TriggeredMode
== ADC_TRIGGEREDMODE_SINGLE_TRIGGER
));
654 /* Configuration of Oversampler: */
655 /* - Oversampling Ratio */
656 /* - Right bit shift */
657 /* - Left bit shift */
658 /* - Triggered mode */
659 /* - Oversampling mode (continued/resumed) */
660 MODIFY_REG(hadc
->Instance
->CFGR2
, ADC_CFGR2_FIELDS
,
662 ((hadc
->Init
.Oversampling
.Ratio
- 1UL) << ADC_CFGR2_OVSR_Pos
) |
663 hadc
->Init
.Oversampling
.RightBitShift
|
664 hadc
->Init
.Oversampling
.TriggeredMode
|
665 hadc
->Init
.Oversampling
.OversamplingStopReset
);
670 /* Disable ADC oversampling scope on ADC group regular */
671 CLEAR_BIT(hadc
->Instance
->CFGR2
, ADC_CFGR2_ROVSE
);
674 /* Set the LeftShift parameter: it is applied to the final result with or without oversampling */
675 MODIFY_REG(hadc
->Instance
->CFGR2
, ADC_CFGR2_LSHIFT
, hadc
->Init
.LeftBitShift
);
677 /* Configure the BOOST Mode */
678 ADC_ConfigureBoostMode(hadc
);
681 /* Configuration of regular group sequencer: */
682 /* - if scan mode is disabled, regular channels sequence length is set to */
683 /* 0x00: 1 channel converted (channel on regular rank 1) */
684 /* Parameter "NbrOfConversion" is discarded. */
685 /* Note: Scan mode is not present by hardware on this device, but */
686 /* emulated by software for alignment over all STM32 devices. */
687 /* - if scan mode is enabled, regular channels sequence length is set to */
688 /* parameter "NbrOfConversion". */
690 if (hadc
->Init
.ScanConvMode
== ADC_SCAN_ENABLE
)
692 /* Set number of ranks in regular group sequencer */
693 MODIFY_REG(hadc
->Instance
->SQR1
, ADC_SQR1_L
, (hadc
->Init
.NbrOfConversion
- (uint8_t)1));
697 CLEAR_BIT(hadc
->Instance
->SQR1
, ADC_SQR1_L
);
700 /* Initialize the ADC state */
701 /* Clear HAL_ADC_STATE_BUSY_INTERNAL bit, set HAL_ADC_STATE_READY bit */
702 ADC_STATE_CLR_SET(hadc
->State
, HAL_ADC_STATE_BUSY_INTERNAL
, HAL_ADC_STATE_READY
);
706 /* Update ADC state machine to error */
707 SET_BIT(hadc
->State
, HAL_ADC_STATE_ERROR_INTERNAL
);
709 tmp_hal_status
= HAL_ERROR
;
712 /* Return function status */
713 return tmp_hal_status
;
717 * @brief Deinitialize the ADC peripheral registers to their default reset
718 * values, with deinitialization of the ADC MSP.
719 * @note For devices with several ADCs: reset of ADC common registers is done
720 * only if all ADCs sharing the same common group are disabled.
721 * (function "HAL_ADC_MspDeInit()" is also called under the same conditions:
722 * all ADC instances use the same core clock at RCC level, disabling
723 * the core clock reset all ADC instances).
724 * If this is not the case, reset of these common parameters reset is
725 * bypassed without error reporting: it can be the intended behavior in
726 * case of reset of a single ADC while the other ADCs sharing the same
727 * common group is still running.
728 * @note By default, HAL_ADC_DeInit() set ADC in mode deep power-down:
729 * this saves more power by reducing leakage currents
730 * and is particularly interesting before entering MCU low-power modes.
731 * @param hadc ADC handle
734 HAL_StatusTypeDef
HAL_ADC_DeInit(ADC_HandleTypeDef
*hadc
)
736 HAL_StatusTypeDef tmp_hal_status
;
738 /* Check ADC handle */
744 /* Check the parameters */
745 assert_param(IS_ADC_ALL_INSTANCE(hadc
->Instance
));
748 SET_BIT(hadc
->State
, HAL_ADC_STATE_BUSY_INTERNAL
);
750 /* Stop potential conversion on going */
751 tmp_hal_status
= ADC_ConversionStop(hadc
, ADC_REGULAR_INJECTED_GROUP
);
753 /* Disable ADC peripheral if conversions are effectively stopped */
754 /* Flush register JSQR: reset the queue sequencer when injected */
755 /* queue sequencer is enabled and ADC disabled. */
756 /* The software and hardware triggers of the injected sequence are both */
757 /* internally disabled just after the completion of the last valid */
758 /* injected sequence. */
759 SET_BIT(hadc
->Instance
->CFGR
, ADC_CFGR_JQM
);
761 /* Disable ADC peripheral if conversions are effectively stopped */
762 if (tmp_hal_status
== HAL_OK
)
764 /* Disable the ADC peripheral */
765 tmp_hal_status
= ADC_Disable(hadc
);
767 /* Check if ADC is effectively disabled */
768 if (tmp_hal_status
== HAL_OK
)
770 /* Change ADC state */
771 hadc
->State
= HAL_ADC_STATE_READY
;
775 /* Note: HAL ADC deInit is done independently of ADC conversion stop */
776 /* and disable return status. In case of status fail, attempt to */
777 /* perform deinitialization anyway and it is up user code in */
778 /* in HAL_ADC_MspDeInit() to reset the ADC peripheral using */
779 /* system RCC hard reset. */
781 /* ========== Reset ADC registers ========== */
782 /* Reset register IER */
783 __HAL_ADC_DISABLE_IT(hadc
, (ADC_IT_AWD3
| ADC_IT_AWD2
| ADC_IT_AWD1
|
784 ADC_IT_JQOVF
| ADC_IT_OVR
|
785 ADC_IT_JEOS
| ADC_IT_JEOC
|
786 ADC_IT_EOS
| ADC_IT_EOC
|
787 ADC_IT_EOSMP
| ADC_IT_RDY
));
789 /* Reset register ISR */
790 __HAL_ADC_CLEAR_FLAG(hadc
, (ADC_FLAG_AWD3
| ADC_FLAG_AWD2
| ADC_FLAG_AWD1
|
791 ADC_FLAG_JQOVF
| ADC_FLAG_OVR
|
792 ADC_FLAG_JEOS
| ADC_FLAG_JEOC
|
793 ADC_FLAG_EOS
| ADC_FLAG_EOC
|
794 ADC_FLAG_EOSMP
| ADC_FLAG_RDY
));
796 /* Reset register CR */
797 /* Bits ADC_CR_JADSTP, ADC_CR_ADSTP, ADC_CR_JADSTART, ADC_CR_ADSTART,
798 ADC_CR_ADCAL, ADC_CR_ADDIS and ADC_CR_ADEN are in access mode "read-set":
799 no direct reset applicable.
800 Update CR register to reset value where doable by software */
801 CLEAR_BIT(hadc
->Instance
->CR
, ADC_CR_ADVREGEN
| ADC_CR_ADCALDIF
);
802 SET_BIT(hadc
->Instance
->CR
, ADC_CR_DEEPPWD
);
804 /* Reset register CFGR */
805 CLEAR_BIT(hadc
->Instance
->CFGR
, ADC_CFGR_AWD1CH
| ADC_CFGR_JAUTO
| ADC_CFGR_JAWD1EN
|
806 ADC_CFGR_AWD1EN
| ADC_CFGR_AWD1SGL
| ADC_CFGR_JQM
|
807 ADC_CFGR_JDISCEN
| ADC_CFGR_DISCNUM
| ADC_CFGR_DISCEN
|
808 ADC_CFGR_AUTDLY
| ADC_CFGR_CONT
| ADC_CFGR_OVRMOD
|
809 ADC_CFGR_EXTEN
| ADC_CFGR_EXTSEL
|
810 ADC_CFGR_RES
| ADC_CFGR_DMNGT
);
811 SET_BIT(hadc
->Instance
->CFGR
, ADC_CFGR_JQDIS
);
813 /* Reset register CFGR2 */
814 CLEAR_BIT(hadc
->Instance
->CFGR2
, ADC_CFGR2_ROVSM
| ADC_CFGR2_TROVS
| ADC_CFGR2_OVSS
|
815 ADC_CFGR2_OVSR
| ADC_CFGR2_JOVSE
| ADC_CFGR2_ROVSE
);
817 /* Reset register SMPR1 */
818 CLEAR_BIT(hadc
->Instance
->SMPR1
, ADC_SMPR1_FIELDS
);
820 /* Reset register SMPR2 */
821 CLEAR_BIT(hadc
->Instance
->SMPR2
, ADC_SMPR2_SMP18
| ADC_SMPR2_SMP17
| ADC_SMPR2_SMP16
|
822 ADC_SMPR2_SMP15
| ADC_SMPR2_SMP14
| ADC_SMPR2_SMP13
|
823 ADC_SMPR2_SMP12
| ADC_SMPR2_SMP11
| ADC_SMPR2_SMP10
);
825 /* Reset register LTR1 and HTR1 */
826 CLEAR_BIT(hadc
->Instance
->LTR1
, ADC_LTR_LT
);
827 CLEAR_BIT(hadc
->Instance
->HTR1
, ADC_HTR_HT
);
829 /* Reset register LTR2 and HTR2*/
830 CLEAR_BIT(hadc
->Instance
->LTR2
, ADC_LTR_LT
);
831 CLEAR_BIT(hadc
->Instance
->HTR2
, ADC_HTR_HT
);
833 /* Reset register LTR3 and HTR3 */
834 CLEAR_BIT(hadc
->Instance
->LTR3
, ADC_LTR_LT
);
835 CLEAR_BIT(hadc
->Instance
->HTR3
, ADC_HTR_HT
);
837 /* Reset register SQR1 */
838 CLEAR_BIT(hadc
->Instance
->SQR1
, ADC_SQR1_SQ4
| ADC_SQR1_SQ3
| ADC_SQR1_SQ2
|
839 ADC_SQR1_SQ1
| ADC_SQR1_L
);
841 /* Reset register SQR2 */
842 CLEAR_BIT(hadc
->Instance
->SQR2
, ADC_SQR2_SQ9
| ADC_SQR2_SQ8
| ADC_SQR2_SQ7
|
843 ADC_SQR2_SQ6
| ADC_SQR2_SQ5
);
845 /* Reset register SQR3 */
846 CLEAR_BIT(hadc
->Instance
->SQR3
, ADC_SQR3_SQ14
| ADC_SQR3_SQ13
| ADC_SQR3_SQ12
|
847 ADC_SQR3_SQ11
| ADC_SQR3_SQ10
);
849 /* Reset register SQR4 */
850 CLEAR_BIT(hadc
->Instance
->SQR4
, ADC_SQR4_SQ16
| ADC_SQR4_SQ15
);
852 /* Register JSQR was reset when the ADC was disabled */
854 /* Reset register DR */
855 /* bits in access mode read only, no direct reset applicable*/
857 /* Reset register OFR1 */
858 CLEAR_BIT(hadc
->Instance
->OFR1
, ADC_OFR1_SSATE
| ADC_OFR1_OFFSET1_CH
| ADC_OFR1_OFFSET1
);
859 /* Reset register OFR2 */
860 CLEAR_BIT(hadc
->Instance
->OFR2
, ADC_OFR2_SSATE
| ADC_OFR2_OFFSET2_CH
| ADC_OFR2_OFFSET2
);
861 /* Reset register OFR3 */
862 CLEAR_BIT(hadc
->Instance
->OFR3
, ADC_OFR3_SSATE
| ADC_OFR3_OFFSET3_CH
| ADC_OFR3_OFFSET3
);
863 /* Reset register OFR4 */
864 CLEAR_BIT(hadc
->Instance
->OFR4
, ADC_OFR4_SSATE
| ADC_OFR4_OFFSET4_CH
| ADC_OFR4_OFFSET4
);
866 /* Reset registers JDR1, JDR2, JDR3, JDR4 */
867 /* bits in access mode read only, no direct reset applicable*/
869 /* Reset register AWD2CR */
870 CLEAR_BIT(hadc
->Instance
->AWD2CR
, ADC_AWD2CR_AWD2CH
);
872 /* Reset register AWD3CR */
873 CLEAR_BIT(hadc
->Instance
->AWD3CR
, ADC_AWD3CR_AWD3CH
);
875 /* Reset register DIFSEL */
876 CLEAR_BIT(hadc
->Instance
->DIFSEL
, ADC_DIFSEL_DIFSEL
);
878 /* Reset register CALFACT */
879 CLEAR_BIT(hadc
->Instance
->CALFACT
, ADC_CALFACT_CALFACT_D
| ADC_CALFACT_CALFACT_S
);
882 /* ========== Reset common ADC registers ========== */
884 /* Software is allowed to change common parameters only when all the other
885 ADCs are disabled. */
886 if (__LL_ADC_IS_ENABLED_ALL_COMMON_INSTANCE(__LL_ADC_COMMON_INSTANCE(hadc
->Instance
)) == 0UL)
888 /* Reset configuration of ADC common register CCR:
889 - clock mode: CKMODE, PRESCEN
890 - multimode related parameters(when this feature is available): DELAY, DUAL
891 (set into HAL_ADCEx_MultiModeConfigChannel() API)
892 - internal measurement paths: Vbat, temperature sensor, Vref (set into
893 HAL_ADC_ConfigChannel() or HAL_ADCEx_InjectedConfigChannel() )
895 ADC_CLEAR_COMMON_CONTROL_REGISTER(hadc
);
898 /* DeInit the low level hardware.
901 __HAL_RCC_ADC_FORCE_RESET();
902 __HAL_RCC_ADC_RELEASE_RESET();
903 __HAL_RCC_ADC_CLK_DISABLE();
905 Keep in mind that all ADCs use the same clock: disabling
906 the clock will reset all ADCs.
909 #if (USE_HAL_ADC_REGISTER_CALLBACKS == 1)
910 if (hadc
->MspDeInitCallback
== NULL
)
912 hadc
->MspDeInitCallback
= HAL_ADC_MspDeInit
; /* Legacy weak MspDeInit */
915 /* DeInit the low level hardware: RCC clock, NVIC */
916 hadc
->MspDeInitCallback(hadc
);
918 /* DeInit the low level hardware: RCC clock, NVIC */
919 HAL_ADC_MspDeInit(hadc
);
920 #endif /* USE_HAL_ADC_REGISTER_CALLBACKS */
922 /* Set ADC error code to none */
923 ADC_CLEAR_ERRORCODE(hadc
);
925 /* Reset injected channel configuration parameters */
926 hadc
->InjectionConfig
.ContextQueue
= 0;
927 hadc
->InjectionConfig
.ChannelCount
= 0;
930 hadc
->State
= HAL_ADC_STATE_RESET
;
932 /* Process unlocked */
935 /* Return function status */
936 return tmp_hal_status
;
940 * @brief Initialize the ADC MSP.
941 * @param hadc ADC handle
944 __weak
void HAL_ADC_MspInit(ADC_HandleTypeDef
*hadc
)
946 /* Prevent unused argument(s) compilation warning */
949 /* NOTE : This function should not be modified. When the callback is needed,
950 function HAL_ADC_MspInit must be implemented in the user file.
955 * @brief DeInitialize the ADC MSP.
956 * @param hadc ADC handle
957 * @note All ADC instances use the same core clock at RCC level, disabling
958 * the core clock reset all ADC instances).
961 __weak
void HAL_ADC_MspDeInit(ADC_HandleTypeDef
*hadc
)
963 /* Prevent unused argument(s) compilation warning */
966 /* NOTE : This function should not be modified. When the callback is needed,
967 function HAL_ADC_MspDeInit must be implemented in the user file.
971 #if (USE_HAL_ADC_REGISTER_CALLBACKS == 1)
973 * @brief Register a User ADC Callback
974 * To be used instead of the weak predefined callback
975 * @param hadc Pointer to a ADC_HandleTypeDef structure that contains
976 * the configuration information for the specified ADC.
977 * @param CallbackID ID of the callback to be registered
978 * This parameter can be one of the following values:
979 * @arg @ref HAL_ADC_CONVERSION_COMPLETE_CB_ID ADC conversion complete callback ID
980 * @arg @ref HAL_ADC_CONVERSION_HALF_CB_ID ADC conversion DMA half-transfer callback ID
981 * @arg @ref HAL_ADC_LEVEL_OUT_OF_WINDOW_1_CB_ID ADC analog watchdog 1 callback ID
982 * @arg @ref HAL_ADC_ERROR_CB_ID ADC error callback ID
983 * @arg @ref HAL_ADC_INJ_CONVERSION_COMPLETE_CB_ID ADC group injected conversion complete callback ID
984 * @arg @ref HAL_ADC_INJ_QUEUE_OVEFLOW_CB_ID ADC group injected context queue overflow callback ID
985 * @arg @ref HAL_ADC_LEVEL_OUT_OF_WINDOW_2_CB_ID ADC analog watchdog 2 callback ID
986 * @arg @ref HAL_ADC_LEVEL_OUT_OF_WINDOW_3_CB_ID ADC analog watchdog 3 callback ID
987 * @arg @ref HAL_ADC_END_OF_SAMPLING_CB_ID ADC end of sampling callback ID
988 * @arg @ref HAL_ADC_MSPINIT_CB_ID ADC Msp Init callback ID
989 * @arg @ref HAL_ADC_MSPDEINIT_CB_ID ADC Msp DeInit callback ID
990 * @param pCallback pointer to the Callback function
993 HAL_StatusTypeDef
HAL_ADC_RegisterCallback(ADC_HandleTypeDef
*hadc
, HAL_ADC_CallbackIDTypeDef CallbackID
, pADC_CallbackTypeDef pCallback
)
995 HAL_StatusTypeDef status
= HAL_OK
;
997 if (pCallback
== NULL
)
999 /* Update the error code */
1000 hadc
->ErrorCode
|= HAL_ADC_ERROR_INVALID_CALLBACK
;
1005 if ((hadc
->State
& HAL_ADC_STATE_READY
) != 0UL)
1009 case HAL_ADC_CONVERSION_COMPLETE_CB_ID
:
1010 hadc
->ConvCpltCallback
= pCallback
;
1013 case HAL_ADC_CONVERSION_HALF_CB_ID
:
1014 hadc
->ConvHalfCpltCallback
= pCallback
;
1017 case HAL_ADC_LEVEL_OUT_OF_WINDOW_1_CB_ID
:
1018 hadc
->LevelOutOfWindowCallback
= pCallback
;
1021 case HAL_ADC_ERROR_CB_ID
:
1022 hadc
->ErrorCallback
= pCallback
;
1025 case HAL_ADC_INJ_CONVERSION_COMPLETE_CB_ID
:
1026 hadc
->InjectedConvCpltCallback
= pCallback
;
1029 case HAL_ADC_INJ_QUEUE_OVEFLOW_CB_ID
:
1030 hadc
->InjectedQueueOverflowCallback
= pCallback
;
1033 case HAL_ADC_LEVEL_OUT_OF_WINDOW_2_CB_ID
:
1034 hadc
->LevelOutOfWindow2Callback
= pCallback
;
1037 case HAL_ADC_LEVEL_OUT_OF_WINDOW_3_CB_ID
:
1038 hadc
->LevelOutOfWindow3Callback
= pCallback
;
1041 case HAL_ADC_END_OF_SAMPLING_CB_ID
:
1042 hadc
->EndOfSamplingCallback
= pCallback
;
1045 case HAL_ADC_MSPINIT_CB_ID
:
1046 hadc
->MspInitCallback
= pCallback
;
1049 case HAL_ADC_MSPDEINIT_CB_ID
:
1050 hadc
->MspDeInitCallback
= pCallback
;
1054 /* Update the error code */
1055 hadc
->ErrorCode
|= HAL_ADC_ERROR_INVALID_CALLBACK
;
1057 /* Return error status */
1062 else if (HAL_ADC_STATE_RESET
== hadc
->State
)
1066 case HAL_ADC_MSPINIT_CB_ID
:
1067 hadc
->MspInitCallback
= pCallback
;
1070 case HAL_ADC_MSPDEINIT_CB_ID
:
1071 hadc
->MspDeInitCallback
= pCallback
;
1075 /* Update the error code */
1076 hadc
->ErrorCode
|= HAL_ADC_ERROR_INVALID_CALLBACK
;
1078 /* Return error status */
1085 /* Update the error code */
1086 hadc
->ErrorCode
|= HAL_ADC_ERROR_INVALID_CALLBACK
;
1088 /* Return error status */
1096 * @brief Unregister a ADC Callback
1097 * ADC callback is redirected to the weak predefined callback
1098 * @param hadc Pointer to a ADC_HandleTypeDef structure that contains
1099 * the configuration information for the specified ADC.
1100 * @param CallbackID ID of the callback to be unregistered
1101 * This parameter can be one of the following values:
1102 * @arg @ref HAL_ADC_CONVERSION_COMPLETE_CB_ID ADC conversion complete callback ID
1103 * @arg @ref HAL_ADC_CONVERSION_HALF_CB_ID ADC conversion DMA half-transfer callback ID
1104 * @arg @ref HAL_ADC_LEVEL_OUT_OF_WINDOW_1_CB_ID ADC analog watchdog 1 callback ID
1105 * @arg @ref HAL_ADC_ERROR_CB_ID ADC error callback ID
1106 * @arg @ref HAL_ADC_INJ_CONVERSION_COMPLETE_CB_ID ADC group injected conversion complete callback ID
1107 * @arg @ref HAL_ADC_INJ_QUEUE_OVEFLOW_CB_ID ADC group injected context queue overflow callback ID
1108 * @arg @ref HAL_ADC_LEVEL_OUT_OF_WINDOW_2_CB_ID ADC analog watchdog 2 callback ID
1109 * @arg @ref HAL_ADC_LEVEL_OUT_OF_WINDOW_3_CB_ID ADC analog watchdog 3 callback ID
1110 * @arg @ref HAL_ADC_END_OF_SAMPLING_CB_ID ADC end of sampling callback ID
1111 * @arg @ref HAL_ADC_MSPINIT_CB_ID ADC Msp Init callback ID
1112 * @arg @ref HAL_ADC_MSPDEINIT_CB_ID ADC Msp DeInit callback ID
1113 * @retval HAL status
1115 HAL_StatusTypeDef
HAL_ADC_UnRegisterCallback(ADC_HandleTypeDef
*hadc
, HAL_ADC_CallbackIDTypeDef CallbackID
)
1117 HAL_StatusTypeDef status
= HAL_OK
;
1119 if ((hadc
->State
& HAL_ADC_STATE_READY
) != 0UL)
1123 case HAL_ADC_CONVERSION_COMPLETE_CB_ID
:
1124 hadc
->ConvCpltCallback
= HAL_ADC_ConvCpltCallback
;
1127 case HAL_ADC_CONVERSION_HALF_CB_ID
:
1128 hadc
->ConvHalfCpltCallback
= HAL_ADC_ConvHalfCpltCallback
;
1131 case HAL_ADC_LEVEL_OUT_OF_WINDOW_1_CB_ID
:
1132 hadc
->LevelOutOfWindowCallback
= HAL_ADC_LevelOutOfWindowCallback
;
1135 case HAL_ADC_ERROR_CB_ID
:
1136 hadc
->ErrorCallback
= HAL_ADC_ErrorCallback
;
1139 case HAL_ADC_INJ_CONVERSION_COMPLETE_CB_ID
:
1140 hadc
->InjectedConvCpltCallback
= HAL_ADCEx_InjectedConvCpltCallback
;
1143 case HAL_ADC_INJ_QUEUE_OVEFLOW_CB_ID
:
1144 hadc
->InjectedQueueOverflowCallback
= HAL_ADCEx_InjectedQueueOverflowCallback
;
1147 case HAL_ADC_LEVEL_OUT_OF_WINDOW_2_CB_ID
:
1148 hadc
->LevelOutOfWindow2Callback
= HAL_ADCEx_LevelOutOfWindow2Callback
;
1151 case HAL_ADC_LEVEL_OUT_OF_WINDOW_3_CB_ID
:
1152 hadc
->LevelOutOfWindow3Callback
= HAL_ADCEx_LevelOutOfWindow3Callback
;
1155 case HAL_ADC_END_OF_SAMPLING_CB_ID
:
1156 hadc
->EndOfSamplingCallback
= HAL_ADCEx_EndOfSamplingCallback
;
1159 case HAL_ADC_MSPINIT_CB_ID
:
1160 hadc
->MspInitCallback
= HAL_ADC_MspInit
; /* Legacy weak MspInit */
1163 case HAL_ADC_MSPDEINIT_CB_ID
:
1164 hadc
->MspDeInitCallback
= HAL_ADC_MspDeInit
; /* Legacy weak MspDeInit */
1168 /* Update the error code */
1169 hadc
->ErrorCode
|= HAL_ADC_ERROR_INVALID_CALLBACK
;
1171 /* Return error status */
1176 else if (HAL_ADC_STATE_RESET
== hadc
->State
)
1180 case HAL_ADC_MSPINIT_CB_ID
:
1181 hadc
->MspInitCallback
= HAL_ADC_MspInit
; /* Legacy weak MspInit */
1184 case HAL_ADC_MSPDEINIT_CB_ID
:
1185 hadc
->MspDeInitCallback
= HAL_ADC_MspDeInit
; /* Legacy weak MspDeInit */
1189 /* Update the error code */
1190 hadc
->ErrorCode
|= HAL_ADC_ERROR_INVALID_CALLBACK
;
1192 /* Return error status */
1199 /* Update the error code */
1200 hadc
->ErrorCode
|= HAL_ADC_ERROR_INVALID_CALLBACK
;
1202 /* Return error status */
1209 #endif /* USE_HAL_ADC_REGISTER_CALLBACKS */
1215 /** @defgroup ADC_Exported_Functions_Group2 ADC Input and Output operation functions
1216 * @brief ADC IO operation functions
1219 ===============================================================================
1220 ##### IO operation functions #####
1221 ===============================================================================
1222 [..] This section provides functions allowing to:
1223 (+) Start conversion of regular group.
1224 (+) Stop conversion of regular group.
1225 (+) Poll for conversion complete on regular group.
1226 (+) Poll for conversion event.
1227 (+) Get result of regular channel conversion.
1228 (+) Start conversion of regular group and enable interruptions.
1229 (+) Stop conversion of regular group and disable interruptions.
1230 (+) Handle ADC interrupt request
1231 (+) Start conversion of regular group and enable DMA transfer.
1232 (+) Stop conversion of regular group and disable ADC DMA transfer.
1238 * @brief Enable ADC, start conversion of regular group.
1239 * @note Interruptions enabled in this function: None.
1240 * @note Case of multimode enabled (when multimode feature is available):
1241 * if ADC is Slave, ADC is enabled but conversion is not started,
1242 * if ADC is master, ADC is enabled and multimode conversion is started.
1243 * @param hadc ADC handle
1244 * @retval HAL status
1246 HAL_StatusTypeDef
HAL_ADC_Start(ADC_HandleTypeDef
*hadc
)
1248 HAL_StatusTypeDef tmp_hal_status
;
1249 const ADC_TypeDef
*tmpADC_Master
;
1250 uint32_t tmp_multimode_config
= LL_ADC_GetMultimode(__LL_ADC_COMMON_INSTANCE(hadc
->Instance
));
1252 /* Check the parameters */
1253 assert_param(IS_ADC_ALL_INSTANCE(hadc
->Instance
));
1255 /* Perform ADC enable and conversion start if no conversion is on going */
1256 if (LL_ADC_REG_IsConversionOngoing(hadc
->Instance
) == 0UL)
1258 /* Process locked */
1261 /* Enable the ADC peripheral */
1262 tmp_hal_status
= ADC_Enable(hadc
);
1264 /* Start conversion if ADC is effectively enabled */
1265 if (tmp_hal_status
== HAL_OK
)
1268 /* - Clear state bitfield related to regular group conversion results */
1269 /* - Set state bitfield related to regular operation */
1270 ADC_STATE_CLR_SET(hadc
->State
,
1271 HAL_ADC_STATE_READY
| HAL_ADC_STATE_REG_EOC
| HAL_ADC_STATE_REG_OVR
| HAL_ADC_STATE_REG_EOSMP
,
1272 HAL_ADC_STATE_REG_BUSY
);
1274 /* Reset HAL_ADC_STATE_MULTIMODE_SLAVE bit
1275 - if ADC instance is master or if multimode feature is not available
1276 - if multimode setting is disabled (ADC instance slave in independent mode) */
1277 if ((__LL_ADC_MULTI_INSTANCE_MASTER(hadc
->Instance
) == hadc
->Instance
)
1278 || (tmp_multimode_config
== LL_ADC_MULTI_INDEPENDENT
)
1281 CLEAR_BIT(hadc
->State
, HAL_ADC_STATE_MULTIMODE_SLAVE
);
1284 /* Set ADC error code */
1285 /* Check if a conversion is on going on ADC group injected */
1286 if (HAL_IS_BIT_SET(hadc
->State
, HAL_ADC_STATE_INJ_BUSY
))
1288 /* Reset ADC error code fields related to regular conversions only */
1289 CLEAR_BIT(hadc
->ErrorCode
, (HAL_ADC_ERROR_OVR
| HAL_ADC_ERROR_DMA
));
1293 /* Reset all ADC error code fields */
1294 ADC_CLEAR_ERRORCODE(hadc
);
1297 /* Clear ADC group regular conversion flag and overrun flag */
1298 /* (To ensure of no unknown state from potential previous ADC operations) */
1299 __HAL_ADC_CLEAR_FLAG(hadc
, (ADC_FLAG_EOC
| ADC_FLAG_EOS
| ADC_FLAG_OVR
));
1301 /* Process unlocked */
1302 /* Unlock before starting ADC conversions: in case of potential */
1303 /* interruption, to let the process to ADC IRQ Handler. */
1306 /* Enable conversion of regular group. */
1307 /* If software start has been selected, conversion starts immediately. */
1308 /* If external trigger has been selected, conversion will start at next */
1309 /* trigger event. */
1310 /* Case of multimode enabled (when multimode feature is available): */
1311 /* - if ADC is slave and dual regular conversions are enabled, ADC is */
1312 /* enabled only (conversion is not started), */
1313 /* - if ADC is master, ADC is enabled and conversion is started. */
1314 if ((__LL_ADC_MULTI_INSTANCE_MASTER(hadc
->Instance
) == hadc
->Instance
)
1315 || (tmp_multimode_config
== LL_ADC_MULTI_INDEPENDENT
)
1316 || (tmp_multimode_config
== LL_ADC_MULTI_DUAL_INJ_SIMULT
)
1317 || (tmp_multimode_config
== LL_ADC_MULTI_DUAL_INJ_ALTERN
)
1320 /* ADC instance is not a multimode slave instance with multimode regular conversions enabled */
1321 if (READ_BIT(hadc
->Instance
->CFGR
, ADC_CFGR_JAUTO
) != 0UL)
1323 ADC_STATE_CLR_SET(hadc
->State
, HAL_ADC_STATE_INJ_EOC
, HAL_ADC_STATE_INJ_BUSY
);
1326 /* Start ADC group regular conversion */
1327 LL_ADC_REG_StartConversion(hadc
->Instance
);
1331 /* ADC instance is a multimode slave instance with multimode regular conversions enabled */
1332 SET_BIT(hadc
->State
, HAL_ADC_STATE_MULTIMODE_SLAVE
);
1333 /* if Master ADC JAUTO bit is set, update Slave State in setting
1334 HAL_ADC_STATE_INJ_BUSY bit and in resetting HAL_ADC_STATE_INJ_EOC bit */
1335 tmpADC_Master
= __LL_ADC_MULTI_INSTANCE_MASTER(hadc
->Instance
);
1336 if (READ_BIT(tmpADC_Master
->CFGR
, ADC_CFGR_JAUTO
) != 0UL)
1338 ADC_STATE_CLR_SET(hadc
->State
, HAL_ADC_STATE_INJ_EOC
, HAL_ADC_STATE_INJ_BUSY
);
1345 /* Process unlocked */
1351 tmp_hal_status
= HAL_BUSY
;
1354 /* Return function status */
1355 return tmp_hal_status
;
1359 * @brief Stop ADC conversion of regular group (and injected channels in
1360 * case of auto_injection mode), disable ADC peripheral.
1361 * @note: ADC peripheral disable is forcing stop of potential
1362 * conversion on injected group. If injected group is under use, it
1363 * should be preliminarily stopped using HAL_ADCEx_InjectedStop function.
1364 * @param hadc ADC handle
1365 * @retval HAL status.
1367 HAL_StatusTypeDef
HAL_ADC_Stop(ADC_HandleTypeDef
*hadc
)
1369 HAL_StatusTypeDef tmp_hal_status
;
1371 /* Check the parameters */
1372 assert_param(IS_ADC_ALL_INSTANCE(hadc
->Instance
));
1374 /* Process locked */
1377 /* 1. Stop potential conversion on going, on ADC groups regular and injected */
1378 tmp_hal_status
= ADC_ConversionStop(hadc
, ADC_REGULAR_INJECTED_GROUP
);
1380 /* Disable ADC peripheral if conversions are effectively stopped */
1381 if (tmp_hal_status
== HAL_OK
)
1383 /* 2. Disable the ADC peripheral */
1384 tmp_hal_status
= ADC_Disable(hadc
);
1386 /* Check if ADC is effectively disabled */
1387 if (tmp_hal_status
== HAL_OK
)
1390 ADC_STATE_CLR_SET(hadc
->State
,
1391 HAL_ADC_STATE_REG_BUSY
| HAL_ADC_STATE_INJ_BUSY
,
1392 HAL_ADC_STATE_READY
);
1396 /* Process unlocked */
1399 /* Return function status */
1400 return tmp_hal_status
;
1404 * @brief Wait for regular group conversion to be completed.
1405 * @note ADC conversion flags EOS (end of sequence) and EOC (end of
1406 * conversion) are cleared by this function, with an exception:
1407 * if low power feature "LowPowerAutoWait" is enabled, flags are
1408 * not cleared to not interfere with this feature until data register
1409 * is read using function HAL_ADC_GetValue().
1410 * @note This function cannot be used in a particular setup: ADC configured
1411 * in DMA mode and polling for end of each conversion (ADC init
1412 * parameter "EOCSelection" set to ADC_EOC_SINGLE_CONV).
1413 * In this case, DMA resets the flag EOC and polling cannot be
1414 * performed on each conversion. Nevertheless, polling can still
1415 * be performed on the complete sequence (ADC init
1416 * parameter "EOCSelection" set to ADC_EOC_SEQ_CONV).
1417 * @param hadc ADC handle
1418 * @param Timeout Timeout value in millisecond.
1419 * @retval HAL status
1421 HAL_StatusTypeDef
HAL_ADC_PollForConversion(ADC_HandleTypeDef
*hadc
, uint32_t Timeout
)
1424 uint32_t tmp_Flag_End
;
1426 const ADC_TypeDef
*tmpADC_Master
;
1427 uint32_t tmp_multimode_config
= LL_ADC_GetMultimode(__LL_ADC_COMMON_INSTANCE(hadc
->Instance
));
1429 /* Check the parameters */
1430 assert_param(IS_ADC_ALL_INSTANCE(hadc
->Instance
));
1432 /* If end of conversion selected to end of sequence conversions */
1433 if (hadc
->Init
.EOCSelection
== ADC_EOC_SEQ_CONV
)
1435 tmp_Flag_End
= ADC_FLAG_EOS
;
1437 /* If end of conversion selected to end of unitary conversion */
1438 else /* ADC_EOC_SINGLE_CONV */
1440 /* Verification that ADC configuration is compliant with polling for */
1441 /* each conversion: */
1442 /* Particular case is ADC configured in DMA mode and ADC sequencer with */
1443 /* several ranks and polling for end of each conversion. */
1444 /* For code simplicity sake, this particular case is generalized to */
1445 /* ADC configured in DMA mode and and polling for end of each conversion. */
1446 if ((tmp_multimode_config
== LL_ADC_MULTI_INDEPENDENT
)
1447 || (tmp_multimode_config
== LL_ADC_MULTI_DUAL_INJ_SIMULT
)
1448 || (tmp_multimode_config
== LL_ADC_MULTI_DUAL_INJ_ALTERN
)
1451 /* Check DMNGT bit in handle ADC CFGR register */
1452 if (READ_BIT(hadc
->Instance
->CFGR
, ADC_CFGR_DMNGT_0
) != 0UL)
1454 SET_BIT(hadc
->State
, HAL_ADC_STATE_ERROR_CONFIG
);
1459 tmp_Flag_End
= (ADC_FLAG_EOC
);
1464 /* Check ADC DMA mode in multimode on ADC group regular */
1465 if (LL_ADC_GetMultiDMATransfer(__LL_ADC_COMMON_INSTANCE(hadc
->Instance
)) != LL_ADC_MULTI_REG_DMA_EACH_ADC
)
1467 SET_BIT(hadc
->State
, HAL_ADC_STATE_ERROR_CONFIG
);
1472 tmp_Flag_End
= (ADC_FLAG_EOC
);
1477 /* Get tick count */
1478 tickstart
= HAL_GetTick();
1480 /* Wait until End of unitary conversion or sequence conversions flag is raised */
1481 while ((hadc
->Instance
->ISR
& tmp_Flag_End
) == 0UL)
1483 /* Check if timeout is disabled (set to infinite wait) */
1484 if (Timeout
!= HAL_MAX_DELAY
)
1486 if (((HAL_GetTick() - tickstart
) > Timeout
) || (Timeout
== 0UL))
1488 /* Update ADC state machine to timeout */
1489 SET_BIT(hadc
->State
, HAL_ADC_STATE_TIMEOUT
);
1491 /* Process unlocked */
1499 /* Update ADC state machine */
1500 SET_BIT(hadc
->State
, HAL_ADC_STATE_REG_EOC
);
1502 /* Determine whether any further conversion upcoming on group regular */
1503 /* by external trigger, continuous mode or scan sequence on going. */
1504 if ((LL_ADC_REG_IsTriggerSourceSWStart(hadc
->Instance
) != 0UL)
1505 && (hadc
->Init
.ContinuousConvMode
== DISABLE
)
1508 /* Check whether end of sequence is reached */
1509 if (__HAL_ADC_GET_FLAG(hadc
, ADC_FLAG_EOS
))
1512 CLEAR_BIT(hadc
->State
, HAL_ADC_STATE_REG_BUSY
);
1514 if ((hadc
->State
& HAL_ADC_STATE_INJ_BUSY
) == 0UL)
1516 SET_BIT(hadc
->State
, HAL_ADC_STATE_READY
);
1521 /* Get relevant register CFGR in ADC instance of ADC master or slave */
1522 /* in function of multimode state (for devices with multimode */
1524 if ((__LL_ADC_MULTI_INSTANCE_MASTER(hadc
->Instance
) == hadc
->Instance
)
1525 || (tmp_multimode_config
== LL_ADC_MULTI_INDEPENDENT
)
1526 || (tmp_multimode_config
== LL_ADC_MULTI_DUAL_INJ_SIMULT
)
1527 || (tmp_multimode_config
== LL_ADC_MULTI_DUAL_INJ_ALTERN
)
1530 /* Retrieve handle ADC CFGR register */
1531 tmp_cfgr
= READ_REG(hadc
->Instance
->CFGR
);
1535 /* Retrieve Master ADC CFGR register */
1536 tmpADC_Master
= __LL_ADC_MULTI_INSTANCE_MASTER(hadc
->Instance
);
1537 tmp_cfgr
= READ_REG(tmpADC_Master
->CFGR
);
1540 /* Clear polled flag */
1541 if (tmp_Flag_End
== ADC_FLAG_EOS
)
1543 __HAL_ADC_CLEAR_FLAG(hadc
, ADC_FLAG_EOS
);
1547 /* Clear end of conversion EOC flag of regular group if low power feature */
1548 /* "LowPowerAutoWait " is disabled, to not interfere with this feature */
1549 /* until data register is read using function HAL_ADC_GetValue(). */
1550 if (READ_BIT(tmp_cfgr
, ADC_CFGR_AUTDLY
) == 0UL)
1552 __HAL_ADC_CLEAR_FLAG(hadc
, (ADC_FLAG_EOC
| ADC_FLAG_EOS
));
1556 /* Return function status */
1561 * @brief Poll for ADC event.
1562 * @param hadc ADC handle
1563 * @param EventType the ADC event type.
1564 * This parameter can be one of the following values:
1565 * @arg @ref ADC_EOSMP_EVENT ADC End of Sampling event
1566 * @arg @ref ADC_AWD1_EVENT ADC Analog watchdog 1 event (main analog watchdog, present on all STM32 devices)
1567 * @arg @ref ADC_AWD2_EVENT ADC Analog watchdog 2 event (additional analog watchdog, not present on all STM32 families)
1568 * @arg @ref ADC_AWD3_EVENT ADC Analog watchdog 3 event (additional analog watchdog, not present on all STM32 families)
1569 * @arg @ref ADC_OVR_EVENT ADC Overrun event
1570 * @arg @ref ADC_JQOVF_EVENT ADC Injected context queue overflow event
1571 * @param Timeout Timeout value in millisecond.
1572 * @note The relevant flag is cleared if found to be set, except for ADC_FLAG_OVR.
1573 * Indeed, the latter is reset only if hadc->Init.Overrun field is set
1574 * to ADC_OVR_DATA_OVERWRITTEN. Otherwise, data register may be potentially overwritten
1575 * by a new converted data as soon as OVR is cleared.
1576 * To reset OVR flag once the preserved data is retrieved, the user can resort
1577 * to macro __HAL_ADC_CLEAR_FLAG(hadc, ADC_FLAG_OVR);
1578 * @retval HAL status
1580 HAL_StatusTypeDef
HAL_ADC_PollForEvent(ADC_HandleTypeDef
*hadc
, uint32_t EventType
, uint32_t Timeout
)
1584 /* Check the parameters */
1585 assert_param(IS_ADC_ALL_INSTANCE(hadc
->Instance
));
1586 assert_param(IS_ADC_EVENT_TYPE(EventType
));
1588 /* Get tick count */
1589 tickstart
= HAL_GetTick();
1591 /* Check selected event flag */
1592 while (__HAL_ADC_GET_FLAG(hadc
, EventType
) == 0UL)
1594 /* Check if timeout is disabled (set to infinite wait) */
1595 if (Timeout
!= HAL_MAX_DELAY
)
1597 if (((HAL_GetTick() - tickstart
) > Timeout
) || (Timeout
== 0UL))
1599 /* Update ADC state machine to timeout */
1600 SET_BIT(hadc
->State
, HAL_ADC_STATE_TIMEOUT
);
1602 /* Process unlocked */
1612 /* End Of Sampling event */
1613 case ADC_EOSMP_EVENT
:
1615 SET_BIT(hadc
->State
, HAL_ADC_STATE_REG_EOSMP
);
1617 /* Clear the End Of Sampling flag */
1618 __HAL_ADC_CLEAR_FLAG(hadc
, ADC_FLAG_EOSMP
);
1622 /* Analog watchdog (level out of window) event */
1623 /* Note: In case of several analog watchdog enabled, if needed to know */
1624 /* which one triggered and on which ADCx, test ADC state of analog watchdog */
1625 /* flags HAL_ADC_STATE_AWD1/2/3 using function "HAL_ADC_GetState()". */
1627 /* " if ((HAL_ADC_GetState(hadc1) & HAL_ADC_STATE_AWD1) != 0UL) " */
1628 /* " if ((HAL_ADC_GetState(hadc1) & HAL_ADC_STATE_AWD2) != 0UL) " */
1629 /* " if ((HAL_ADC_GetState(hadc1) & HAL_ADC_STATE_AWD3) != 0UL) " */
1631 /* Check analog watchdog 1 flag */
1634 SET_BIT(hadc
->State
, HAL_ADC_STATE_AWD1
);
1636 /* Clear ADC analog watchdog flag */
1637 __HAL_ADC_CLEAR_FLAG(hadc
, ADC_FLAG_AWD1
);
1641 /* Check analog watchdog 2 flag */
1642 case ADC_AWD2_EVENT
:
1644 SET_BIT(hadc
->State
, HAL_ADC_STATE_AWD2
);
1646 /* Clear ADC analog watchdog flag */
1647 __HAL_ADC_CLEAR_FLAG(hadc
, ADC_FLAG_AWD2
);
1651 /* Check analog watchdog 3 flag */
1652 case ADC_AWD3_EVENT
:
1654 SET_BIT(hadc
->State
, HAL_ADC_STATE_AWD3
);
1656 /* Clear ADC analog watchdog flag */
1657 __HAL_ADC_CLEAR_FLAG(hadc
, ADC_FLAG_AWD3
);
1661 /* Injected context queue overflow event */
1662 case ADC_JQOVF_EVENT
:
1664 SET_BIT(hadc
->State
, HAL_ADC_STATE_INJ_JQOVF
);
1666 /* Set ADC error code to Injected context queue overflow */
1667 SET_BIT(hadc
->ErrorCode
, HAL_ADC_ERROR_JQOVF
);
1669 /* Clear ADC Injected context queue overflow flag */
1670 __HAL_ADC_CLEAR_FLAG(hadc
, ADC_FLAG_JQOVF
);
1675 default: /* Case ADC_OVR_EVENT */
1676 /* If overrun is set to overwrite previous data, overrun event is not */
1677 /* considered as an error. */
1678 /* (cf ref manual "Managing conversions without using the DMA and without */
1680 if (hadc
->Init
.Overrun
== ADC_OVR_DATA_PRESERVED
)
1683 SET_BIT(hadc
->State
, HAL_ADC_STATE_REG_OVR
);
1685 /* Set ADC error code to overrun */
1686 SET_BIT(hadc
->ErrorCode
, HAL_ADC_ERROR_OVR
);
1690 /* Clear ADC Overrun flag only if Overrun is set to ADC_OVR_DATA_OVERWRITTEN
1691 otherwise, data register is potentially overwritten by new converted data as soon
1692 as OVR is cleared. */
1693 __HAL_ADC_CLEAR_FLAG(hadc
, ADC_FLAG_OVR
);
1698 /* Return function status */
1703 * @brief Enable ADC, start conversion of regular group with interruption.
1704 * @note Interruptions enabled in this function according to initialization
1705 * setting : EOC (end of conversion), EOS (end of sequence),
1707 * Each of these interruptions has its dedicated callback function.
1708 * @note Case of multimode enabled (when multimode feature is available):
1709 * HAL_ADC_Start_IT() must be called for ADC Slave first, then for
1711 * For ADC Slave, ADC is enabled only (conversion is not started).
1712 * For ADC Master, ADC is enabled and multimode conversion is started.
1713 * @note To guarantee a proper reset of all interruptions once all the needed
1714 * conversions are obtained, HAL_ADC_Stop_IT() must be called to ensure
1715 * a correct stop of the IT-based conversions.
1716 * @note By default, HAL_ADC_Start_IT() does not enable the End Of Sampling
1717 * interruption. If required (e.g. in case of oversampling with trigger
1718 * mode), the user must:
1719 * 1. first clear the EOSMP flag if set with macro __HAL_ADC_CLEAR_FLAG(hadc, ADC_FLAG_EOSMP)
1720 * 2. then enable the EOSMP interrupt with macro __HAL_ADC_ENABLE_IT(hadc, ADC_IT_EOSMP)
1721 * before calling HAL_ADC_Start_IT().
1722 * @param hadc ADC handle
1723 * @retval HAL status
1725 HAL_StatusTypeDef
HAL_ADC_Start_IT(ADC_HandleTypeDef
*hadc
)
1727 HAL_StatusTypeDef tmp_hal_status
;
1728 const ADC_TypeDef
*tmpADC_Master
;
1729 uint32_t tmp_multimode_config
= LL_ADC_GetMultimode(__LL_ADC_COMMON_INSTANCE(hadc
->Instance
));
1731 /* Check the parameters */
1732 assert_param(IS_ADC_ALL_INSTANCE(hadc
->Instance
));
1734 /* Perform ADC enable and conversion start if no conversion is on going */
1735 if (LL_ADC_REG_IsConversionOngoing(hadc
->Instance
) == 0UL)
1737 /* Process locked */
1740 /* Enable the ADC peripheral */
1741 tmp_hal_status
= ADC_Enable(hadc
);
1743 /* Start conversion if ADC is effectively enabled */
1744 if (tmp_hal_status
== HAL_OK
)
1747 /* - Clear state bitfield related to regular group conversion results */
1748 /* - Set state bitfield related to regular operation */
1749 ADC_STATE_CLR_SET(hadc
->State
,
1750 HAL_ADC_STATE_READY
| HAL_ADC_STATE_REG_EOC
| HAL_ADC_STATE_REG_OVR
| HAL_ADC_STATE_REG_EOSMP
,
1751 HAL_ADC_STATE_REG_BUSY
);
1753 /* Reset HAL_ADC_STATE_MULTIMODE_SLAVE bit
1754 - if ADC instance is master or if multimode feature is not available
1755 - if multimode setting is disabled (ADC instance slave in independent mode) */
1756 if ((__LL_ADC_MULTI_INSTANCE_MASTER(hadc
->Instance
) == hadc
->Instance
)
1757 || (tmp_multimode_config
== LL_ADC_MULTI_INDEPENDENT
)
1760 CLEAR_BIT(hadc
->State
, HAL_ADC_STATE_MULTIMODE_SLAVE
);
1763 /* Set ADC error code */
1764 /* Check if a conversion is on going on ADC group injected */
1765 if ((hadc
->State
& HAL_ADC_STATE_INJ_BUSY
) != 0UL)
1767 /* Reset ADC error code fields related to regular conversions only */
1768 CLEAR_BIT(hadc
->ErrorCode
, (HAL_ADC_ERROR_OVR
| HAL_ADC_ERROR_DMA
));
1772 /* Reset all ADC error code fields */
1773 ADC_CLEAR_ERRORCODE(hadc
);
1776 /* Clear ADC group regular conversion flag and overrun flag */
1777 /* (To ensure of no unknown state from potential previous ADC operations) */
1778 __HAL_ADC_CLEAR_FLAG(hadc
, (ADC_FLAG_EOC
| ADC_FLAG_EOS
| ADC_FLAG_OVR
));
1780 /* Process unlocked */
1781 /* Unlock before starting ADC conversions: in case of potential */
1782 /* interruption, to let the process to ADC IRQ Handler. */
1785 /* Disable all interruptions before enabling the desired ones */
1786 __HAL_ADC_DISABLE_IT(hadc
, (ADC_IT_EOC
| ADC_IT_EOS
| ADC_IT_OVR
));
1788 /* Enable ADC end of conversion interrupt */
1789 switch (hadc
->Init
.EOCSelection
)
1791 case ADC_EOC_SEQ_CONV
:
1792 __HAL_ADC_ENABLE_IT(hadc
, ADC_IT_EOS
);
1794 /* case ADC_EOC_SINGLE_CONV */
1796 __HAL_ADC_ENABLE_IT(hadc
, ADC_IT_EOC
);
1800 /* Enable ADC overrun interrupt */
1801 /* If hadc->Init.Overrun is set to ADC_OVR_DATA_PRESERVED, only then is
1802 ADC_IT_OVR enabled; otherwise data overwrite is considered as normal
1803 behavior and no CPU time is lost for a non-processed interruption */
1804 if (hadc
->Init
.Overrun
== ADC_OVR_DATA_PRESERVED
)
1806 __HAL_ADC_ENABLE_IT(hadc
, ADC_IT_OVR
);
1809 /* Enable conversion of regular group. */
1810 /* If software start has been selected, conversion starts immediately. */
1811 /* If external trigger has been selected, conversion will start at next */
1812 /* trigger event. */
1813 /* Case of multimode enabled (when multimode feature is available): */
1814 /* - if ADC is slave and dual regular conversions are enabled, ADC is */
1815 /* enabled only (conversion is not started), */
1816 /* - if ADC is master, ADC is enabled and conversion is started. */
1817 if ((__LL_ADC_MULTI_INSTANCE_MASTER(hadc
->Instance
) == hadc
->Instance
)
1818 || (tmp_multimode_config
== LL_ADC_MULTI_INDEPENDENT
)
1819 || (tmp_multimode_config
== LL_ADC_MULTI_DUAL_INJ_SIMULT
)
1820 || (tmp_multimode_config
== LL_ADC_MULTI_DUAL_INJ_ALTERN
)
1823 /* ADC instance is not a multimode slave instance with multimode regular conversions enabled */
1824 if (READ_BIT(hadc
->Instance
->CFGR
, ADC_CFGR_JAUTO
) != 0UL)
1826 ADC_STATE_CLR_SET(hadc
->State
, HAL_ADC_STATE_INJ_EOC
, HAL_ADC_STATE_INJ_BUSY
);
1828 /* Enable as well injected interruptions in case
1829 HAL_ADCEx_InjectedStart_IT() has not been called beforehand. This
1830 allows to start regular and injected conversions when JAUTO is
1831 set with a single call to HAL_ADC_Start_IT() */
1832 switch (hadc
->Init
.EOCSelection
)
1834 case ADC_EOC_SEQ_CONV
:
1835 __HAL_ADC_DISABLE_IT(hadc
, ADC_IT_JEOC
);
1836 __HAL_ADC_ENABLE_IT(hadc
, ADC_IT_JEOS
);
1838 /* case ADC_EOC_SINGLE_CONV */
1840 __HAL_ADC_DISABLE_IT(hadc
, ADC_IT_JEOS
);
1841 __HAL_ADC_ENABLE_IT(hadc
, ADC_IT_JEOC
);
1846 /* Start ADC group regular conversion */
1847 LL_ADC_REG_StartConversion(hadc
->Instance
);
1851 /* ADC instance is a multimode slave instance with multimode regular conversions enabled */
1852 SET_BIT(hadc
->State
, HAL_ADC_STATE_MULTIMODE_SLAVE
);
1853 /* if Master ADC JAUTO bit is set, Slave injected interruptions
1854 are enabled nevertheless (for same reason as above) */
1855 tmpADC_Master
= __LL_ADC_MULTI_INSTANCE_MASTER(hadc
->Instance
);
1856 if (READ_BIT(tmpADC_Master
->CFGR
, ADC_CFGR_JAUTO
) != 0UL)
1858 /* First, update Slave State in setting HAL_ADC_STATE_INJ_BUSY bit
1859 and in resetting HAL_ADC_STATE_INJ_EOC bit */
1860 ADC_STATE_CLR_SET(hadc
->State
, HAL_ADC_STATE_INJ_EOC
, HAL_ADC_STATE_INJ_BUSY
);
1861 /* Next, set Slave injected interruptions */
1862 switch (hadc
->Init
.EOCSelection
)
1864 case ADC_EOC_SEQ_CONV
:
1865 __HAL_ADC_DISABLE_IT(hadc
, ADC_IT_JEOC
);
1866 __HAL_ADC_ENABLE_IT(hadc
, ADC_IT_JEOS
);
1868 /* case ADC_EOC_SINGLE_CONV */
1870 __HAL_ADC_DISABLE_IT(hadc
, ADC_IT_JEOS
);
1871 __HAL_ADC_ENABLE_IT(hadc
, ADC_IT_JEOC
);
1879 /* Process unlocked */
1886 tmp_hal_status
= HAL_BUSY
;
1889 /* Return function status */
1890 return tmp_hal_status
;
1894 * @brief Stop ADC conversion of regular group (and injected group in
1895 * case of auto_injection mode), disable interrution of
1896 * end-of-conversion, disable ADC peripheral.
1897 * @param hadc ADC handle
1898 * @retval HAL status.
1900 HAL_StatusTypeDef
HAL_ADC_Stop_IT(ADC_HandleTypeDef
*hadc
)
1902 HAL_StatusTypeDef tmp_hal_status
;
1904 /* Check the parameters */
1905 assert_param(IS_ADC_ALL_INSTANCE(hadc
->Instance
));
1907 /* Process locked */
1910 /* 1. Stop potential conversion on going, on ADC groups regular and injected */
1911 tmp_hal_status
= ADC_ConversionStop(hadc
, ADC_REGULAR_INJECTED_GROUP
);
1913 /* Disable ADC peripheral if conversions are effectively stopped */
1914 if (tmp_hal_status
== HAL_OK
)
1916 /* Disable ADC end of conversion interrupt for regular group */
1917 /* Disable ADC overrun interrupt */
1918 __HAL_ADC_DISABLE_IT(hadc
, (ADC_IT_EOC
| ADC_IT_EOS
| ADC_IT_OVR
));
1920 /* 2. Disable the ADC peripheral */
1921 tmp_hal_status
= ADC_Disable(hadc
);
1923 /* Check if ADC is effectively disabled */
1924 if (tmp_hal_status
== HAL_OK
)
1927 ADC_STATE_CLR_SET(hadc
->State
,
1928 HAL_ADC_STATE_REG_BUSY
| HAL_ADC_STATE_INJ_BUSY
,
1929 HAL_ADC_STATE_READY
);
1933 /* Process unlocked */
1936 /* Return function status */
1937 return tmp_hal_status
;
1941 * @brief Enable ADC, start conversion of regular group and transfer result through DMA.
1942 * @note Interruptions enabled in this function:
1943 * overrun (if applicable), DMA half transfer, DMA transfer complete.
1944 * Each of these interruptions has its dedicated callback function.
1945 * @note Case of multimode enabled (when multimode feature is available): HAL_ADC_Start_DMA()
1946 * is designed for single-ADC mode only. For multimode, the dedicated
1947 * HAL_ADCEx_MultiModeStart_DMA() function must be used.
1948 * @param hadc ADC handle
1949 * @param pData Destination Buffer address.
1950 * @param Length Number of data to be transferred from ADC peripheral to memory
1951 * @retval HAL status.
1953 HAL_StatusTypeDef
HAL_ADC_Start_DMA(ADC_HandleTypeDef
*hadc
, uint32_t *pData
, uint32_t Length
)
1955 HAL_StatusTypeDef tmp_hal_status
;
1956 uint32_t tmp_multimode_config
= LL_ADC_GetMultimode(__LL_ADC_COMMON_INSTANCE(hadc
->Instance
));
1958 /* Check the parameters */
1959 assert_param(IS_ADC_ALL_INSTANCE(hadc
->Instance
));
1961 /* Perform ADC enable and conversion start if no conversion is on going */
1962 if (LL_ADC_REG_IsConversionOngoing(hadc
->Instance
) == 0UL)
1964 /* Process locked */
1967 /* Ensure that multimode regular conversions are not enabled. */
1968 /* Otherwise, dedicated API HAL_ADCEx_MultiModeStart_DMA() must be used. */
1969 if ((tmp_multimode_config
== LL_ADC_MULTI_INDEPENDENT
)
1970 || (tmp_multimode_config
== LL_ADC_MULTI_DUAL_INJ_SIMULT
)
1971 || (tmp_multimode_config
== LL_ADC_MULTI_DUAL_INJ_ALTERN
)
1974 /* Enable the ADC peripheral */
1975 tmp_hal_status
= ADC_Enable(hadc
);
1977 /* Start conversion if ADC is effectively enabled */
1978 if (tmp_hal_status
== HAL_OK
)
1981 /* - Clear state bitfield related to regular group conversion results */
1982 /* - Set state bitfield related to regular operation */
1983 ADC_STATE_CLR_SET(hadc
->State
,
1984 HAL_ADC_STATE_READY
| HAL_ADC_STATE_REG_EOC
| HAL_ADC_STATE_REG_OVR
| HAL_ADC_STATE_REG_EOSMP
,
1985 HAL_ADC_STATE_REG_BUSY
);
1987 /* Reset HAL_ADC_STATE_MULTIMODE_SLAVE bit
1988 - if ADC instance is master or if multimode feature is not available
1989 - if multimode setting is disabled (ADC instance slave in independent mode) */
1990 if ((__LL_ADC_MULTI_INSTANCE_MASTER(hadc
->Instance
) == hadc
->Instance
)
1991 || (tmp_multimode_config
== LL_ADC_MULTI_INDEPENDENT
)
1994 CLEAR_BIT(hadc
->State
, HAL_ADC_STATE_MULTIMODE_SLAVE
);
1997 /* Check if a conversion is on going on ADC group injected */
1998 if ((hadc
->State
& HAL_ADC_STATE_INJ_BUSY
) != 0UL)
2000 /* Reset ADC error code fields related to regular conversions only */
2001 CLEAR_BIT(hadc
->ErrorCode
, (HAL_ADC_ERROR_OVR
| HAL_ADC_ERROR_DMA
));
2005 /* Reset all ADC error code fields */
2006 ADC_CLEAR_ERRORCODE(hadc
);
2009 /* Set the DMA transfer complete callback */
2010 hadc
->DMA_Handle
->XferCpltCallback
= ADC_DMAConvCplt
;
2012 /* Set the DMA half transfer complete callback */
2013 hadc
->DMA_Handle
->XferHalfCpltCallback
= ADC_DMAHalfConvCplt
;
2015 /* Set the DMA error callback */
2016 hadc
->DMA_Handle
->XferErrorCallback
= ADC_DMAError
;
2019 /* Manage ADC and DMA start: ADC overrun interruption, DMA start, */
2020 /* ADC start (in case of SW start): */
2022 /* Clear regular group conversion flag and overrun flag */
2023 /* (To ensure of no unknown state from potential previous ADC */
2025 __HAL_ADC_CLEAR_FLAG(hadc
, (ADC_FLAG_EOC
| ADC_FLAG_EOS
| ADC_FLAG_OVR
));
2027 /* Process unlocked */
2028 /* Unlock before starting ADC conversions: in case of potential */
2029 /* interruption, to let the process to ADC IRQ Handler. */
2032 /* With DMA, overrun event is always considered as an error even if
2033 hadc->Init.Overrun is set to ADC_OVR_DATA_OVERWRITTEN. Therefore,
2034 ADC_IT_OVR is enabled. */
2035 __HAL_ADC_ENABLE_IT(hadc
, ADC_IT_OVR
);
2037 /* Enable ADC DMA mode*/
2038 LL_ADC_REG_SetDataTransferMode(hadc
->Instance
, (uint32_t)hadc
->Init
.ConversionDataManagement
);
2040 /* Start the DMA channel */
2041 tmp_hal_status
= HAL_DMA_Start_IT(hadc
->DMA_Handle
, (uint32_t)&hadc
->Instance
->DR
, (uint32_t)pData
, Length
);
2043 /* Enable conversion of regular group. */
2044 /* If software start has been selected, conversion starts immediately. */
2045 /* If external trigger has been selected, conversion will start at next */
2046 /* trigger event. */
2047 /* Start ADC group regular conversion */
2048 LL_ADC_REG_StartConversion(hadc
->Instance
);
2052 /* Process unlocked */
2059 tmp_hal_status
= HAL_ERROR
;
2060 /* Process unlocked */
2066 tmp_hal_status
= HAL_BUSY
;
2069 /* Return function status */
2070 return tmp_hal_status
;
2074 * @brief Stop ADC conversion of regular group (and injected group in
2075 * case of auto_injection mode), disable ADC DMA transfer, disable
2077 * @note: ADC peripheral disable is forcing stop of potential
2078 * conversion on ADC group injected. If ADC group injected is under use, it
2079 * should be preliminarily stopped using HAL_ADCEx_InjectedStop function.
2080 * @note Case of multimode enabled (when multimode feature is available):
2081 * HAL_ADC_Stop_DMA() function is dedicated to single-ADC mode only.
2082 * For multimode, the dedicated HAL_ADCEx_MultiModeStop_DMA() API must be used.
2083 * @param hadc ADC handle
2084 * @retval HAL status.
2086 HAL_StatusTypeDef
HAL_ADC_Stop_DMA(ADC_HandleTypeDef
*hadc
)
2088 HAL_StatusTypeDef tmp_hal_status
;
2090 /* Check the parameters */
2091 assert_param(IS_ADC_ALL_INSTANCE(hadc
->Instance
));
2093 /* Process locked */
2096 /* 1. Stop potential ADC group regular conversion on going */
2097 tmp_hal_status
= ADC_ConversionStop(hadc
, ADC_REGULAR_INJECTED_GROUP
);
2099 /* Disable ADC peripheral if conversions are effectively stopped */
2100 if (tmp_hal_status
== HAL_OK
)
2102 /* Disable ADC DMA (ADC DMA configuration of continous requests is kept) */
2103 MODIFY_REG(hadc
->Instance
->CFGR
, ADC_CFGR_DMNGT_0
|ADC_CFGR_DMNGT_1
, 0UL);
2105 /* Disable the DMA channel (in case of DMA in circular mode or stop */
2106 /* while DMA transfer is on going) */
2107 if (hadc
->DMA_Handle
->State
== HAL_DMA_STATE_BUSY
)
2109 tmp_hal_status
= HAL_DMA_Abort(hadc
->DMA_Handle
);
2111 /* Check if DMA channel effectively disabled */
2112 if (tmp_hal_status
!= HAL_OK
)
2114 /* Update ADC state machine to error */
2115 SET_BIT(hadc
->State
, HAL_ADC_STATE_ERROR_DMA
);
2119 /* Disable ADC overrun interrupt */
2120 __HAL_ADC_DISABLE_IT(hadc
, ADC_IT_OVR
);
2122 /* 2. Disable the ADC peripheral */
2123 /* Update "tmp_hal_status" only if DMA channel disabling passed, */
2124 /* to keep in memory a potential failing status. */
2125 if (tmp_hal_status
== HAL_OK
)
2127 tmp_hal_status
= ADC_Disable(hadc
);
2131 (void)ADC_Disable(hadc
);
2134 /* Check if ADC is effectively disabled */
2135 if (tmp_hal_status
== HAL_OK
)
2138 ADC_STATE_CLR_SET(hadc
->State
,
2139 HAL_ADC_STATE_REG_BUSY
| HAL_ADC_STATE_INJ_BUSY
,
2140 HAL_ADC_STATE_READY
);
2145 /* Process unlocked */
2148 /* Return function status */
2149 return tmp_hal_status
;
2153 * @brief Get ADC regular group conversion result.
2154 * @note Reading register DR automatically clears ADC flag EOC
2155 * (ADC group regular end of unitary conversion).
2156 * @note This function does not clear ADC flag EOS
2157 * (ADC group regular end of sequence conversion).
2158 * Occurrence of flag EOS rising:
2159 * - If sequencer is composed of 1 rank, flag EOS is equivalent
2161 * - If sequencer is composed of several ranks, during the scan
2162 * sequence flag EOC only is raised, at the end of the scan sequence
2163 * both flags EOC and EOS are raised.
2164 * To clear this flag, either use function:
2165 * in programming model IT: @ref HAL_ADC_IRQHandler(), in programming
2166 * model polling: @ref HAL_ADC_PollForConversion()
2167 * or @ref __HAL_ADC_CLEAR_FLAG(&hadc, ADC_FLAG_EOS).
2168 * @param hadc ADC handle
2169 * @retval ADC group regular conversion data
2171 uint32_t HAL_ADC_GetValue(ADC_HandleTypeDef
*hadc
)
2173 /* Check the parameters */
2174 assert_param(IS_ADC_ALL_INSTANCE(hadc
->Instance
));
2176 /* Note: EOC flag is not cleared here by software because automatically */
2177 /* cleared by hardware when reading register DR. */
2179 /* Return ADC converted value */
2180 return hadc
->Instance
->DR
;
2184 * @brief Handle ADC interrupt request.
2185 * @param hadc ADC handle
2188 void HAL_ADC_IRQHandler(ADC_HandleTypeDef
*hadc
)
2190 uint32_t overrun_error
= 0UL; /* flag set if overrun occurrence has to be considered as an error */
2191 uint32_t tmp_isr
= hadc
->Instance
->ISR
;
2192 uint32_t tmp_ier
= hadc
->Instance
->IER
;
2193 uint32_t tmp_adc_inj_is_trigger_source_sw_start
;
2194 uint32_t tmp_adc_reg_is_trigger_source_sw_start
;
2196 const ADC_TypeDef
*tmpADC_Master
;
2197 uint32_t tmp_multimode_config
= LL_ADC_GetMultimode(__LL_ADC_COMMON_INSTANCE(hadc
->Instance
));
2199 /* Check the parameters */
2200 assert_param(IS_ADC_ALL_INSTANCE(hadc
->Instance
));
2201 assert_param(IS_ADC_EOC_SELECTION(hadc
->Init
.EOCSelection
));
2203 /* ========== Check End of Sampling flag for ADC group regular ========== */
2204 if (((tmp_isr
& ADC_FLAG_EOSMP
) == ADC_FLAG_EOSMP
) && ((tmp_ier
& ADC_IT_EOSMP
) == ADC_IT_EOSMP
))
2206 /* Update state machine on end of sampling status if not in error state */
2207 if ((hadc
->State
& HAL_ADC_STATE_ERROR_INTERNAL
) == 0UL)
2210 SET_BIT(hadc
->State
, HAL_ADC_STATE_REG_EOSMP
);
2213 /* End Of Sampling callback */
2214 #if (USE_HAL_ADC_REGISTER_CALLBACKS == 1)
2215 hadc
->EndOfSamplingCallback(hadc
);
2217 HAL_ADCEx_EndOfSamplingCallback(hadc
);
2218 #endif /* USE_HAL_ADC_REGISTER_CALLBACKS */
2220 /* Clear regular group conversion flag */
2221 __HAL_ADC_CLEAR_FLAG(hadc
, ADC_FLAG_EOSMP
);
2224 /* ====== Check ADC group regular end of unitary conversion sequence conversions ===== */
2225 if ((((tmp_isr
& ADC_FLAG_EOC
) == ADC_FLAG_EOC
) && ((tmp_ier
& ADC_IT_EOC
) == ADC_IT_EOC
)) ||
2226 (((tmp_isr
& ADC_FLAG_EOS
) == ADC_FLAG_EOS
) && ((tmp_ier
& ADC_IT_EOS
) == ADC_IT_EOS
)))
2228 /* Update state machine on conversion status if not in error state */
2229 if ((hadc
->State
& HAL_ADC_STATE_ERROR_INTERNAL
) == 0UL)
2232 SET_BIT(hadc
->State
, HAL_ADC_STATE_REG_EOC
);
2235 /* Determine whether any further conversion upcoming on group regular */
2236 /* by external trigger, continuous mode or scan sequence on going */
2237 /* to disable interruption. */
2238 if (LL_ADC_REG_IsTriggerSourceSWStart(hadc
->Instance
) != 0UL)
2240 /* Get relevant register CFGR in ADC instance of ADC master or slave */
2241 /* in function of multimode state (for devices with multimode */
2243 if ((__LL_ADC_MULTI_INSTANCE_MASTER(hadc
->Instance
) == hadc
->Instance
)
2244 || (tmp_multimode_config
== LL_ADC_MULTI_INDEPENDENT
)
2245 || (tmp_multimode_config
== LL_ADC_MULTI_DUAL_INJ_SIMULT
)
2246 || (tmp_multimode_config
== LL_ADC_MULTI_DUAL_INJ_ALTERN
)
2249 /* check CONT bit directly in handle ADC CFGR register */
2250 tmp_cfgr
= READ_REG(hadc
->Instance
->CFGR
);
2254 /* else need to check Master ADC CONT bit */
2255 tmpADC_Master
= __LL_ADC_MULTI_INSTANCE_MASTER(hadc
->Instance
);
2256 tmp_cfgr
= READ_REG(tmpADC_Master
->CFGR
);
2259 /* Carry on if continuous mode is disabled */
2260 if (READ_BIT(tmp_cfgr
, ADC_CFGR_CONT
) != ADC_CFGR_CONT
)
2262 /* If End of Sequence is reached, disable interrupts */
2263 if (__HAL_ADC_GET_FLAG(hadc
, ADC_FLAG_EOS
))
2265 /* Allowed to modify bits ADC_IT_EOC/ADC_IT_EOS only if bit */
2266 /* ADSTART==0 (no conversion on going) */
2267 if (LL_ADC_REG_IsConversionOngoing(hadc
->Instance
) == 0UL)
2269 /* Disable ADC end of sequence conversion interrupt */
2270 /* Note: Overrun interrupt was enabled with EOC interrupt in */
2271 /* HAL_Start_IT(), but is not disabled here because can be used */
2272 /* by overrun IRQ process below. */
2273 __HAL_ADC_DISABLE_IT(hadc
, ADC_IT_EOC
| ADC_IT_EOS
);
2276 CLEAR_BIT(hadc
->State
, HAL_ADC_STATE_REG_BUSY
);
2278 if ((hadc
->State
& HAL_ADC_STATE_INJ_BUSY
) == 0UL)
2280 SET_BIT(hadc
->State
, HAL_ADC_STATE_READY
);
2285 /* Change ADC state to error state */
2286 SET_BIT(hadc
->State
, HAL_ADC_STATE_ERROR_INTERNAL
);
2288 /* Set ADC error code to ADC peripheral internal error */
2289 SET_BIT(hadc
->ErrorCode
, HAL_ADC_ERROR_INTERNAL
);
2295 /* Conversion complete callback */
2296 /* Note: Into callback function "HAL_ADC_ConvCpltCallback()", */
2297 /* to determine if conversion has been triggered from EOC or EOS, */
2298 /* possibility to use: */
2299 /* " if( __HAL_ADC_GET_FLAG(&hadc, ADC_FLAG_EOS)) " */
2300 #if (USE_HAL_ADC_REGISTER_CALLBACKS == 1)
2301 hadc
->ConvCpltCallback(hadc
);
2303 HAL_ADC_ConvCpltCallback(hadc
);
2304 #endif /* USE_HAL_ADC_REGISTER_CALLBACKS */
2306 /* Clear regular group conversion flag */
2307 /* Note: in case of overrun set to ADC_OVR_DATA_PRESERVED, end of */
2308 /* conversion flags clear induces the release of the preserved data.*/
2309 /* Therefore, if the preserved data value is needed, it must be */
2310 /* read preliminarily into HAL_ADC_ConvCpltCallback(). */
2311 __HAL_ADC_CLEAR_FLAG(hadc
, (ADC_FLAG_EOC
| ADC_FLAG_EOS
));
2314 /* ====== Check ADC group injected end of unitary conversion sequence conversions ===== */
2315 if ((((tmp_isr
& ADC_FLAG_JEOC
) == ADC_FLAG_JEOC
) && ((tmp_ier
& ADC_IT_JEOC
) == ADC_IT_JEOC
)) ||
2316 (((tmp_isr
& ADC_FLAG_JEOS
) == ADC_FLAG_JEOS
) && ((tmp_ier
& ADC_IT_JEOS
) == ADC_IT_JEOS
)))
2318 /* Update state machine on conversion status if not in error state */
2319 if ((hadc
->State
& HAL_ADC_STATE_ERROR_INTERNAL
) == 0UL)
2322 SET_BIT(hadc
->State
, HAL_ADC_STATE_INJ_EOC
);
2325 /* Retrieve ADC configuration */
2326 tmp_adc_inj_is_trigger_source_sw_start
= LL_ADC_INJ_IsTriggerSourceSWStart(hadc
->Instance
);
2327 tmp_adc_reg_is_trigger_source_sw_start
= LL_ADC_REG_IsTriggerSourceSWStart(hadc
->Instance
);
2328 /* Get relevant register CFGR in ADC instance of ADC master or slave */
2329 /* in function of multimode state (for devices with multimode */
2331 if ((__LL_ADC_MULTI_INSTANCE_MASTER(hadc
->Instance
) == hadc
->Instance
)
2332 || (tmp_multimode_config
== LL_ADC_MULTI_INDEPENDENT
)
2333 || (tmp_multimode_config
== LL_ADC_MULTI_DUAL_REG_SIMULT
)
2334 || (tmp_multimode_config
== LL_ADC_MULTI_DUAL_REG_INTERL
)
2337 tmp_cfgr
= READ_REG(hadc
->Instance
->CFGR
);
2341 tmpADC_Master
= __LL_ADC_MULTI_INSTANCE_MASTER(hadc
->Instance
);
2342 tmp_cfgr
= READ_REG(tmpADC_Master
->CFGR
);
2345 /* Disable interruption if no further conversion upcoming by injected */
2346 /* external trigger or by automatic injected conversion with regular */
2347 /* group having no further conversion upcoming (same conditions as */
2348 /* regular group interruption disabling above), */
2349 /* and if injected scan sequence is completed. */
2350 if ((tmp_adc_inj_is_trigger_source_sw_start
!= 0UL) ||
2351 ((READ_BIT(tmp_cfgr
, ADC_CFGR_JAUTO
) == 0UL) &&
2352 ((tmp_adc_reg_is_trigger_source_sw_start
!= 0UL) &&
2353 (READ_BIT(tmp_cfgr
, ADC_CFGR_CONT
) == 0UL))))
2355 /* If End of Sequence is reached, disable interrupts */
2356 if (__HAL_ADC_GET_FLAG(hadc
, ADC_FLAG_JEOS
))
2358 /* Particular case if injected contexts queue is enabled: */
2359 /* when the last context has been fully processed, JSQR is reset */
2360 /* by the hardware. Even if no injected conversion is planned to come */
2361 /* (queue empty, triggers are ignored), it can start again */
2362 /* immediately after setting a new context (JADSTART is still set). */
2363 /* Therefore, state of HAL ADC injected group is kept to busy. */
2364 if (READ_BIT(tmp_cfgr
, ADC_CFGR_JQM
) == 0UL)
2366 /* Allowed to modify bits ADC_IT_JEOC/ADC_IT_JEOS only if bit */
2367 /* JADSTART==0 (no conversion on going) */
2368 if (LL_ADC_INJ_IsConversionOngoing(hadc
->Instance
) == 0UL)
2370 /* Disable ADC end of sequence conversion interrupt */
2371 __HAL_ADC_DISABLE_IT(hadc
, ADC_IT_JEOC
| ADC_IT_JEOS
);
2374 CLEAR_BIT(hadc
->State
, HAL_ADC_STATE_INJ_BUSY
);
2376 if ((hadc
->State
& HAL_ADC_STATE_REG_BUSY
) == 0UL)
2378 SET_BIT(hadc
->State
, HAL_ADC_STATE_READY
);
2383 /* Update ADC state machine to error */
2384 SET_BIT(hadc
->State
, HAL_ADC_STATE_ERROR_INTERNAL
);
2386 /* Set ADC error code to ADC peripheral internal error */
2387 SET_BIT(hadc
->ErrorCode
, HAL_ADC_ERROR_INTERNAL
);
2393 /* Injected Conversion complete callback */
2394 /* Note: HAL_ADCEx_InjectedConvCpltCallback can resort to
2395 if( __HAL_ADC_GET_FLAG(&hadc, ADC_FLAG_JEOS)) or
2396 if( __HAL_ADC_GET_FLAG(&hadc, ADC_FLAG_JEOC)) to determine whether
2397 interruption has been triggered by end of conversion or end of
2399 #if (USE_HAL_ADC_REGISTER_CALLBACKS == 1)
2400 hadc
->InjectedConvCpltCallback(hadc
);
2402 HAL_ADCEx_InjectedConvCpltCallback(hadc
);
2403 #endif /* USE_HAL_ADC_REGISTER_CALLBACKS */
2405 /* Clear injected group conversion flag */
2406 __HAL_ADC_CLEAR_FLAG(hadc
, ADC_FLAG_JEOC
| ADC_FLAG_JEOS
);
2409 /* ========== Check Analog watchdog 1 flag ========== */
2410 if (((tmp_isr
& ADC_FLAG_AWD1
) == ADC_FLAG_AWD1
) && ((tmp_ier
& ADC_IT_AWD1
) == ADC_IT_AWD1
))
2413 SET_BIT(hadc
->State
, HAL_ADC_STATE_AWD1
);
2415 /* Level out of window 1 callback */
2416 #if (USE_HAL_ADC_REGISTER_CALLBACKS == 1)
2417 hadc
->LevelOutOfWindowCallback(hadc
);
2419 HAL_ADC_LevelOutOfWindowCallback(hadc
);
2420 #endif /* USE_HAL_ADC_REGISTER_CALLBACKS */
2422 /* Clear ADC analog watchdog flag */
2423 __HAL_ADC_CLEAR_FLAG(hadc
, ADC_FLAG_AWD1
);
2426 /* ========== Check analog watchdog 2 flag ========== */
2427 if (((tmp_isr
& ADC_FLAG_AWD2
) == ADC_FLAG_AWD2
) && ((tmp_ier
& ADC_IT_AWD2
) == ADC_IT_AWD2
))
2430 SET_BIT(hadc
->State
, HAL_ADC_STATE_AWD2
);
2432 /* Level out of window 2 callback */
2433 #if (USE_HAL_ADC_REGISTER_CALLBACKS == 1)
2434 hadc
->LevelOutOfWindow2Callback(hadc
);
2436 HAL_ADCEx_LevelOutOfWindow2Callback(hadc
);
2437 #endif /* USE_HAL_ADC_REGISTER_CALLBACKS */
2439 /* Clear ADC analog watchdog flag */
2440 __HAL_ADC_CLEAR_FLAG(hadc
, ADC_FLAG_AWD2
);
2443 /* ========== Check analog watchdog 3 flag ========== */
2444 if (((tmp_isr
& ADC_FLAG_AWD3
) == ADC_FLAG_AWD3
) && ((tmp_ier
& ADC_IT_AWD3
) == ADC_IT_AWD3
))
2447 SET_BIT(hadc
->State
, HAL_ADC_STATE_AWD3
);
2449 /* Level out of window 3 callback */
2450 #if (USE_HAL_ADC_REGISTER_CALLBACKS == 1)
2451 hadc
->LevelOutOfWindow3Callback(hadc
);
2453 HAL_ADCEx_LevelOutOfWindow3Callback(hadc
);
2454 #endif /* USE_HAL_ADC_REGISTER_CALLBACKS */
2456 /* Clear ADC analog watchdog flag */
2457 __HAL_ADC_CLEAR_FLAG(hadc
, ADC_FLAG_AWD3
);
2460 /* ========== Check Overrun flag ========== */
2461 if (((tmp_isr
& ADC_FLAG_OVR
) == ADC_FLAG_OVR
) && ((tmp_ier
& ADC_IT_OVR
) == ADC_IT_OVR
))
2463 /* If overrun is set to overwrite previous data (default setting), */
2464 /* overrun event is not considered as an error. */
2465 /* (cf ref manual "Managing conversions without using the DMA and without */
2467 /* Exception for usage with DMA overrun event always considered as an */
2469 if (hadc
->Init
.Overrun
== ADC_OVR_DATA_PRESERVED
)
2471 overrun_error
= 1UL;
2475 /* Check DMA configuration */
2476 if (tmp_multimode_config
!= LL_ADC_MULTI_INDEPENDENT
)
2478 /* Multimode (when feature is available) is enabled,
2479 Common Control Register MDMA bits must be checked. */
2480 if (LL_ADC_GetMultiDMATransfer(__LL_ADC_COMMON_INSTANCE(hadc
->Instance
)) != LL_ADC_MULTI_REG_DMA_EACH_ADC
)
2482 overrun_error
= 1UL;
2487 /* Multimode not set or feature not available or ADC independent */
2488 if ((hadc
->Instance
->CFGR
& ADC_CFGR_DMNGT
) != 0UL)
2490 overrun_error
= 1UL;
2495 if (overrun_error
== 1UL)
2497 /* Change ADC state to error state */
2498 SET_BIT(hadc
->State
, HAL_ADC_STATE_REG_OVR
);
2500 /* Set ADC error code to overrun */
2501 SET_BIT(hadc
->ErrorCode
, HAL_ADC_ERROR_OVR
);
2503 /* Error callback */
2504 /* Note: In case of overrun, ADC conversion data is preserved until */
2505 /* flag OVR is reset. */
2506 /* Therefore, old ADC conversion data can be retrieved in */
2507 /* function "HAL_ADC_ErrorCallback()". */
2508 #if (USE_HAL_ADC_REGISTER_CALLBACKS == 1)
2509 hadc
->ErrorCallback(hadc
);
2511 HAL_ADC_ErrorCallback(hadc
);
2512 #endif /* USE_HAL_ADC_REGISTER_CALLBACKS */
2515 /* Clear ADC overrun flag */
2516 __HAL_ADC_CLEAR_FLAG(hadc
, ADC_FLAG_OVR
);
2519 /* ========== Check Injected context queue overflow flag ========== */
2520 if (((tmp_isr
& ADC_FLAG_JQOVF
) == ADC_FLAG_JQOVF
) && ((tmp_ier
& ADC_IT_JQOVF
) == ADC_IT_JQOVF
))
2522 /* Change ADC state to overrun state */
2523 SET_BIT(hadc
->State
, HAL_ADC_STATE_INJ_JQOVF
);
2525 /* Set ADC error code to Injected context queue overflow */
2526 SET_BIT(hadc
->ErrorCode
, HAL_ADC_ERROR_JQOVF
);
2528 /* Clear the Injected context queue overflow flag */
2529 __HAL_ADC_CLEAR_FLAG(hadc
, ADC_FLAG_JQOVF
);
2531 /* Injected context queue overflow callback */
2532 #if (USE_HAL_ADC_REGISTER_CALLBACKS == 1)
2533 hadc
->InjectedQueueOverflowCallback(hadc
);
2535 HAL_ADCEx_InjectedQueueOverflowCallback(hadc
);
2536 #endif /* USE_HAL_ADC_REGISTER_CALLBACKS */
2542 * @brief Conversion complete callback in non-blocking mode.
2543 * @param hadc ADC handle
2546 __weak
void HAL_ADC_ConvCpltCallback(ADC_HandleTypeDef
*hadc
)
2548 /* Prevent unused argument(s) compilation warning */
2551 /* NOTE : This function should not be modified. When the callback is needed,
2552 function HAL_ADC_ConvCpltCallback must be implemented in the user file.
2557 * @brief Conversion DMA half-transfer callback in non-blocking mode.
2558 * @param hadc ADC handle
2561 __weak
void HAL_ADC_ConvHalfCpltCallback(ADC_HandleTypeDef
*hadc
)
2563 /* Prevent unused argument(s) compilation warning */
2566 /* NOTE : This function should not be modified. When the callback is needed,
2567 function HAL_ADC_ConvHalfCpltCallback must be implemented in the user file.
2572 * @brief Analog watchdog 1 callback in non-blocking mode.
2573 * @param hadc ADC handle
2576 __weak
void HAL_ADC_LevelOutOfWindowCallback(ADC_HandleTypeDef
*hadc
)
2578 /* Prevent unused argument(s) compilation warning */
2581 /* NOTE : This function should not be modified. When the callback is needed,
2582 function HAL_ADC_LevelOutOfWindowCallback must be implemented in the user file.
2587 * @brief ADC error callback in non-blocking mode
2588 * (ADC conversion with interruption or transfer by DMA).
2589 * @note In case of error due to overrun when using ADC with DMA transfer
2590 * (HAL ADC handle parameter "ErrorCode" to state "HAL_ADC_ERROR_OVR"):
2591 * - Reinitialize the DMA using function "HAL_ADC_Stop_DMA()".
2592 * - If needed, restart a new ADC conversion using function
2593 * "HAL_ADC_Start_DMA()"
2594 * (this function is also clearing overrun flag)
2595 * @param hadc ADC handle
2598 __weak
void HAL_ADC_ErrorCallback(ADC_HandleTypeDef
*hadc
)
2600 /* Prevent unused argument(s) compilation warning */
2603 /* NOTE : This function should not be modified. When the callback is needed,
2604 function HAL_ADC_ErrorCallback must be implemented in the user file.
2612 /** @defgroup ADC_Exported_Functions_Group3 Peripheral Control functions
2613 * @brief Peripheral Control functions
2616 ===============================================================================
2617 ##### Peripheral Control functions #####
2618 ===============================================================================
2619 [..] This section provides functions allowing to:
2620 (+) Configure channels on regular group
2621 (+) Configure the analog watchdog
2628 * @brief Configure a channel to be assigned to ADC group regular.
2629 * @note In case of usage of internal measurement channels:
2630 * Vbat/VrefInt/TempSensor.
2631 * These internal paths can be disabled using function
2633 * @note Possibility to update parameters on the fly:
2634 * This function initializes channel into ADC group regular,
2635 * following calls to this function can be used to reconfigure
2636 * some parameters of structure "ADC_ChannelConfTypeDef" on the fly,
2637 * without resetting the ADC.
2638 * The setting of these parameters is conditioned to ADC state:
2639 * Refer to comments of structure "ADC_ChannelConfTypeDef".
2640 * @param hadc ADC handle
2641 * @param sConfig Structure of ADC channel assigned to ADC group regular.
2642 * @retval HAL status
2644 HAL_StatusTypeDef
HAL_ADC_ConfigChannel(ADC_HandleTypeDef
*hadc
, ADC_ChannelConfTypeDef
*sConfig
)
2646 HAL_StatusTypeDef tmp_hal_status
= HAL_OK
;
2647 uint32_t tmpOffsetShifted
;
2648 uint32_t tmp_config_internal_channel
;
2649 __IO
uint32_t wait_loop_index
= 0;
2650 uint32_t tmp_adc_is_conversion_on_going_regular
;
2651 uint32_t tmp_adc_is_conversion_on_going_injected
;
2653 /* Check the parameters */
2654 assert_param(IS_ADC_ALL_INSTANCE(hadc
->Instance
));
2655 assert_param(IS_ADC_REGULAR_RANK(sConfig
->Rank
));
2656 assert_param(IS_ADC_SAMPLE_TIME(sConfig
->SamplingTime
));
2657 assert_param(IS_ADC_SINGLE_DIFFERENTIAL(sConfig
->SingleDiff
));
2658 assert_param(IS_ADC_OFFSET_NUMBER(sConfig
->OffsetNumber
));
2659 /* Check offset range according to oversampling setting */
2660 if (hadc
->Init
.OversamplingMode
== ENABLE
)
2662 assert_param(IS_ADC_RANGE(ADC_GET_RESOLUTION(hadc
), sConfig
->Offset
/(hadc
->Init
.Oversampling
.Ratio
+1U)));
2666 assert_param(IS_ADC_RANGE(ADC_GET_RESOLUTION(hadc
), sConfig
->Offset
));
2669 /* if ROVSE is set, the value of the OFFSETy_EN bit in ADCx_OFRy register is
2670 ignored (considered as reset) */
2671 assert_param(!((sConfig
->OffsetNumber
!= ADC_OFFSET_NONE
) && (hadc
->Init
.OversamplingMode
== ENABLE
)));
2673 /* Verification of channel number */
2674 if (sConfig
->SingleDiff
!= ADC_DIFFERENTIAL_ENDED
)
2676 assert_param(IS_ADC_CHANNEL(sConfig
->Channel
));
2680 if (hadc
->Instance
== ADC1
)
2682 assert_param(IS_ADC1_DIFF_CHANNEL(sConfig
->Channel
));
2684 if (hadc
->Instance
== ADC2
)
2686 assert_param(IS_ADC2_DIFF_CHANNEL(sConfig
->Channel
));
2689 /* ADC3 is not available on some STM32H7 products */
2690 if (hadc
->Instance
== ADC3
)
2692 assert_param(IS_ADC3_DIFF_CHANNEL(sConfig
->Channel
));
2697 /* Process locked */
2700 /* Parameters update conditioned to ADC state: */
2701 /* Parameters that can be updated when ADC is disabled or enabled without */
2702 /* conversion on going on regular group: */
2703 /* - Channel number */
2704 /* - Channel rank */
2705 if (LL_ADC_REG_IsConversionOngoing(hadc
->Instance
) == 0UL)
2707 /* ADC channels preselection */
2708 hadc
->Instance
->PCSEL
|= (1UL << (__LL_ADC_CHANNEL_TO_DECIMAL_NB((uint32_t)sConfig
->Channel
) & 0x1FUL
));
2710 /* Set ADC group regular sequence: channel on the selected scan sequence rank */
2711 LL_ADC_REG_SetSequencerRanks(hadc
->Instance
, sConfig
->Rank
, sConfig
->Channel
);
2713 /* Parameters update conditioned to ADC state: */
2714 /* Parameters that can be updated when ADC is disabled or enabled without */
2715 /* conversion on going on regular group: */
2716 /* - Channel sampling time */
2717 /* - Channel offset */
2718 tmp_adc_is_conversion_on_going_regular
= LL_ADC_REG_IsConversionOngoing(hadc
->Instance
);
2719 tmp_adc_is_conversion_on_going_injected
= LL_ADC_INJ_IsConversionOngoing(hadc
->Instance
);
2720 if ((tmp_adc_is_conversion_on_going_regular
== 0UL)
2721 && (tmp_adc_is_conversion_on_going_injected
== 0UL)
2724 /* Set sampling time of the selected ADC channel */
2725 LL_ADC_SetChannelSamplingTime(hadc
->Instance
, sConfig
->Channel
, sConfig
->SamplingTime
);
2727 /* Configure the offset: offset enable/disable, channel, offset value */
2729 /* Shift the offset with respect to the selected ADC resolution. */
2730 /* Offset has to be left-aligned on bit 11, the LSB (right bits) are set to 0 */
2731 tmpOffsetShifted
= ADC_OFFSET_SHIFT_RESOLUTION(hadc
, (uint32_t)sConfig
->Offset
);
2733 if (sConfig
->OffsetNumber
!= ADC_OFFSET_NONE
)
2735 /* Set ADC selected offset number */
2736 LL_ADC_SetOffset(hadc
->Instance
, sConfig
->OffsetNumber
, sConfig
->Channel
, tmpOffsetShifted
);
2738 assert_param(IS_FUNCTIONAL_STATE(sConfig
->OffsetSignedSaturation
));
2739 /* Set ADC selected offset signed saturation */
2740 LL_ADC_SetOffsetSignedSaturation(hadc
->Instance
, sConfig
->OffsetNumber
, (sConfig
->OffsetSignedSaturation
== ENABLE
) ? LL_ADC_OFFSET_SIGNED_SATURATION_ENABLE
: LL_ADC_OFFSET_SIGNED_SATURATION_DISABLE
);
2742 assert_param(IS_FUNCTIONAL_STATE(sConfig
->OffsetRightShift
));
2743 /* Set ADC selected offset right shift */
2744 LL_ADC_SetDataRightShift(hadc
->Instance
, sConfig
->OffsetNumber
, (sConfig
->OffsetRightShift
== ENABLE
) ? LL_ADC_OFFSET_RSHIFT_ENABLE
: LL_ADC_OFFSET_RSHIFT_DISABLE
);
2749 /* Scan OFR1, OFR2, OFR3, OFR4 to check if the selected channel is enabled.
2750 If this is the case, offset OFRx is disabled since
2751 sConfig->OffsetNumber = ADC_OFFSET_NONE. */
2752 if (((hadc
->Instance
->OFR1
) & ADC_OFR1_OFFSET1_CH
) == ADC_OFR_CHANNEL(sConfig
->Channel
))
2754 CLEAR_BIT(hadc
->Instance
->OFR1
, ADC_OFR1_SSATE
);
2756 if (((hadc
->Instance
->OFR2
) & ADC_OFR2_OFFSET2_CH
) == ADC_OFR_CHANNEL(sConfig
->Channel
))
2758 CLEAR_BIT(hadc
->Instance
->OFR2
, ADC_OFR2_SSATE
);
2760 if (((hadc
->Instance
->OFR3
) & ADC_OFR3_OFFSET3_CH
) == ADC_OFR_CHANNEL(sConfig
->Channel
))
2762 CLEAR_BIT(hadc
->Instance
->OFR3
, ADC_OFR3_SSATE
);
2764 if (((hadc
->Instance
->OFR4
) & ADC_OFR4_OFFSET4_CH
) == ADC_OFR_CHANNEL(sConfig
->Channel
))
2766 CLEAR_BIT(hadc
->Instance
->OFR4
, ADC_OFR4_SSATE
);
2771 /* Parameters update conditioned to ADC state: */
2772 /* Parameters that can be updated only when ADC is disabled: */
2773 /* - Single or differential mode */
2774 /* - Internal measurement channels: Vbat/VrefInt/TempSensor */
2775 if (LL_ADC_IsEnabled(hadc
->Instance
) == 0UL)
2777 /* Set mode single-ended or differential input of the selected ADC channel */
2778 LL_ADC_SetChannelSingleDiff(hadc
->Instance
, sConfig
->Channel
, sConfig
->SingleDiff
);
2780 /* Configuration of differential mode */
2781 if (sConfig
->SingleDiff
== ADC_DIFFERENTIAL_ENDED
)
2783 /* Set sampling time of the selected ADC channel */
2784 /* Note: ADC channel number masked with value "0x1F" to ensure shift value within 32 bits range */
2785 LL_ADC_SetChannelSamplingTime(hadc
->Instance
,
2786 (uint32_t)(__LL_ADC_DECIMAL_NB_TO_CHANNEL((__LL_ADC_CHANNEL_TO_DECIMAL_NB((uint32_t)sConfig
->Channel
) + 1UL) & 0x1FUL
)),
2787 sConfig
->SamplingTime
);
2790 /* Management of internal measurement channels: Vbat/VrefInt/TempSensor. */
2791 /* If internal channel selected, enable dedicated internal buffers and */
2793 /* Note: these internal measurement paths can be disabled using */
2794 /* HAL_ADC_DeInit(). */
2796 if(__LL_ADC_IS_CHANNEL_INTERNAL(sConfig
->Channel
))
2798 /* Configuration of common ADC parameters */
2800 tmp_config_internal_channel
= LL_ADC_GetCommonPathInternalCh(__LL_ADC_COMMON_INSTANCE(hadc
->Instance
));
2802 /* Software is allowed to change common parameters only when all ADCs */
2803 /* of the common group are disabled. */
2804 if (__LL_ADC_IS_ENABLED_ALL_COMMON_INSTANCE(__LL_ADC_COMMON_INSTANCE(hadc
->Instance
)) == 0UL)
2806 /* If the requested internal measurement path has already been enabled, */
2807 /* bypass the configuration processing. */
2808 if ((sConfig
->Channel
== ADC_CHANNEL_TEMPSENSOR
) && ((tmp_config_internal_channel
& LL_ADC_PATH_INTERNAL_TEMPSENSOR
) == 0UL))
2810 if (ADC_TEMPERATURE_SENSOR_INSTANCE(hadc
))
2812 LL_ADC_SetCommonPathInternalCh(__LL_ADC_COMMON_INSTANCE(hadc
->Instance
), LL_ADC_PATH_INTERNAL_TEMPSENSOR
| tmp_config_internal_channel
);
2814 /* Delay for temperature sensor stabilization time */
2815 /* Wait loop initialization and execution */
2816 /* Note: Variable divided by 2 to compensate partially */
2817 /* CPU processing cycles, scaling in us split to not */
2818 /* exceed 32 bits register capacity and handle low frequency. */
2819 wait_loop_index
= ((LL_ADC_DELAY_TEMPSENSOR_STAB_US
/ 10UL) * (SystemCoreClock
/ (100000UL * 2UL)));
2820 while(wait_loop_index
!= 0UL)
2826 else if ((sConfig
->Channel
== ADC_CHANNEL_VBAT
) && ((tmp_config_internal_channel
& LL_ADC_PATH_INTERNAL_VBAT
) == 0UL))
2828 if (ADC_BATTERY_VOLTAGE_INSTANCE(hadc
))
2830 LL_ADC_SetCommonPathInternalCh(__LL_ADC_COMMON_INSTANCE(hadc
->Instance
), LL_ADC_PATH_INTERNAL_VBAT
| tmp_config_internal_channel
);
2833 else if ((sConfig
->Channel
== ADC_CHANNEL_VREFINT
) && ((tmp_config_internal_channel
& LL_ADC_PATH_INTERNAL_VREFINT
) == 0UL))
2835 if (ADC_VREFINT_INSTANCE(hadc
))
2837 LL_ADC_SetCommonPathInternalCh(__LL_ADC_COMMON_INSTANCE(hadc
->Instance
), LL_ADC_PATH_INTERNAL_VREFINT
| tmp_config_internal_channel
);
2845 /* If the requested internal measurement path has already been */
2846 /* enabled and other ADC of the common group are enabled, internal */
2847 /* measurement paths cannot be enabled. */
2850 /* Update ADC state machine to error */
2851 SET_BIT(hadc
->State
, HAL_ADC_STATE_ERROR_CONFIG
);
2853 tmp_hal_status
= HAL_ERROR
;
2859 /* If a conversion is on going on regular group, no update on regular */
2860 /* channel could be done on neither of the channel configuration structure */
2864 /* Update ADC state machine to error */
2865 SET_BIT(hadc
->State
, HAL_ADC_STATE_ERROR_CONFIG
);
2867 tmp_hal_status
= HAL_ERROR
;
2870 /* Process unlocked */
2873 /* Return function status */
2874 return tmp_hal_status
;
2878 * @brief Configure the analog watchdog.
2879 * @note Possibility to update parameters on the fly:
2880 * This function initializes the selected analog watchdog, successive
2881 * calls to this function can be used to reconfigure some parameters
2882 * of structure "ADC_AnalogWDGConfTypeDef" on the fly, without resetting
2884 * The setting of these parameters is conditioned to ADC state.
2885 * For parameters constraints, see comments of structure
2886 * "ADC_AnalogWDGConfTypeDef".
2887 * @note On this STM32 serie, analog watchdog thresholds cannot be modified
2888 * while ADC conversion is on going.
2889 * @param hadc ADC handle
2890 * @param AnalogWDGConfig Structure of ADC analog watchdog configuration
2891 * @retval HAL status
2893 HAL_StatusTypeDef
HAL_ADC_AnalogWDGConfig(ADC_HandleTypeDef
*hadc
, ADC_AnalogWDGConfTypeDef
*AnalogWDGConfig
)
2895 HAL_StatusTypeDef tmp_hal_status
= HAL_OK
;
2896 uint32_t tmpAWDHighThresholdShifted
;
2897 uint32_t tmpAWDLowThresholdShifted
;
2898 uint32_t tmp_adc_is_conversion_on_going_regular
;
2899 uint32_t tmp_adc_is_conversion_on_going_injected
;
2901 /* Check the parameters */
2902 assert_param(IS_ADC_ALL_INSTANCE(hadc
->Instance
));
2903 assert_param(IS_ADC_ANALOG_WATCHDOG_NUMBER(AnalogWDGConfig
->WatchdogNumber
));
2904 assert_param(IS_ADC_ANALOG_WATCHDOG_MODE(AnalogWDGConfig
->WatchdogMode
));
2905 assert_param(IS_FUNCTIONAL_STATE(AnalogWDGConfig
->ITMode
));
2907 if ((AnalogWDGConfig
->WatchdogMode
== ADC_ANALOGWATCHDOG_SINGLE_REG
) ||
2908 (AnalogWDGConfig
->WatchdogMode
== ADC_ANALOGWATCHDOG_SINGLE_INJEC
) ||
2909 (AnalogWDGConfig
->WatchdogMode
== ADC_ANALOGWATCHDOG_SINGLE_REGINJEC
))
2911 assert_param(IS_ADC_CHANNEL(AnalogWDGConfig
->Channel
));
2914 /* Verify thresholds range */
2915 if (hadc
->Init
.OversamplingMode
== ENABLE
)
2917 /* Case of oversampling enabled: thresholds are compared to oversampling
2918 intermediate computation (after ratio, before shift application) */
2919 assert_param(IS_ADC_RANGE(ADC_GET_RESOLUTION(hadc
), AnalogWDGConfig
->HighThreshold
/ (hadc
->Init
.Oversampling
.Ratio
+ 1UL)));
2920 assert_param(IS_ADC_RANGE(ADC_GET_RESOLUTION(hadc
), AnalogWDGConfig
->LowThreshold
/ (hadc
->Init
.Oversampling
.Ratio
+ 1UL)));
2924 /* Verify if thresholds are within the selected ADC resolution */
2925 assert_param(IS_ADC_RANGE(ADC_GET_RESOLUTION(hadc
), AnalogWDGConfig
->HighThreshold
));
2926 assert_param(IS_ADC_RANGE(ADC_GET_RESOLUTION(hadc
), AnalogWDGConfig
->LowThreshold
));
2929 /* Process locked */
2932 /* Parameters update conditioned to ADC state: */
2933 /* Parameters that can be updated when ADC is disabled or enabled without */
2934 /* conversion on going on ADC groups regular and injected: */
2935 /* - Analog watchdog channels */
2936 /* - Analog watchdog thresholds */
2937 tmp_adc_is_conversion_on_going_regular
= LL_ADC_REG_IsConversionOngoing(hadc
->Instance
);
2938 tmp_adc_is_conversion_on_going_injected
= LL_ADC_INJ_IsConversionOngoing(hadc
->Instance
);
2939 if ((tmp_adc_is_conversion_on_going_regular
== 0UL)
2940 && (tmp_adc_is_conversion_on_going_injected
== 0UL)
2943 /* Analog watchdog configuration */
2944 if (AnalogWDGConfig
->WatchdogNumber
== ADC_ANALOGWATCHDOG_1
)
2946 /* Configuration of analog watchdog: */
2947 /* - Set the analog watchdog enable mode: one or overall group of */
2948 /* channels, on groups regular and-or injected. */
2949 switch (AnalogWDGConfig
->WatchdogMode
)
2951 case ADC_ANALOGWATCHDOG_SINGLE_REG
:
2952 LL_ADC_SetAnalogWDMonitChannels(hadc
->Instance
, LL_ADC_AWD1
, __LL_ADC_ANALOGWD_CHANNEL_GROUP(AnalogWDGConfig
->Channel
,
2953 LL_ADC_GROUP_REGULAR
));
2956 case ADC_ANALOGWATCHDOG_SINGLE_INJEC
:
2957 LL_ADC_SetAnalogWDMonitChannels(hadc
->Instance
, LL_ADC_AWD1
, __LL_ADC_ANALOGWD_CHANNEL_GROUP(AnalogWDGConfig
->Channel
,
2958 LL_ADC_GROUP_INJECTED
));
2961 case ADC_ANALOGWATCHDOG_SINGLE_REGINJEC
:
2962 LL_ADC_SetAnalogWDMonitChannels(hadc
->Instance
, LL_ADC_AWD1
, __LL_ADC_ANALOGWD_CHANNEL_GROUP(AnalogWDGConfig
->Channel
,
2963 LL_ADC_GROUP_REGULAR_INJECTED
));
2966 case ADC_ANALOGWATCHDOG_ALL_REG
:
2967 LL_ADC_SetAnalogWDMonitChannels(hadc
->Instance
, LL_ADC_AWD1
, LL_ADC_AWD_ALL_CHANNELS_REG
);
2970 case ADC_ANALOGWATCHDOG_ALL_INJEC
:
2971 LL_ADC_SetAnalogWDMonitChannels(hadc
->Instance
, LL_ADC_AWD1
, LL_ADC_AWD_ALL_CHANNELS_INJ
);
2974 case ADC_ANALOGWATCHDOG_ALL_REGINJEC
:
2975 LL_ADC_SetAnalogWDMonitChannels(hadc
->Instance
, LL_ADC_AWD1
, LL_ADC_AWD_ALL_CHANNELS_REG_INJ
);
2978 default: /* ADC_ANALOGWATCHDOG_NONE */
2979 LL_ADC_SetAnalogWDMonitChannels(hadc
->Instance
, LL_ADC_AWD1
, LL_ADC_AWD_DISABLE
);
2983 /* Shift the offset in function of the selected ADC resolution: */
2984 /* Thresholds have to be left-aligned on bit 11, the LSB (right bits) */
2986 tmpAWDHighThresholdShifted
= ADC_AWD1THRESHOLD_SHIFT_RESOLUTION(hadc
, AnalogWDGConfig
->HighThreshold
);
2987 tmpAWDLowThresholdShifted
= ADC_AWD1THRESHOLD_SHIFT_RESOLUTION(hadc
, AnalogWDGConfig
->LowThreshold
);
2989 /* Set the high and low thresholds */
2990 MODIFY_REG(hadc
->Instance
->LTR1
, ADC_LTR_LT
, tmpAWDLowThresholdShifted
);
2991 MODIFY_REG(hadc
->Instance
->HTR1
, ADC_HTR_HT
, tmpAWDHighThresholdShifted
);
2993 /* Update state, clear previous result related to AWD1 */
2994 CLEAR_BIT(hadc
->State
, HAL_ADC_STATE_AWD1
);
2996 /* Clear flag ADC analog watchdog */
2997 /* Note: Flag cleared Clear the ADC Analog watchdog flag to be ready */
2998 /* to use for HAL_ADC_IRQHandler() or HAL_ADC_PollForEvent() */
2999 /* (in case left enabled by previous ADC operations). */
3000 LL_ADC_ClearFlag_AWD1(hadc
->Instance
);
3002 /* Configure ADC analog watchdog interrupt */
3003 if (AnalogWDGConfig
->ITMode
== ENABLE
)
3005 LL_ADC_EnableIT_AWD1(hadc
->Instance
);
3009 LL_ADC_DisableIT_AWD1(hadc
->Instance
);
3012 /* Case of ADC_ANALOGWATCHDOG_2 or ADC_ANALOGWATCHDOG_3 */
3015 switch (AnalogWDGConfig
->WatchdogMode
)
3017 case ADC_ANALOGWATCHDOG_SINGLE_REG
:
3018 case ADC_ANALOGWATCHDOG_SINGLE_INJEC
:
3019 case ADC_ANALOGWATCHDOG_SINGLE_REGINJEC
:
3020 /* Update AWD by bitfield to keep the possibility to monitor */
3021 /* several channels by successive calls of this function. */
3022 if (AnalogWDGConfig
->WatchdogNumber
== ADC_ANALOGWATCHDOG_2
)
3024 SET_BIT(hadc
->Instance
->AWD2CR
, (1UL << (__LL_ADC_CHANNEL_TO_DECIMAL_NB(AnalogWDGConfig
->Channel
) & 0x1FUL
)));
3028 SET_BIT(hadc
->Instance
->AWD3CR
, (1UL << (__LL_ADC_CHANNEL_TO_DECIMAL_NB(AnalogWDGConfig
->Channel
) & 0x1FUL
)));
3032 case ADC_ANALOGWATCHDOG_ALL_REG
:
3033 case ADC_ANALOGWATCHDOG_ALL_INJEC
:
3034 case ADC_ANALOGWATCHDOG_ALL_REGINJEC
:
3035 /* Update AWD by bitfield to keep the possibility to monitor */
3036 /* several channels by successive calls of this function. */
3037 if (AnalogWDGConfig
->WatchdogNumber
== ADC_ANALOGWATCHDOG_2
)
3039 SET_BIT(hadc
->Instance
->AWD2CR
, (1UL << (__LL_ADC_CHANNEL_TO_DECIMAL_NB(AnalogWDGConfig
->Channel
) & 0x1FUL
)));
3043 SET_BIT(hadc
->Instance
->AWD3CR
, (1UL << (__LL_ADC_CHANNEL_TO_DECIMAL_NB(AnalogWDGConfig
->Channel
) & 0x1FUL
)));
3047 default: /* ADC_ANALOGWATCHDOG_NONE */
3048 LL_ADC_SetAnalogWDMonitChannels(hadc
->Instance
, AnalogWDGConfig
->WatchdogNumber
, LL_ADC_AWD_DISABLE
);
3052 /* Shift the thresholds in function of the selected ADC resolution */
3053 /* have to be left-aligned on bit 15, the LSB (right bits) are set to 0 */
3054 tmpAWDHighThresholdShifted
= ADC_AWD23THRESHOLD_SHIFT_RESOLUTION(hadc
, AnalogWDGConfig
->HighThreshold
);
3055 tmpAWDLowThresholdShifted
= ADC_AWD23THRESHOLD_SHIFT_RESOLUTION(hadc
, AnalogWDGConfig
->LowThreshold
);
3057 if (AnalogWDGConfig
->WatchdogNumber
== ADC_ANALOGWATCHDOG_2
)
3059 /* Set ADC analog watchdog thresholds value of both thresholds high and low */
3060 MODIFY_REG(hadc
->Instance
->LTR2
, ADC_LTR_LT
, tmpAWDLowThresholdShifted
);
3061 MODIFY_REG(hadc
->Instance
->HTR2
, ADC_HTR_HT
, tmpAWDHighThresholdShifted
);
3065 /* Set ADC analog watchdog thresholds value of both thresholds high and low */
3066 MODIFY_REG(hadc
->Instance
->LTR3
, ADC_LTR_LT
, tmpAWDLowThresholdShifted
);
3067 MODIFY_REG(hadc
->Instance
->HTR3
, ADC_HTR_HT
, tmpAWDHighThresholdShifted
);
3070 if (AnalogWDGConfig
->WatchdogNumber
== ADC_ANALOGWATCHDOG_2
)
3072 /* Update state, clear previous result related to AWD2 */
3073 CLEAR_BIT(hadc
->State
, HAL_ADC_STATE_AWD2
);
3075 /* Clear flag ADC analog watchdog */
3076 /* Note: Flag cleared Clear the ADC Analog watchdog flag to be ready */
3077 /* to use for HAL_ADC_IRQHandler() or HAL_ADC_PollForEvent() */
3078 /* (in case left enabled by previous ADC operations). */
3079 LL_ADC_ClearFlag_AWD2(hadc
->Instance
);
3081 /* Configure ADC analog watchdog interrupt */
3082 if (AnalogWDGConfig
->ITMode
== ENABLE
)
3084 LL_ADC_EnableIT_AWD2(hadc
->Instance
);
3088 LL_ADC_DisableIT_AWD2(hadc
->Instance
);
3091 /* (AnalogWDGConfig->WatchdogNumber == ADC_ANALOGWATCHDOG_3) */
3094 /* Update state, clear previous result related to AWD3 */
3095 CLEAR_BIT(hadc
->State
, HAL_ADC_STATE_AWD3
);
3097 /* Clear flag ADC analog watchdog */
3098 /* Note: Flag cleared Clear the ADC Analog watchdog flag to be ready */
3099 /* to use for HAL_ADC_IRQHandler() or HAL_ADC_PollForEvent() */
3100 /* (in case left enabled by previous ADC operations). */
3101 LL_ADC_ClearFlag_AWD3(hadc
->Instance
);
3103 /* Configure ADC analog watchdog interrupt */
3104 if (AnalogWDGConfig
->ITMode
== ENABLE
)
3106 LL_ADC_EnableIT_AWD3(hadc
->Instance
);
3110 LL_ADC_DisableIT_AWD3(hadc
->Instance
);
3116 /* If a conversion is on going on ADC group regular or injected, no update */
3117 /* could be done on neither of the AWD configuration structure parameters. */
3120 /* Update ADC state machine to error */
3121 SET_BIT(hadc
->State
, HAL_ADC_STATE_ERROR_CONFIG
);
3123 tmp_hal_status
= HAL_ERROR
;
3125 /* Process unlocked */
3128 /* Return function status */
3129 return tmp_hal_status
;
3137 /** @defgroup ADC_Exported_Functions_Group4 Peripheral State functions
3138 * @brief ADC Peripheral State functions
3141 ===============================================================================
3142 ##### Peripheral state and errors functions #####
3143 ===============================================================================
3145 This subsection provides functions to get in run-time the status of the
3147 (+) Check the ADC state
3148 (+) Check the ADC error code
3155 * @brief Return the ADC handle state.
3156 * @note ADC state machine is managed by bitfields, ADC status must be
3157 * compared with states bits.
3159 * " if ((HAL_ADC_GetState(hadc1) & HAL_ADC_STATE_REG_BUSY) != 0UL) "
3160 * " if ((HAL_ADC_GetState(hadc1) & HAL_ADC_STATE_AWD1) != 0UL) "
3161 * @param hadc ADC handle
3162 * @retval ADC handle state (bitfield on 32 bits)
3164 uint32_t HAL_ADC_GetState(ADC_HandleTypeDef
*hadc
)
3166 /* Check the parameters */
3167 assert_param(IS_ADC_ALL_INSTANCE(hadc
->Instance
));
3169 /* Return ADC handle state */
3174 * @brief Return the ADC error code.
3175 * @param hadc ADC handle
3176 * @retval ADC error code (bitfield on 32 bits)
3178 uint32_t HAL_ADC_GetError(ADC_HandleTypeDef
*hadc
)
3180 /* Check the parameters */
3181 assert_param(IS_ADC_ALL_INSTANCE(hadc
->Instance
));
3183 return hadc
->ErrorCode
;
3194 /** @defgroup ADC_Private_Functions ADC Private Functions
3199 * @brief Stop ADC conversion.
3200 * @param hadc ADC handle
3201 * @param ConversionGroup ADC group regular and/or injected.
3202 * This parameter can be one of the following values:
3203 * @arg @ref ADC_REGULAR_GROUP ADC regular conversion type.
3204 * @arg @ref ADC_INJECTED_GROUP ADC injected conversion type.
3205 * @arg @ref ADC_REGULAR_INJECTED_GROUP ADC regular and injected conversion type.
3206 * @retval HAL status.
3208 HAL_StatusTypeDef
ADC_ConversionStop(ADC_HandleTypeDef
*hadc
, uint32_t ConversionGroup
)
3211 uint32_t Conversion_Timeout_CPU_cycles
= 0UL;
3212 uint32_t conversion_group_reassigned
= ConversionGroup
;
3213 uint32_t tmp_ADC_CR_ADSTART_JADSTART
;
3214 uint32_t tmp_adc_is_conversion_on_going_regular
;
3215 uint32_t tmp_adc_is_conversion_on_going_injected
;
3217 /* Check the parameters */
3218 assert_param(IS_ADC_ALL_INSTANCE(hadc
->Instance
));
3219 assert_param(IS_ADC_CONVERSION_GROUP(ConversionGroup
));
3221 /* Verification if ADC is not already stopped (on regular and injected */
3222 /* groups) to bypass this function if not needed. */
3223 tmp_adc_is_conversion_on_going_regular
= LL_ADC_REG_IsConversionOngoing(hadc
->Instance
);
3224 tmp_adc_is_conversion_on_going_injected
= LL_ADC_INJ_IsConversionOngoing(hadc
->Instance
);
3225 if ((tmp_adc_is_conversion_on_going_regular
!= 0UL)
3226 || (tmp_adc_is_conversion_on_going_injected
!= 0UL)
3229 /* Particular case of continuous auto-injection mode combined with */
3230 /* auto-delay mode. */
3231 /* In auto-injection mode, regular group stop ADC_CR_ADSTP is used (not */
3232 /* injected group stop ADC_CR_JADSTP). */
3233 /* Procedure to be followed: Wait until JEOS=1, clear JEOS, set ADSTP=1 */
3234 /* (see reference manual). */
3235 if (((hadc
->Instance
->CFGR
& ADC_CFGR_JAUTO
) != 0UL)
3236 && (hadc
->Init
.ContinuousConvMode
== ENABLE
)
3237 && (hadc
->Init
.LowPowerAutoWait
== ENABLE
)
3240 /* Use stop of regular group */
3241 conversion_group_reassigned
= ADC_REGULAR_GROUP
;
3243 /* Wait until JEOS=1 (maximum Timeout: 4 injected conversions) */
3244 while (__HAL_ADC_GET_FLAG(hadc
, ADC_FLAG_JEOS
) == 0UL)
3246 if (Conversion_Timeout_CPU_cycles
>= (ADC_CONVERSION_TIME_MAX_CPU_CYCLES
* 4UL))
3248 /* Update ADC state machine to error */
3249 SET_BIT(hadc
->State
, HAL_ADC_STATE_ERROR_INTERNAL
);
3251 /* Set ADC error code to ADC peripheral internal error */
3252 SET_BIT(hadc
->ErrorCode
, HAL_ADC_ERROR_INTERNAL
);
3256 Conversion_Timeout_CPU_cycles
++;
3260 __HAL_ADC_CLEAR_FLAG(hadc
, ADC_FLAG_JEOS
);
3263 /* Stop potential conversion on going on ADC group regular */
3264 if (conversion_group_reassigned
!= ADC_INJECTED_GROUP
)
3266 /* Software is allowed to set ADSTP only when ADSTART=1 and ADDIS=0 */
3267 if (LL_ADC_REG_IsConversionOngoing(hadc
->Instance
) != 0UL)
3269 if (LL_ADC_IsDisableOngoing(hadc
->Instance
) == 0UL)
3271 /* Stop ADC group regular conversion */
3272 LL_ADC_REG_StopConversion(hadc
->Instance
);
3277 /* Stop potential conversion on going on ADC group injected */
3278 if (conversion_group_reassigned
!= ADC_REGULAR_GROUP
)
3280 /* Software is allowed to set JADSTP only when JADSTART=1 and ADDIS=0 */
3281 if (LL_ADC_INJ_IsConversionOngoing(hadc
->Instance
) != 0UL)
3283 if (LL_ADC_IsDisableOngoing(hadc
->Instance
) == 0UL)
3285 /* Stop ADC group injected conversion */
3286 LL_ADC_INJ_StopConversion(hadc
->Instance
);
3291 /* Selection of start and stop bits with respect to the regular or injected group */
3292 switch (conversion_group_reassigned
)
3294 case ADC_REGULAR_INJECTED_GROUP
:
3295 tmp_ADC_CR_ADSTART_JADSTART
= (ADC_CR_ADSTART
| ADC_CR_JADSTART
);
3297 case ADC_INJECTED_GROUP
:
3298 tmp_ADC_CR_ADSTART_JADSTART
= ADC_CR_JADSTART
;
3300 /* Case ADC_REGULAR_GROUP only*/
3302 tmp_ADC_CR_ADSTART_JADSTART
= ADC_CR_ADSTART
;
3306 /* Wait for conversion effectively stopped */
3307 tickstart
= HAL_GetTick();
3309 while ((hadc
->Instance
->CR
& tmp_ADC_CR_ADSTART_JADSTART
) != 0UL)
3311 if ((HAL_GetTick() - tickstart
) > ADC_STOP_CONVERSION_TIMEOUT
)
3313 /* Update ADC state machine to error */
3314 SET_BIT(hadc
->State
, HAL_ADC_STATE_ERROR_INTERNAL
);
3316 /* Set ADC error code to ADC peripheral internal error */
3317 SET_BIT(hadc
->ErrorCode
, HAL_ADC_ERROR_INTERNAL
);
3325 /* Return HAL status */
3332 * @brief Enable the selected ADC.
3333 * @note Prerequisite condition to use this function: ADC must be disabled
3334 * and voltage regulator must be enabled (done into HAL_ADC_Init()).
3335 * @param hadc ADC handle
3336 * @retval HAL status.
3338 HAL_StatusTypeDef
ADC_Enable(ADC_HandleTypeDef
*hadc
)
3342 /* ADC enable and wait for ADC ready (in case of ADC is disabled or */
3343 /* enabling phase not yet completed: flag ADC ready not yet set). */
3344 /* Timeout implemented to not be stuck if ADC cannot be enabled (possible */
3345 /* causes: ADC clock not running, ...). */
3346 if (LL_ADC_IsEnabled(hadc
->Instance
) == 0UL)
3348 /* Check if conditions to enable the ADC are fulfilled */
3349 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)
3351 /* Update ADC state machine to error */
3352 SET_BIT(hadc
->State
, HAL_ADC_STATE_ERROR_INTERNAL
);
3354 /* Set ADC error code to ADC peripheral internal error */
3355 SET_BIT(hadc
->ErrorCode
, HAL_ADC_ERROR_INTERNAL
);
3360 /* Enable the ADC peripheral */
3361 LL_ADC_Enable(hadc
->Instance
);
3363 /* Wait for ADC effectively enabled */
3364 tickstart
= HAL_GetTick();
3366 /* Poll for ADC ready flag raised except case of multimode enabled
3367 and ADC slave selected. */
3368 uint32_t tmp_multimode_config
= LL_ADC_GetMultimode(__LL_ADC_COMMON_INSTANCE(hadc
->Instance
));
3369 if ( (__LL_ADC_MULTI_INSTANCE_MASTER(hadc
->Instance
) == hadc
->Instance
)
3370 || (tmp_multimode_config
== LL_ADC_MULTI_INDEPENDENT
)
3373 while(__HAL_ADC_GET_FLAG(hadc
, ADC_FLAG_RDY
) == 0UL)
3375 /* If ADEN bit is set less than 4 ADC clock cycles after the ADCAL bit
3376 has been cleared (after a calibration), ADEN bit is reset by the
3378 The workaround is to continue setting ADEN until ADRDY is becomes 1.
3379 Additionally, ADC_ENABLE_TIMEOUT is defined to encompass this
3380 4 ADC clock cycle duration */
3381 /* Note: Test of ADC enabled required due to hardware constraint to */
3382 /* not enable ADC if already enabled. */
3383 if(LL_ADC_IsEnabled(hadc
->Instance
) == 0UL)
3385 LL_ADC_Enable(hadc
->Instance
);
3388 if((HAL_GetTick() - tickstart
) > ADC_ENABLE_TIMEOUT
)
3390 /* Update ADC state machine to error */
3391 SET_BIT(hadc
->State
, HAL_ADC_STATE_ERROR_INTERNAL
);
3393 /* Set ADC error code to ADC peripheral internal error */
3394 SET_BIT(hadc
->ErrorCode
, HAL_ADC_ERROR_INTERNAL
);
3402 /* Return HAL status */
3407 * @brief Disable the selected ADC.
3408 * @note Prerequisite condition to use this function: ADC conversions must be
3410 * @param hadc ADC handle
3411 * @retval HAL status.
3413 HAL_StatusTypeDef
ADC_Disable(ADC_HandleTypeDef
*hadc
)
3416 const uint32_t tmp_adc_is_disable_on_going
= LL_ADC_IsDisableOngoing(hadc
->Instance
);
3418 /* Verification if ADC is not already disabled: */
3419 /* Note: forbidden to disable ADC (set bit ADC_CR_ADDIS) if ADC is already */
3421 if ((LL_ADC_IsEnabled(hadc
->Instance
) != 0UL)
3422 && (tmp_adc_is_disable_on_going
== 0UL)
3425 /* Check if conditions to disable the ADC are fulfilled */
3426 if ((hadc
->Instance
->CR
& (ADC_CR_JADSTART
| ADC_CR_ADSTART
| ADC_CR_ADEN
)) == ADC_CR_ADEN
)
3428 /* Disable the ADC peripheral */
3429 LL_ADC_Disable(hadc
->Instance
);
3430 __HAL_ADC_CLEAR_FLAG(hadc
, (ADC_FLAG_EOSMP
| ADC_FLAG_RDY
));
3434 /* Update ADC state machine to error */
3435 SET_BIT(hadc
->State
, HAL_ADC_STATE_ERROR_INTERNAL
);
3437 /* Set ADC error code to ADC peripheral internal error */
3438 SET_BIT(hadc
->ErrorCode
, HAL_ADC_ERROR_INTERNAL
);
3443 /* Wait for ADC effectively disabled */
3444 /* Get tick count */
3445 tickstart
= HAL_GetTick();
3447 while ((hadc
->Instance
->CR
& ADC_CR_ADEN
) != 0UL)
3449 if ((HAL_GetTick() - tickstart
) > ADC_DISABLE_TIMEOUT
)
3451 /* Update ADC state machine to error */
3452 SET_BIT(hadc
->State
, HAL_ADC_STATE_ERROR_INTERNAL
);
3454 /* Set ADC error code to ADC peripheral internal error */
3455 SET_BIT(hadc
->ErrorCode
, HAL_ADC_ERROR_INTERNAL
);
3462 /* Return HAL status */
3467 * @brief DMA transfer complete callback.
3468 * @param hdma pointer to DMA handle.
3471 void ADC_DMAConvCplt(DMA_HandleTypeDef
*hdma
)
3473 /* Retrieve ADC handle corresponding to current DMA handle */
3474 ADC_HandleTypeDef
*hadc
= (ADC_HandleTypeDef
*)((DMA_HandleTypeDef
*)hdma
)->Parent
;
3476 /* Update state machine on conversion status if not in error state */
3477 if ((hadc
->State
& (HAL_ADC_STATE_ERROR_INTERNAL
| HAL_ADC_STATE_ERROR_DMA
)) == 0UL)
3480 SET_BIT(hadc
->State
, HAL_ADC_STATE_REG_EOC
);
3482 /* Determine whether any further conversion upcoming on group regular */
3483 /* by external trigger, continuous mode or scan sequence on going */
3484 /* to disable interruption. */
3485 /* Is it the end of the regular sequence ? */
3486 if ((hadc
->Instance
->ISR
& ADC_FLAG_EOS
) != 0UL)
3488 /* Are conversions software-triggered ? */
3489 if (LL_ADC_REG_IsTriggerSourceSWStart(hadc
->Instance
) != 0UL)
3491 /* Is CONT bit set ? */
3492 if (READ_BIT(hadc
->Instance
->CFGR
, ADC_CFGR_CONT
) == 0UL)
3494 /* CONT bit is not set, no more conversions expected */
3495 CLEAR_BIT(hadc
->State
, HAL_ADC_STATE_REG_BUSY
);
3496 if ((hadc
->State
& HAL_ADC_STATE_INJ_BUSY
) == 0UL)
3498 SET_BIT(hadc
->State
, HAL_ADC_STATE_READY
);
3505 /* DMA End of Transfer interrupt was triggered but conversions sequence
3506 is not over. If DMACFG is set to 0, conversions are stopped. */
3507 if (READ_BIT(hadc
->Instance
->CFGR
, ADC_CFGR_DMNGT
) == 0UL)
3509 /* DMACFG bit is not set, conversions are stopped. */
3510 CLEAR_BIT(hadc
->State
, HAL_ADC_STATE_REG_BUSY
);
3511 if ((hadc
->State
& HAL_ADC_STATE_INJ_BUSY
) == 0UL)
3513 SET_BIT(hadc
->State
, HAL_ADC_STATE_READY
);
3518 /* Conversion complete callback */
3519 #if (USE_HAL_ADC_REGISTER_CALLBACKS == 1)
3520 hadc
->ConvCpltCallback(hadc
);
3522 HAL_ADC_ConvCpltCallback(hadc
);
3523 #endif /* USE_HAL_ADC_REGISTER_CALLBACKS */
3525 else /* DMA and-or internal error occurred */
3527 if ((hadc
->State
& HAL_ADC_STATE_ERROR_INTERNAL
) != 0UL)
3529 /* Call HAL ADC Error Callback function */
3530 #if (USE_HAL_ADC_REGISTER_CALLBACKS == 1)
3531 hadc
->ErrorCallback(hadc
);
3533 HAL_ADC_ErrorCallback(hadc
);
3534 #endif /* USE_HAL_ADC_REGISTER_CALLBACKS */
3538 /* Call ADC DMA error callback */
3539 hadc
->DMA_Handle
->XferErrorCallback(hdma
);
3545 * @brief DMA half transfer complete callback.
3546 * @param hdma pointer to DMA handle.
3549 void ADC_DMAHalfConvCplt(DMA_HandleTypeDef
*hdma
)
3551 /* Retrieve ADC handle corresponding to current DMA handle */
3552 ADC_HandleTypeDef
*hadc
= (ADC_HandleTypeDef
*)((DMA_HandleTypeDef
*)hdma
)->Parent
;
3554 /* Half conversion callback */
3555 #if (USE_HAL_ADC_REGISTER_CALLBACKS == 1)
3556 hadc
->ConvHalfCpltCallback(hadc
);
3558 HAL_ADC_ConvHalfCpltCallback(hadc
);
3559 #endif /* USE_HAL_ADC_REGISTER_CALLBACKS */
3563 * @brief DMA error callback.
3564 * @param hdma pointer to DMA handle.
3567 void ADC_DMAError(DMA_HandleTypeDef
*hdma
)
3569 /* Retrieve ADC handle corresponding to current DMA handle */
3570 ADC_HandleTypeDef
*hadc
= (ADC_HandleTypeDef
*)((DMA_HandleTypeDef
*)hdma
)->Parent
;
3573 SET_BIT(hadc
->State
, HAL_ADC_STATE_ERROR_DMA
);
3575 /* Set ADC error code to DMA error */
3576 SET_BIT(hadc
->ErrorCode
, HAL_ADC_ERROR_DMA
);
3578 /* Error callback */
3579 #if (USE_HAL_ADC_REGISTER_CALLBACKS == 1)
3580 hadc
->ErrorCallback(hadc
);
3582 HAL_ADC_ErrorCallback(hadc
);
3583 #endif /* USE_HAL_ADC_REGISTER_CALLBACKS */
3587 * @brief Configure boost mode of selected ADC.
3588 * @note Prerequisite condition to use this function: ADC conversions must be
3590 * @param hadc ADC handle
3593 void ADC_ConfigureBoostMode(ADC_HandleTypeDef
* hadc
)
3596 if(ADC_IS_SYNCHRONOUS_CLOCK_MODE(hadc
))
3598 freq
= HAL_RCC_GetHCLKFreq();
3599 switch(hadc
->Init
.ClockPrescaler
)
3601 case ADC_CLOCK_SYNC_PCLK_DIV1
:
3602 case ADC_CLOCK_SYNC_PCLK_DIV2
:
3603 freq
/= (hadc
->Init
.ClockPrescaler
>> ADC_CCR_CKMODE_Pos
);
3605 case ADC_CLOCK_SYNC_PCLK_DIV4
:
3614 freq
= HAL_RCCEx_GetPeriphCLKFreq(RCC_PERIPHCLK_ADC
);
3615 switch(hadc
->Init
.ClockPrescaler
)
3617 case ADC_CLOCK_ASYNC_DIV2
:
3618 case ADC_CLOCK_ASYNC_DIV4
:
3619 case ADC_CLOCK_ASYNC_DIV6
:
3620 case ADC_CLOCK_ASYNC_DIV8
:
3621 case ADC_CLOCK_ASYNC_DIV10
:
3622 case ADC_CLOCK_ASYNC_DIV12
:
3623 freq
/= ((hadc
->Init
.ClockPrescaler
>> ADC_CCR_PRESC_Pos
) << 1UL);
3625 case ADC_CLOCK_ASYNC_DIV16
:
3628 case ADC_CLOCK_ASYNC_DIV32
:
3631 case ADC_CLOCK_ASYNC_DIV64
:
3634 case ADC_CLOCK_ASYNC_DIV128
:
3637 case ADC_CLOCK_ASYNC_DIV256
:
3645 #if defined(ADC_VER_V5_3)
3648 if (freq
<= 6250000UL)
3650 MODIFY_REG(hadc
->Instance
->CR
, ADC_CR_BOOST
, 0UL);
3652 else if(freq
<= 12500000UL)
3654 MODIFY_REG(hadc
->Instance
->CR
, ADC_CR_BOOST
, ADC_CR_BOOST_0
);
3656 else if(freq
<= 25000000UL)
3658 MODIFY_REG(hadc
->Instance
->CR
, ADC_CR_BOOST
, ADC_CR_BOOST_1
);
3660 else /* if(freq > 25000000UL) */
3662 MODIFY_REG(hadc
->Instance
->CR
, ADC_CR_BOOST
, ADC_CR_BOOST_1
| ADC_CR_BOOST_0
);
3665 if(HAL_GetREVID() <= REV_ID_Y
) /* STM32H7 silicon Rev.Y */
3667 if(freq
> 20000000UL)
3669 SET_BIT(hadc
->Instance
->CR
, ADC_CR_BOOST_0
);
3673 CLEAR_BIT(hadc
->Instance
->CR
, ADC_CR_BOOST_0
);
3676 else /* STM32H7 silicon Rev.V */
3678 freq
/= 2U; /* divider by 2 for Rev.V */
3680 if (freq
<= 6250000UL)
3682 MODIFY_REG(hadc
->Instance
->CR
, ADC_CR_BOOST
, 0UL);
3684 else if(freq
<= 12500000UL)
3686 MODIFY_REG(hadc
->Instance
->CR
, ADC_CR_BOOST
, ADC_CR_BOOST_0
);
3688 else if(freq
<= 25000000UL)
3690 MODIFY_REG(hadc
->Instance
->CR
, ADC_CR_BOOST
, ADC_CR_BOOST_1
);
3692 else /* if(freq > 25000000UL) */
3694 MODIFY_REG(hadc
->Instance
->CR
, ADC_CR_BOOST
, ADC_CR_BOOST_1
| ADC_CR_BOOST_0
);
3697 #endif /* ADC_VER_V5_3 */
3704 #endif /* HAL_ADC_MODULE_ENABLED */
3713 /************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/