2 ******************************************************************************
3 * @file stm32f1xx_hal_adc.c
4 * @author MCD Application Team
7 * @brief This file provides firmware functions to manage the following
8 * functionalities of the Analog to Digital Convertor (ADC)
10 * + Initialization and de-initialization functions
11 * ++ Initialization and Configuration of ADC
12 * + Operation functions
13 * ++ Start, stop, get result of conversions of regular
14 * group, using 3 possible modes: polling, interruption or DMA.
16 * ++ Channels configuration on regular group
17 * ++ Channels configuration on injected group
18 * ++ Analog Watchdog configuration
20 * ++ ADC state machine management
21 * ++ Interrupts and flags management
22 * Other functions (extended functions) are available in file
23 * "stm32f1xx_hal_adc_ex.c".
26 ==============================================================================
27 ##### ADC peripheral features #####
28 ==============================================================================
32 (+) Interrupt generation at the end of regular conversion, end of injected
33 conversion, and in case of analog watchdog or overrun events.
35 (+) Single and continuous conversion modes.
37 (+) Scan mode for conversion of several channels sequentially.
39 (+) Data alignment with in-built data coherency.
41 (+) Programmable sampling time (channel wise)
43 (+) ADC conversion of regular group and injected group.
45 (+) External trigger (timer or EXTI)
46 for both regular and injected groups.
48 (+) DMA request generation for transfer of conversions data of regular group.
50 (+) Multimode Dual mode (available on devices with 2 ADCs or more).
52 (+) Configurable DMA data storage in Multimode Dual mode (available on devices
55 (+) Configurable delay between conversions in Dual interleaved mode (available
56 on devices with 2 DCs or more).
60 (+) ADC supply requirements: 2.4 V to 3.6 V at full speed and down to 1.8 V at
63 (+) ADC input range: from Vref- (connected to Vssa) to Vref+ (connected to
64 Vdda or to an external voltage reference).
67 ##### How to use this driver #####
68 ==============================================================================
71 *** Configuration of top level parameters related to ADC ***
72 ============================================================
75 (#) Enable the ADC interface
76 (++) As prerequisite, ADC clock must be configured at RCC top level.
77 Caution: On STM32F1, ADC clock frequency max is 14MHz (refer
79 Therefore, ADC clock prescaler must be configured in
80 function of ADC clock source frequency to remain below
81 this maximum frequency.
82 (++) One clock setting is mandatory:
83 ADC clock (core clock, also possibly conversion clock).
85 Into HAL_ADC_MspInit() (recommended code location) or with
86 other device clock parameters configuration:
87 (+++) RCC_PeriphCLKInitTypeDef PeriphClkInit;
88 (+++) __ADC1_CLK_ENABLE();
89 (+++) PeriphClkInit.PeriphClockSelection = RCC_PERIPHCLK_ADC;
90 (+++) PeriphClkInit.AdcClockSelection = RCC_ADCPCLK2_DIV2;
91 (+++) HAL_RCCEx_PeriphCLKConfig(&PeriphClkInit);
93 (#) ADC pins configuration
94 (++) Enable the clock for the ADC GPIOs
95 using macro __HAL_RCC_GPIOx_CLK_ENABLE()
96 (++) Configure these ADC pins in analog mode
97 using function HAL_GPIO_Init()
99 (#) Optionally, in case of usage of ADC with interruptions:
100 (++) Configure the NVIC for ADC
101 using function HAL_NVIC_EnableIRQ(ADCx_IRQn)
102 (++) Insert the ADC interruption handler function HAL_ADC_IRQHandler()
103 into the function of corresponding ADC interruption vector
106 (#) Optionally, in case of usage of DMA:
107 (++) Configure the DMA (DMA channel, mode normal or circular, ...)
108 using function HAL_DMA_Init().
109 (++) Configure the NVIC for DMA
110 using function HAL_NVIC_EnableIRQ(DMAx_Channelx_IRQn)
111 (++) Insert the ADC interruption handler function HAL_ADC_IRQHandler()
112 into the function of corresponding DMA interruption vector
113 DMAx_Channelx_IRQHandler().
115 *** Configuration of ADC, groups regular/injected, channels parameters ***
116 ==========================================================================
119 (#) Configure the ADC parameters (resolution, data alignment, ...)
120 and regular group parameters (conversion trigger, sequencer, ...)
121 using function HAL_ADC_Init().
123 (#) Configure the channels for regular group parameters (channel number,
124 channel rank into sequencer, ..., into regular group)
125 using function HAL_ADC_ConfigChannel().
127 (#) Optionally, configure the injected group parameters (conversion trigger,
128 sequencer, ..., of injected group)
129 and the channels for injected group parameters (channel number,
130 channel rank into sequencer, ..., into injected group)
131 using function HAL_ADCEx_InjectedConfigChannel().
133 (#) Optionally, configure the analog watchdog parameters (channels
134 monitored, thresholds, ...)
135 using function HAL_ADC_AnalogWDGConfig().
137 (#) Optionally, for devices with several ADC instances: configure the
139 using function HAL_ADCEx_MultiModeConfigChannel().
141 *** Execution of ADC conversions ***
142 ====================================
145 (#) Optionally, perform an automatic ADC calibration to improve the
147 using function HAL_ADCEx_Calibration_Start().
149 (#) ADC driver can be used among three modes: polling, interruption,
152 (++) ADC conversion by polling:
153 (+++) Activate the ADC peripheral and start conversions
154 using function HAL_ADC_Start()
155 (+++) Wait for ADC conversion completion
156 using function HAL_ADC_PollForConversion()
157 (or for injected group: HAL_ADCEx_InjectedPollForConversion() )
158 (+++) Retrieve conversion results
159 using function HAL_ADC_GetValue()
160 (or for injected group: HAL_ADCEx_InjectedGetValue() )
161 (+++) Stop conversion and disable the ADC peripheral
162 using function HAL_ADC_Stop()
164 (++) ADC conversion by interruption:
165 (+++) Activate the ADC peripheral and start conversions
166 using function HAL_ADC_Start_IT()
167 (+++) Wait for ADC conversion completion by call of function
168 HAL_ADC_ConvCpltCallback()
169 (this function must be implemented in user program)
170 (or for injected group: HAL_ADCEx_InjectedConvCpltCallback() )
171 (+++) Retrieve conversion results
172 using function HAL_ADC_GetValue()
173 (or for injected group: HAL_ADCEx_InjectedGetValue() )
174 (+++) Stop conversion and disable the ADC peripheral
175 using function HAL_ADC_Stop_IT()
177 (++) ADC conversion with transfer by DMA:
178 (+++) Activate the ADC peripheral and start conversions
179 using function HAL_ADC_Start_DMA()
180 (+++) Wait for ADC conversion completion by call of function
181 HAL_ADC_ConvCpltCallback() or HAL_ADC_ConvHalfCpltCallback()
182 (these functions must be implemented in user program)
183 (+++) Conversion results are automatically transferred by DMA into
184 destination variable address.
185 (+++) Stop conversion and disable the ADC peripheral
186 using function HAL_ADC_Stop_DMA()
188 (++) For devices with several ADCs: ADC multimode conversion
189 with transfer by DMA:
190 (+++) Activate the ADC peripheral (slave) and start conversions
191 using function HAL_ADC_Start()
192 (+++) Activate the ADC peripheral (master) and start conversions
193 using function HAL_ADCEx_MultiModeStart_DMA()
194 (+++) Wait for ADC conversion completion by call of function
195 HAL_ADC_ConvCpltCallback() or HAL_ADC_ConvHalfCpltCallback()
196 (these functions must be implemented in user program)
197 (+++) Conversion results are automatically transferred by DMA into
198 destination variable address.
199 (+++) Stop conversion and disable the ADC peripheral (master)
200 using function HAL_ADCEx_MultiModeStop_DMA()
201 (+++) Stop conversion and disable the ADC peripheral (slave)
202 using function HAL_ADC_Stop_IT()
206 (@) Callback functions must be implemented in user program:
207 (+@) HAL_ADC_ErrorCallback()
208 (+@) HAL_ADC_LevelOutOfWindowCallback() (callback of analog watchdog)
209 (+@) HAL_ADC_ConvCpltCallback()
210 (+@) HAL_ADC_ConvHalfCpltCallback
211 (+@) HAL_ADCEx_InjectedConvCpltCallback()
213 *** Deinitialization of ADC ***
214 ============================================================
217 (#) Disable the ADC interface
218 (++) ADC clock can be hard reset and disabled at RCC top level.
219 (++) Hard reset of ADC peripherals
220 using macro __ADCx_FORCE_RESET(), __ADCx_RELEASE_RESET().
221 (++) ADC clock disable
222 using the equivalent macro/functions as configuration step.
224 Into HAL_ADC_MspDeInit() (recommended code location) or with
225 other device clock parameters configuration:
226 (+++) PeriphClkInit.PeriphClockSelection = RCC_PERIPHCLK_ADC
227 (+++) PeriphClkInit.AdcClockSelection = RCC_ADCPLLCLK2_OFF
228 (+++) HAL_RCCEx_PeriphCLKConfig(&PeriphClkInit)
230 (#) ADC pins configuration
231 (++) Disable the clock for the ADC GPIOs
232 using macro __HAL_RCC_GPIOx_CLK_DISABLE()
234 (#) Optionally, in case of usage of ADC with interruptions:
235 (++) Disable the NVIC for ADC
236 using function HAL_NVIC_EnableIRQ(ADCx_IRQn)
238 (#) Optionally, in case of usage of DMA:
239 (++) Deinitialize the DMA
240 using function HAL_DMA_Init().
241 (++) Disable the NVIC for DMA
242 using function HAL_NVIC_EnableIRQ(DMAx_Channelx_IRQn)
247 ******************************************************************************
250 * <h2><center>© COPYRIGHT(c) 2016 STMicroelectronics</center></h2>
252 * Redistribution and use in source and binary forms, with or without modification,
253 * are permitted provided that the following conditions are met:
254 * 1. Redistributions of source code must retain the above copyright notice,
255 * this list of conditions and the following disclaimer.
256 * 2. Redistributions in binary form must reproduce the above copyright notice,
257 * this list of conditions and the following disclaimer in the documentation
258 * and/or other materials provided with the distribution.
259 * 3. Neither the name of STMicroelectronics nor the names of its contributors
260 * may be used to endorse or promote products derived from this software
261 * without specific prior written permission.
263 * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
264 * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
265 * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE
266 * DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE
267 * FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL
268 * DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR
269 * SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
270 * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY,
271 * OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE
272 * OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
274 ******************************************************************************
277 /* Includes ------------------------------------------------------------------*/
278 #include "stm32f1xx_hal.h"
280 /** @addtogroup STM32F1xx_HAL_Driver
284 /** @defgroup ADC ADC
285 * @brief ADC HAL module driver
289 #ifdef HAL_ADC_MODULE_ENABLED
291 /* Private typedef -----------------------------------------------------------*/
292 /* Private define ------------------------------------------------------------*/
293 /** @defgroup ADC_Private_Constants ADC Private Constants
297 /* Timeout values for ADC enable and disable settling time. */
298 /* Values defined to be higher than worst cases: low clocks freq, */
299 /* maximum prescaler. */
300 /* Ex of profile low frequency : Clock source at 0.1 MHz, ADC clock */
301 /* prescaler 4, sampling time 12.5 ADC clock cycles, resolution 12 bits. */
303 #define ADC_ENABLE_TIMEOUT 2U
304 #define ADC_DISABLE_TIMEOUT 2U
306 /* Delay for ADC stabilization time. */
307 /* Maximum delay is 1us (refer to device datasheet, parameter tSTAB). */
309 #define ADC_STAB_DELAY_US 1U
311 /* Delay for temperature sensor stabilization time. */
312 /* Maximum delay is 10us (refer to device datasheet, parameter tSTART). */
314 #define ADC_TEMPSENSOR_DELAY_US 10U
320 /* Private macro -------------------------------------------------------------*/
321 /* Private variables ---------------------------------------------------------*/
322 /* Private function prototypes -----------------------------------------------*/
323 /** @defgroup ADC_Private_Functions ADC Private Functions
330 /* Exported functions --------------------------------------------------------*/
332 /** @defgroup ADC_Exported_Functions ADC Exported Functions
336 /** @defgroup ADC_Exported_Functions_Group1 Initialization/de-initialization functions
337 * @brief Initialization and Configuration functions
340 ===============================================================================
341 ##### Initialization and de-initialization functions #####
342 ===============================================================================
343 [..] This section provides functions allowing to:
344 (+) Initialize and configure the ADC.
345 (+) De-initialize the ADC.
352 * @brief Initializes the ADC peripheral and regular group according to
353 * parameters specified in structure "ADC_InitTypeDef".
354 * @note As prerequisite, ADC clock must be configured at RCC top level
355 * (clock source APB2).
356 * See commented example code below that can be copied and uncommented
357 * into HAL_ADC_MspInit().
358 * @note Possibility to update parameters on the fly:
359 * This function initializes the ADC MSP (HAL_ADC_MspInit()) only when
360 * coming from ADC state reset. Following calls to this function can
361 * be used to reconfigure some parameters of ADC_InitTypeDef
362 * structure on the fly, without modifying MSP configuration. If ADC
363 * MSP has to be modified again, HAL_ADC_DeInit() must be called
364 * before HAL_ADC_Init().
365 * The setting of these parameters is conditioned to ADC state.
366 * For parameters constraints, see comments of structure
368 * @note This function configures the ADC within 2 scopes: scope of entire
369 * ADC and scope of regular group. For parameters details, see comments
370 * of structure "ADC_InitTypeDef".
371 * @param hadc: ADC handle
374 HAL_StatusTypeDef
HAL_ADC_Init(ADC_HandleTypeDef
* hadc
)
376 HAL_StatusTypeDef tmp_hal_status
= HAL_OK
;
377 uint32_t tmp_cr1
= 0U;
378 uint32_t tmp_cr2
= 0U;
379 uint32_t tmp_sqr1
= 0U;
381 /* Check ADC handle */
387 /* Check the parameters */
388 assert_param(IS_ADC_ALL_INSTANCE(hadc
->Instance
));
389 assert_param(IS_ADC_DATA_ALIGN(hadc
->Init
.DataAlign
));
390 assert_param(IS_ADC_SCAN_MODE(hadc
->Init
.ScanConvMode
));
391 assert_param(IS_FUNCTIONAL_STATE(hadc
->Init
.ContinuousConvMode
));
392 assert_param(IS_ADC_EXTTRIG(hadc
->Init
.ExternalTrigConv
));
394 if(hadc
->Init
.ScanConvMode
!= ADC_SCAN_DISABLE
)
396 assert_param(IS_ADC_REGULAR_NB_CONV(hadc
->Init
.NbrOfConversion
));
397 assert_param(IS_FUNCTIONAL_STATE(hadc
->Init
.DiscontinuousConvMode
));
398 if(hadc
->Init
.DiscontinuousConvMode
!= DISABLE
)
400 assert_param(IS_ADC_REGULAR_DISCONT_NUMBER(hadc
->Init
.NbrOfDiscConversion
));
404 /* As prerequisite, into HAL_ADC_MspInit(), ADC clock must be configured */
405 /* at RCC top level. */
406 /* Refer to header of this file for more details on clock enabling */
409 /* Actions performed only if ADC is coming from state reset: */
410 /* - Initialization of ADC MSP */
411 if (hadc
->State
== HAL_ADC_STATE_RESET
)
413 /* Initialize ADC error code */
414 ADC_CLEAR_ERRORCODE(hadc
);
416 /* Allocate lock resource and initialize it */
417 hadc
->Lock
= HAL_UNLOCKED
;
419 /* Init the low level hardware */
420 HAL_ADC_MspInit(hadc
);
423 /* Stop potential conversion on going, on regular and injected groups */
424 /* Disable ADC peripheral */
425 /* Note: In case of ADC already enabled, precaution to not launch an */
426 /* unwanted conversion while modifying register CR2 by writing 1 to */
428 tmp_hal_status
= ADC_ConversionStop_Disable(hadc
);
431 /* Configuration of ADC parameters if previous preliminary actions are */
432 /* correctly completed. */
433 if (HAL_IS_BIT_CLR(hadc
->State
, HAL_ADC_STATE_ERROR_INTERNAL
) &&
434 (tmp_hal_status
== HAL_OK
) )
437 ADC_STATE_CLR_SET(hadc
->State
,
438 HAL_ADC_STATE_REG_BUSY
| HAL_ADC_STATE_INJ_BUSY
,
439 HAL_ADC_STATE_BUSY_INTERNAL
);
441 /* Set ADC parameters */
443 /* Configuration of ADC: */
444 /* - data alignment */
445 /* - external trigger to start conversion */
446 /* - external trigger polarity (always set to 1, because needed for all */
447 /* triggers: external trigger of SW start) */
448 /* - continuous conversion mode */
449 /* Note: External trigger polarity (ADC_CR2_EXTTRIG) is set into */
450 /* HAL_ADC_Start_xxx functions because if set in this function, */
451 /* a conversion on injected group would start a conversion also on */
452 /* regular group after ADC enabling. */
453 tmp_cr2
|= (hadc
->Init
.DataAlign
|
454 ADC_CFGR_EXTSEL(hadc
, hadc
->Init
.ExternalTrigConv
) |
455 ADC_CR2_CONTINUOUS(hadc
->Init
.ContinuousConvMode
) );
457 /* Configuration of ADC: */
459 /* - discontinuous mode disable/enable */
460 /* - discontinuous mode number of conversions */
461 tmp_cr1
|= (ADC_CR1_SCAN_SET(hadc
->Init
.ScanConvMode
));
463 /* Enable discontinuous mode only if continuous mode is disabled */
464 /* Note: If parameter "Init.ScanConvMode" is set to disable, parameter */
465 /* discontinuous is set anyway, but will have no effect on ADC HW. */
466 if (hadc
->Init
.DiscontinuousConvMode
== ENABLE
)
468 if (hadc
->Init
.ContinuousConvMode
== DISABLE
)
470 /* Enable the selected ADC regular discontinuous mode */
471 /* Set the number of channels to be converted in discontinuous mode */
472 SET_BIT(tmp_cr1
, ADC_CR1_DISCEN
|
473 ADC_CR1_DISCONTINUOUS_NUM(hadc
->Init
.NbrOfDiscConversion
) );
477 /* ADC regular group settings continuous and sequencer discontinuous*/
478 /* cannot be enabled simultaneously. */
480 /* Update ADC state machine to error */
481 SET_BIT(hadc
->State
, HAL_ADC_STATE_ERROR_CONFIG
);
483 /* Set ADC error code to ADC IP internal error */
484 SET_BIT(hadc
->ErrorCode
, HAL_ADC_ERROR_INTERNAL
);
488 /* Update ADC configuration register CR1 with previous settings */
489 MODIFY_REG(hadc
->Instance
->CR1
,
495 /* Update ADC configuration register CR2 with previous settings */
496 MODIFY_REG(hadc
->Instance
->CR2
,
503 /* Configuration of regular group sequencer: */
504 /* - if scan mode is disabled, regular channels sequence length is set to */
505 /* 0x00: 1 channel converted (channel on regular rank 1) */
506 /* Parameter "NbrOfConversion" is discarded. */
507 /* Note: Scan mode is present by hardware on this device and, if */
508 /* disabled, discards automatically nb of conversions. Anyway, nb of */
509 /* conversions is forced to 0x00 for alignment over all STM32 devices. */
510 /* - if scan mode is enabled, regular channels sequence length is set to */
511 /* parameter "NbrOfConversion" */
512 if (ADC_CR1_SCAN_SET(hadc
->Init
.ScanConvMode
) == ADC_SCAN_ENABLE
)
514 tmp_sqr1
= ADC_SQR1_L_SHIFT(hadc
->Init
.NbrOfConversion
);
517 MODIFY_REG(hadc
->Instance
->SQR1
,
521 /* Check back that ADC registers have effectively been configured to */
522 /* ensure of no potential problem of ADC core IP clocking. */
523 /* Check through register CR2 (excluding bits set in other functions: */
524 /* execution control bits (ADON, JSWSTART, SWSTART), regular group bits */
525 /* (DMA), injected group bits (JEXTTRIG and JEXTSEL), channel internal */
526 /* measurement path bit (TSVREFE). */
527 if (READ_BIT(hadc
->Instance
->CR2
, ~(ADC_CR2_ADON
| ADC_CR2_DMA
|
528 ADC_CR2_SWSTART
| ADC_CR2_JSWSTART
|
529 ADC_CR2_JEXTTRIG
| ADC_CR2_JEXTSEL
|
533 /* Set ADC error code to none */
534 ADC_CLEAR_ERRORCODE(hadc
);
536 /* Set the ADC state */
537 ADC_STATE_CLR_SET(hadc
->State
,
538 HAL_ADC_STATE_BUSY_INTERNAL
,
539 HAL_ADC_STATE_READY
);
543 /* Update ADC state machine to error */
544 ADC_STATE_CLR_SET(hadc
->State
,
545 HAL_ADC_STATE_BUSY_INTERNAL
,
546 HAL_ADC_STATE_ERROR_INTERNAL
);
548 /* Set ADC error code to ADC IP internal error */
549 SET_BIT(hadc
->ErrorCode
, HAL_ADC_ERROR_INTERNAL
);
551 tmp_hal_status
= HAL_ERROR
;
557 /* Update ADC state machine to error */
558 SET_BIT(hadc
->State
, HAL_ADC_STATE_ERROR_INTERNAL
);
560 tmp_hal_status
= HAL_ERROR
;
563 /* Return function status */
564 return tmp_hal_status
;
568 * @brief Deinitialize the ADC peripheral registers to their default reset
569 * values, with deinitialization of the ADC MSP.
570 * If needed, the example code can be copied and uncommented into
571 * function HAL_ADC_MspDeInit().
572 * @param hadc: ADC handle
575 HAL_StatusTypeDef
HAL_ADC_DeInit(ADC_HandleTypeDef
* hadc
)
577 HAL_StatusTypeDef tmp_hal_status
= HAL_OK
;
579 /* Check ADC handle */
585 /* Check the parameters */
586 assert_param(IS_ADC_ALL_INSTANCE(hadc
->Instance
));
589 SET_BIT(hadc
->State
, HAL_ADC_STATE_BUSY_INTERNAL
);
591 /* Stop potential conversion on going, on regular and injected groups */
592 /* Disable ADC peripheral */
593 tmp_hal_status
= ADC_ConversionStop_Disable(hadc
);
596 /* Configuration of ADC parameters if previous preliminary actions are */
597 /* correctly completed. */
598 if (tmp_hal_status
== HAL_OK
)
600 /* ========== Reset ADC registers ========== */
605 /* Reset register SR */
606 __HAL_ADC_CLEAR_FLAG(hadc
, (ADC_FLAG_AWD
| ADC_FLAG_JEOC
| ADC_FLAG_EOC
|
607 ADC_FLAG_JSTRT
| ADC_FLAG_STRT
));
609 /* Reset register CR1 */
610 CLEAR_BIT(hadc
->Instance
->CR1
, (ADC_CR1_AWDEN
| ADC_CR1_JAWDEN
| ADC_CR1_DISCNUM
|
611 ADC_CR1_JDISCEN
| ADC_CR1_DISCEN
| ADC_CR1_JAUTO
|
612 ADC_CR1_AWDSGL
| ADC_CR1_SCAN
| ADC_CR1_JEOCIE
|
613 ADC_CR1_AWDIE
| ADC_CR1_EOCIE
| ADC_CR1_AWDCH
));
615 /* Reset register CR2 */
616 CLEAR_BIT(hadc
->Instance
->CR2
, (ADC_CR2_TSVREFE
| ADC_CR2_SWSTART
| ADC_CR2_JSWSTART
|
617 ADC_CR2_EXTTRIG
| ADC_CR2_EXTSEL
| ADC_CR2_JEXTTRIG
|
618 ADC_CR2_JEXTSEL
| ADC_CR2_ALIGN
| ADC_CR2_DMA
|
619 ADC_CR2_RSTCAL
| ADC_CR2_CAL
| ADC_CR2_CONT
|
622 /* Reset register SMPR1 */
623 CLEAR_BIT(hadc
->Instance
->SMPR1
, (ADC_SMPR1_SMP17
| ADC_SMPR1_SMP16
| ADC_SMPR1_SMP15
|
624 ADC_SMPR1_SMP14
| ADC_SMPR1_SMP13
| ADC_SMPR1_SMP12
|
625 ADC_SMPR1_SMP11
| ADC_SMPR1_SMP10
));
627 /* Reset register SMPR2 */
628 CLEAR_BIT(hadc
->Instance
->SMPR2
, (ADC_SMPR2_SMP9
| ADC_SMPR2_SMP8
| ADC_SMPR2_SMP7
|
629 ADC_SMPR2_SMP6
| ADC_SMPR2_SMP5
| ADC_SMPR2_SMP4
|
630 ADC_SMPR2_SMP3
| ADC_SMPR2_SMP2
| ADC_SMPR2_SMP1
|
633 /* Reset register JOFR1 */
634 CLEAR_BIT(hadc
->Instance
->JOFR1
, ADC_JOFR1_JOFFSET1
);
635 /* Reset register JOFR2 */
636 CLEAR_BIT(hadc
->Instance
->JOFR2
, ADC_JOFR2_JOFFSET2
);
637 /* Reset register JOFR3 */
638 CLEAR_BIT(hadc
->Instance
->JOFR3
, ADC_JOFR3_JOFFSET3
);
639 /* Reset register JOFR4 */
640 CLEAR_BIT(hadc
->Instance
->JOFR4
, ADC_JOFR4_JOFFSET4
);
642 /* Reset register HTR */
643 CLEAR_BIT(hadc
->Instance
->HTR
, ADC_HTR_HT
);
644 /* Reset register LTR */
645 CLEAR_BIT(hadc
->Instance
->LTR
, ADC_LTR_LT
);
647 /* Reset register SQR1 */
648 CLEAR_BIT(hadc
->Instance
->SQR1
, ADC_SQR1_L
|
649 ADC_SQR1_SQ16
| ADC_SQR1_SQ15
|
650 ADC_SQR1_SQ14
| ADC_SQR1_SQ13
);
652 /* Reset register SQR1 */
653 CLEAR_BIT(hadc
->Instance
->SQR1
, ADC_SQR1_L
|
654 ADC_SQR1_SQ16
| ADC_SQR1_SQ15
|
655 ADC_SQR1_SQ14
| ADC_SQR1_SQ13
);
657 /* Reset register SQR2 */
658 CLEAR_BIT(hadc
->Instance
->SQR2
, ADC_SQR2_SQ12
| ADC_SQR2_SQ11
| ADC_SQR2_SQ10
|
659 ADC_SQR2_SQ9
| ADC_SQR2_SQ8
| ADC_SQR2_SQ7
);
661 /* Reset register SQR3 */
662 CLEAR_BIT(hadc
->Instance
->SQR3
, ADC_SQR3_SQ6
| ADC_SQR3_SQ5
| ADC_SQR3_SQ4
|
663 ADC_SQR3_SQ3
| ADC_SQR3_SQ2
| ADC_SQR3_SQ1
);
665 /* Reset register JSQR */
666 CLEAR_BIT(hadc
->Instance
->JSQR
, ADC_JSQR_JL
|
667 ADC_JSQR_JSQ4
| ADC_JSQR_JSQ3
|
668 ADC_JSQR_JSQ2
| ADC_JSQR_JSQ1
);
670 /* Reset register JSQR */
671 CLEAR_BIT(hadc
->Instance
->JSQR
, ADC_JSQR_JL
|
672 ADC_JSQR_JSQ4
| ADC_JSQR_JSQ3
|
673 ADC_JSQR_JSQ2
| ADC_JSQR_JSQ1
);
675 /* Reset register DR */
676 /* bits in access mode read only, no direct reset applicable*/
678 /* Reset registers JDR1, JDR2, JDR3, JDR4 */
679 /* bits in access mode read only, no direct reset applicable*/
681 /* ========== Hard reset ADC peripheral ========== */
682 /* Performs a global reset of the entire ADC peripheral: ADC state is */
683 /* forced to a similar state after device power-on. */
684 /* If needed, copy-paste and uncomment the following reset code into */
685 /* function "void HAL_ADC_MspInit(ADC_HandleTypeDef* hadc)": */
687 /* __HAL_RCC_ADC1_FORCE_RESET() */
688 /* __HAL_RCC_ADC1_RELEASE_RESET() */
690 /* DeInit the low level hardware */
691 HAL_ADC_MspDeInit(hadc
);
693 /* Set ADC error code to none */
694 ADC_CLEAR_ERRORCODE(hadc
);
697 hadc
->State
= HAL_ADC_STATE_RESET
;
701 /* Process unlocked */
704 /* Return function status */
705 return tmp_hal_status
;
709 * @brief Initializes the ADC MSP.
710 * @param hadc: ADC handle
713 __weak
void HAL_ADC_MspInit(ADC_HandleTypeDef
* hadc
)
715 /* Prevent unused argument(s) compilation warning */
717 /* NOTE : This function should not be modified. When the callback is needed,
718 function HAL_ADC_MspInit must be implemented in the user file.
723 * @brief DeInitializes the ADC MSP.
724 * @param hadc: ADC handle
727 __weak
void HAL_ADC_MspDeInit(ADC_HandleTypeDef
* hadc
)
729 /* Prevent unused argument(s) compilation warning */
731 /* NOTE : This function should not be modified. When the callback is needed,
732 function HAL_ADC_MspDeInit must be implemented in the user file.
740 /** @defgroup ADC_Exported_Functions_Group2 IO operation functions
741 * @brief Input and Output operation functions
744 ===============================================================================
745 ##### IO operation functions #####
746 ===============================================================================
747 [..] This section provides functions allowing to:
748 (+) Start conversion of regular group.
749 (+) Stop conversion of regular group.
750 (+) Poll for conversion complete on regular group.
751 (+) Poll for conversion event.
752 (+) Get result of regular channel conversion.
753 (+) Start conversion of regular group and enable interruptions.
754 (+) Stop conversion of regular group and disable interruptions.
755 (+) Handle ADC interrupt request
756 (+) Start conversion of regular group and enable DMA transfer.
757 (+) Stop conversion of regular group and disable ADC DMA transfer.
763 * @brief Enables ADC, starts conversion of regular group.
764 * Interruptions enabled in this function: None.
765 * @param hadc: ADC handle
768 HAL_StatusTypeDef
HAL_ADC_Start(ADC_HandleTypeDef
* hadc
)
770 HAL_StatusTypeDef tmp_hal_status
= HAL_OK
;
772 /* Check the parameters */
773 assert_param(IS_ADC_ALL_INSTANCE(hadc
->Instance
));
778 /* Enable the ADC peripheral */
779 tmp_hal_status
= ADC_Enable(hadc
);
781 /* Start conversion if ADC is effectively enabled */
782 if (tmp_hal_status
== HAL_OK
)
785 /* - Clear state bitfield related to regular group conversion results */
786 /* - Set state bitfield related to regular operation */
787 ADC_STATE_CLR_SET(hadc
->State
,
788 HAL_ADC_STATE_READY
| HAL_ADC_STATE_REG_EOC
,
789 HAL_ADC_STATE_REG_BUSY
);
791 /* Set group injected state (from auto-injection) and multimode state */
792 /* for all cases of multimode: independent mode, multimode ADC master */
793 /* or multimode ADC slave (for devices with several ADCs): */
794 if (ADC_NONMULTIMODE_OR_MULTIMODEMASTER(hadc
))
796 /* Set ADC state (ADC independent or master) */
797 CLEAR_BIT(hadc
->State
, HAL_ADC_STATE_MULTIMODE_SLAVE
);
799 /* If conversions on group regular are also triggering group injected, */
800 /* update ADC state. */
801 if (READ_BIT(hadc
->Instance
->CR1
, ADC_CR1_JAUTO
) != RESET
)
803 ADC_STATE_CLR_SET(hadc
->State
, HAL_ADC_STATE_INJ_EOC
, HAL_ADC_STATE_INJ_BUSY
);
808 /* Set ADC state (ADC slave) */
809 SET_BIT(hadc
->State
, HAL_ADC_STATE_MULTIMODE_SLAVE
);
811 /* If conversions on group regular are also triggering group injected, */
812 /* update ADC state. */
813 if (ADC_MULTIMODE_AUTO_INJECTED(hadc
))
815 ADC_STATE_CLR_SET(hadc
->State
, HAL_ADC_STATE_INJ_EOC
, HAL_ADC_STATE_INJ_BUSY
);
819 /* State machine update: Check if an injected conversion is ongoing */
820 if (HAL_IS_BIT_SET(hadc
->State
, HAL_ADC_STATE_INJ_BUSY
))
822 /* Reset ADC error code fields related to conversions on group regular */
823 CLEAR_BIT(hadc
->ErrorCode
, (HAL_ADC_ERROR_OVR
| HAL_ADC_ERROR_DMA
));
827 /* Reset ADC all error code fields */
828 ADC_CLEAR_ERRORCODE(hadc
);
831 /* Process unlocked */
832 /* Unlock before starting ADC conversions: in case of potential */
833 /* interruption, to let the process to ADC IRQ Handler. */
836 /* Clear regular group conversion flag */
837 /* (To ensure of no unknown state from potential previous ADC operations) */
838 __HAL_ADC_CLEAR_FLAG(hadc
, ADC_FLAG_EOC
);
840 /* Enable conversion of regular group. */
841 /* If software start has been selected, conversion starts immediately. */
842 /* If external trigger has been selected, conversion will start at next */
844 /* Case of multimode enabled: */
845 /* - if ADC is slave, ADC is enabled only (conversion is not started). */
846 /* - if ADC is master, ADC is enabled and conversion is started. */
847 /* If ADC is master, ADC is enabled and conversion is started. */
848 /* Note: Alternate trigger for single conversion could be to force an */
849 /* additional set of bit ADON "hadc->Instance->CR2 |= ADC_CR2_ADON;"*/
850 if (ADC_IS_SOFTWARE_START_REGULAR(hadc
) &&
851 ADC_NONMULTIMODE_OR_MULTIMODEMASTER(hadc
) )
853 /* Start ADC conversion on regular group with SW start */
854 SET_BIT(hadc
->Instance
->CR2
, (ADC_CR2_SWSTART
| ADC_CR2_EXTTRIG
));
858 /* Start ADC conversion on regular group with external trigger */
859 SET_BIT(hadc
->Instance
->CR2
, ADC_CR2_EXTTRIG
);
864 /* Process unlocked */
868 /* Return function status */
869 return tmp_hal_status
;
873 * @brief Stop ADC conversion of regular group (and injected channels in
874 * case of auto_injection mode), disable ADC peripheral.
875 * @note: ADC peripheral disable is forcing stop of potential
876 * conversion on injected group. If injected group is under use, it
877 * should be preliminarily stopped using HAL_ADCEx_InjectedStop function.
878 * @param hadc: ADC handle
879 * @retval HAL status.
881 HAL_StatusTypeDef
HAL_ADC_Stop(ADC_HandleTypeDef
* hadc
)
883 HAL_StatusTypeDef tmp_hal_status
= HAL_OK
;
885 /* Check the parameters */
886 assert_param(IS_ADC_ALL_INSTANCE(hadc
->Instance
));
891 /* Stop potential conversion on going, on regular and injected groups */
892 /* Disable ADC peripheral */
893 tmp_hal_status
= ADC_ConversionStop_Disable(hadc
);
895 /* Check if ADC is effectively disabled */
896 if (tmp_hal_status
== HAL_OK
)
899 ADC_STATE_CLR_SET(hadc
->State
,
900 HAL_ADC_STATE_REG_BUSY
| HAL_ADC_STATE_INJ_BUSY
,
901 HAL_ADC_STATE_READY
);
904 /* Process unlocked */
907 /* Return function status */
908 return tmp_hal_status
;
912 * @brief Wait for regular group conversion to be completed.
913 * @note This function cannot be used in a particular setup: ADC configured
915 * In this case, DMA resets the flag EOC and polling cannot be
916 * performed on each conversion.
917 * @note On STM32F1 devices, limitation in case of sequencer enabled
918 * (several ranks selected): polling cannot be done on each
919 * conversion inside the sequence. In this case, polling is replaced by
920 * wait for maximum conversion time.
921 * @param hadc: ADC handle
922 * @param Timeout: Timeout value in millisecond.
925 HAL_StatusTypeDef
HAL_ADC_PollForConversion(ADC_HandleTypeDef
* hadc
, uint32_t Timeout
)
927 uint32_t tickstart
= 0U;
929 /* Variables for polling in case of scan mode enabled and polling for each */
931 __IO
uint32_t Conversion_Timeout_CPU_cycles
= 0U;
932 uint32_t Conversion_Timeout_CPU_cycles_max
= 0U;
934 /* Check the parameters */
935 assert_param(IS_ADC_ALL_INSTANCE(hadc
->Instance
));
938 tickstart
= HAL_GetTick();
940 /* Verification that ADC configuration is compliant with polling for */
941 /* each conversion: */
942 /* Particular case is ADC configured in DMA mode */
943 if (HAL_IS_BIT_SET(hadc
->Instance
->CR2
, ADC_CR2_DMA
))
945 /* Update ADC state machine to error */
946 SET_BIT(hadc
->State
, HAL_ADC_STATE_ERROR_CONFIG
);
948 /* Process unlocked */
954 /* Polling for end of conversion: differentiation if single/sequence */
956 /* - If single conversion for regular group (Scan mode disabled or enabled */
957 /* with NbrOfConversion =1), flag EOC is used to determine the */
958 /* conversion completion. */
959 /* - If sequence conversion for regular group (scan mode enabled and */
960 /* NbrOfConversion >=2), flag EOC is set only at the end of the */
962 /* To poll for each conversion, the maximum conversion time is computed */
963 /* from ADC conversion time (selected sampling time + conversion time of */
964 /* 12.5 ADC clock cycles) and APB2/ADC clock prescalers (depending on */
965 /* settings, conversion time range can be from 28 to 32256 CPU cycles). */
966 /* As flag EOC is not set after each conversion, no timeout status can */
968 if (HAL_IS_BIT_CLR(hadc
->Instance
->CR1
, ADC_CR1_SCAN
) &&
969 HAL_IS_BIT_CLR(hadc
->Instance
->SQR1
, ADC_SQR1_L
) )
971 /* Wait until End of Conversion flag is raised */
972 while(HAL_IS_BIT_CLR(hadc
->Instance
->SR
, ADC_FLAG_EOC
))
974 /* Check if timeout is disabled (set to infinite wait) */
975 if(Timeout
!= HAL_MAX_DELAY
)
977 if((Timeout
== 0U) || ((HAL_GetTick() - tickstart
) > Timeout
))
979 /* Update ADC state machine to timeout */
980 SET_BIT(hadc
->State
, HAL_ADC_STATE_TIMEOUT
);
982 /* Process unlocked */
992 /* Replace polling by wait for maximum conversion time */
993 /* - Computation of CPU clock cycles corresponding to ADC clock cycles */
994 /* and ADC maximum conversion cycles on all channels. */
995 /* - Wait for the expected ADC clock cycles delay */
996 Conversion_Timeout_CPU_cycles_max
= ((SystemCoreClock
997 / HAL_RCCEx_GetPeriphCLKFreq(RCC_PERIPHCLK_ADC
))
998 * ADC_CONVCYCLES_MAX_RANGE(hadc
) );
1000 while(Conversion_Timeout_CPU_cycles
< Conversion_Timeout_CPU_cycles_max
)
1002 /* Check if timeout is disabled (set to infinite wait) */
1003 if(Timeout
!= HAL_MAX_DELAY
)
1005 if((Timeout
== 0U) || ((HAL_GetTick() - tickstart
) > Timeout
))
1007 /* Update ADC state machine to timeout */
1008 SET_BIT(hadc
->State
, HAL_ADC_STATE_TIMEOUT
);
1010 /* Process unlocked */
1016 Conversion_Timeout_CPU_cycles
++;
1020 /* Clear regular group conversion flag */
1021 __HAL_ADC_CLEAR_FLAG(hadc
, ADC_FLAG_STRT
| ADC_FLAG_EOC
);
1023 /* Update ADC state machine */
1024 SET_BIT(hadc
->State
, HAL_ADC_STATE_REG_EOC
);
1026 /* Determine whether any further conversion upcoming on group regular */
1027 /* by external trigger, continuous mode or scan sequence on going. */
1028 /* Note: On STM32F1 devices, in case of sequencer enabled */
1029 /* (several ranks selected), end of conversion flag is raised */
1030 /* at the end of the sequence. */
1031 if(ADC_IS_SOFTWARE_START_REGULAR(hadc
) &&
1032 (hadc
->Init
.ContinuousConvMode
== DISABLE
) )
1035 CLEAR_BIT(hadc
->State
, HAL_ADC_STATE_REG_BUSY
);
1037 if (HAL_IS_BIT_CLR(hadc
->State
, HAL_ADC_STATE_INJ_BUSY
))
1039 SET_BIT(hadc
->State
, HAL_ADC_STATE_READY
);
1043 /* Return ADC state */
1048 * @brief Poll for conversion event.
1049 * @param hadc: ADC handle
1050 * @param EventType: the ADC event type.
1051 * This parameter can be one of the following values:
1052 * @arg ADC_AWD_EVENT: ADC Analog watchdog event.
1053 * @param Timeout: Timeout value in millisecond.
1054 * @retval HAL status
1056 HAL_StatusTypeDef
HAL_ADC_PollForEvent(ADC_HandleTypeDef
* hadc
, uint32_t EventType
, uint32_t Timeout
)
1058 uint32_t tickstart
= 0U;
1060 /* Check the parameters */
1061 assert_param(IS_ADC_ALL_INSTANCE(hadc
->Instance
));
1062 assert_param(IS_ADC_EVENT_TYPE(EventType
));
1064 /* Get tick count */
1065 tickstart
= HAL_GetTick();
1067 /* Check selected event flag */
1068 while(__HAL_ADC_GET_FLAG(hadc
, EventType
) == RESET
)
1070 /* Check if timeout is disabled (set to infinite wait) */
1071 if(Timeout
!= HAL_MAX_DELAY
)
1073 if((Timeout
== 0U) || ((HAL_GetTick() - tickstart
) > Timeout
))
1075 /* Update ADC state machine to timeout */
1076 SET_BIT(hadc
->State
, HAL_ADC_STATE_TIMEOUT
);
1078 /* Process unlocked */
1086 /* Analog watchdog (level out of window) event */
1088 SET_BIT(hadc
->State
, HAL_ADC_STATE_AWD1
);
1090 /* Clear ADC analog watchdog flag */
1091 __HAL_ADC_CLEAR_FLAG(hadc
, ADC_FLAG_AWD
);
1093 /* Return ADC state */
1098 * @brief Enables ADC, starts conversion of regular group with interruption.
1099 * Interruptions enabled in this function:
1100 * - EOC (end of conversion of regular group)
1101 * Each of these interruptions has its dedicated callback function.
1102 * @param hadc: ADC handle
1103 * @retval HAL status
1105 HAL_StatusTypeDef
HAL_ADC_Start_IT(ADC_HandleTypeDef
* hadc
)
1107 HAL_StatusTypeDef tmp_hal_status
= HAL_OK
;
1109 /* Check the parameters */
1110 assert_param(IS_ADC_ALL_INSTANCE(hadc
->Instance
));
1112 /* Process locked */
1115 /* Enable the ADC peripheral */
1116 tmp_hal_status
= ADC_Enable(hadc
);
1118 /* Start conversion if ADC is effectively enabled */
1119 if (tmp_hal_status
== HAL_OK
)
1122 /* - Clear state bitfield related to regular group conversion results */
1123 /* - Set state bitfield related to regular operation */
1124 ADC_STATE_CLR_SET(hadc
->State
,
1125 HAL_ADC_STATE_READY
| HAL_ADC_STATE_REG_EOC
| HAL_ADC_STATE_REG_OVR
| HAL_ADC_STATE_REG_EOSMP
,
1126 HAL_ADC_STATE_REG_BUSY
);
1128 /* Set group injected state (from auto-injection) and multimode state */
1129 /* for all cases of multimode: independent mode, multimode ADC master */
1130 /* or multimode ADC slave (for devices with several ADCs): */
1131 if (ADC_NONMULTIMODE_OR_MULTIMODEMASTER(hadc
))
1133 /* Set ADC state (ADC independent or master) */
1134 CLEAR_BIT(hadc
->State
, HAL_ADC_STATE_MULTIMODE_SLAVE
);
1136 /* If conversions on group regular are also triggering group injected, */
1137 /* update ADC state. */
1138 if (READ_BIT(hadc
->Instance
->CR1
, ADC_CR1_JAUTO
) != RESET
)
1140 ADC_STATE_CLR_SET(hadc
->State
, HAL_ADC_STATE_INJ_EOC
, HAL_ADC_STATE_INJ_BUSY
);
1145 /* Set ADC state (ADC slave) */
1146 SET_BIT(hadc
->State
, HAL_ADC_STATE_MULTIMODE_SLAVE
);
1148 /* If conversions on group regular are also triggering group injected, */
1149 /* update ADC state. */
1150 if (ADC_MULTIMODE_AUTO_INJECTED(hadc
))
1152 ADC_STATE_CLR_SET(hadc
->State
, HAL_ADC_STATE_INJ_EOC
, HAL_ADC_STATE_INJ_BUSY
);
1156 /* State machine update: Check if an injected conversion is ongoing */
1157 if (HAL_IS_BIT_SET(hadc
->State
, HAL_ADC_STATE_INJ_BUSY
))
1159 /* Reset ADC error code fields related to conversions on group regular */
1160 CLEAR_BIT(hadc
->ErrorCode
, (HAL_ADC_ERROR_OVR
| HAL_ADC_ERROR_DMA
));
1164 /* Reset ADC all error code fields */
1165 ADC_CLEAR_ERRORCODE(hadc
);
1168 /* Process unlocked */
1169 /* Unlock before starting ADC conversions: in case of potential */
1170 /* interruption, to let the process to ADC IRQ Handler. */
1173 /* Clear regular group conversion flag and overrun flag */
1174 /* (To ensure of no unknown state from potential previous ADC operations) */
1175 __HAL_ADC_CLEAR_FLAG(hadc
, ADC_FLAG_EOC
);
1177 /* Enable end of conversion interrupt for regular group */
1178 __HAL_ADC_ENABLE_IT(hadc
, ADC_IT_EOC
);
1180 /* Enable conversion of regular group. */
1181 /* If software start has been selected, conversion starts immediately. */
1182 /* If external trigger has been selected, conversion will start at next */
1183 /* trigger event. */
1184 /* Case of multimode enabled: */
1185 /* - if ADC is slave, ADC is enabled only (conversion is not started). */
1186 /* - if ADC is master, ADC is enabled and conversion is started. */
1187 if (ADC_IS_SOFTWARE_START_REGULAR(hadc
) &&
1188 ADC_NONMULTIMODE_OR_MULTIMODEMASTER(hadc
) )
1190 /* Start ADC conversion on regular group with SW start */
1191 SET_BIT(hadc
->Instance
->CR2
, (ADC_CR2_SWSTART
| ADC_CR2_EXTTRIG
));
1195 /* Start ADC conversion on regular group with external trigger */
1196 SET_BIT(hadc
->Instance
->CR2
, ADC_CR2_EXTTRIG
);
1201 /* Process unlocked */
1205 /* Return function status */
1206 return tmp_hal_status
;
1210 * @brief Stop ADC conversion of regular group (and injected group in
1211 * case of auto_injection mode), disable interrution of
1212 * end-of-conversion, disable ADC peripheral.
1213 * @param hadc: ADC handle
1216 HAL_StatusTypeDef
HAL_ADC_Stop_IT(ADC_HandleTypeDef
* hadc
)
1218 HAL_StatusTypeDef tmp_hal_status
= HAL_OK
;
1220 /* Check the parameters */
1221 assert_param(IS_ADC_ALL_INSTANCE(hadc
->Instance
));
1223 /* Process locked */
1226 /* Stop potential conversion on going, on regular and injected groups */
1227 /* Disable ADC peripheral */
1228 tmp_hal_status
= ADC_ConversionStop_Disable(hadc
);
1230 /* Check if ADC is effectively disabled */
1231 if (tmp_hal_status
== HAL_OK
)
1233 /* Disable ADC end of conversion interrupt for regular group */
1234 __HAL_ADC_DISABLE_IT(hadc
, ADC_IT_EOC
);
1237 ADC_STATE_CLR_SET(hadc
->State
,
1238 HAL_ADC_STATE_REG_BUSY
| HAL_ADC_STATE_INJ_BUSY
,
1239 HAL_ADC_STATE_READY
);
1242 /* Process unlocked */
1245 /* Return function status */
1246 return tmp_hal_status
;
1250 * @brief Enables ADC, starts conversion of regular group and transfers result
1252 * Interruptions enabled in this function:
1253 * - DMA transfer complete
1254 * - DMA half transfer
1255 * Each of these interruptions has its dedicated callback function.
1256 * @note For devices with several ADCs: This function is for single-ADC mode
1257 * only. For multimode, use the dedicated MultimodeStart function.
1258 * @note On STM32F1 devices, only ADC1 and ADC3 (ADC availability depending
1259 * on devices) have DMA capability.
1260 * ADC2 converted data can be transferred in dual ADC mode using DMA
1261 * of ADC1 (ADC master in multimode).
1262 * In case of using ADC1 with DMA on a device featuring 2 ADC
1263 * instances: ADC1 conversion register DR contains ADC1 conversion
1264 * result (ADC1 register DR bits 0 to 11) and, additionally, ADC2 last
1265 * conversion result (ADC1 register DR bits 16 to 27). Therefore, to
1266 * have DMA transferring the conversion results of ADC1 only, DMA must
1267 * be configured to transfer size: half word.
1268 * @param hadc: ADC handle
1269 * @param pData: The destination Buffer address.
1270 * @param Length: The length of data to be transferred from ADC peripheral to memory.
1273 HAL_StatusTypeDef
HAL_ADC_Start_DMA(ADC_HandleTypeDef
* hadc
, uint32_t* pData
, uint32_t Length
)
1275 HAL_StatusTypeDef tmp_hal_status
= HAL_OK
;
1277 /* Check the parameters */
1278 assert_param(IS_ADC_DMA_CAPABILITY_INSTANCE(hadc
->Instance
));
1280 /* Verification if multimode is disabled (for devices with several ADC) */
1281 /* If multimode is enabled, dedicated function multimode conversion */
1282 /* start DMA must be used. */
1283 if(ADC_MULTIMODE_IS_ENABLE(hadc
) == RESET
)
1285 /* Process locked */
1288 /* Enable the ADC peripheral */
1289 tmp_hal_status
= ADC_Enable(hadc
);
1291 /* Start conversion if ADC is effectively enabled */
1292 if (tmp_hal_status
== HAL_OK
)
1295 /* - Clear state bitfield related to regular group conversion results */
1296 /* - Set state bitfield related to regular operation */
1297 ADC_STATE_CLR_SET(hadc
->State
,
1298 HAL_ADC_STATE_READY
| HAL_ADC_STATE_REG_EOC
| HAL_ADC_STATE_REG_OVR
| HAL_ADC_STATE_REG_EOSMP
,
1299 HAL_ADC_STATE_REG_BUSY
);
1301 /* Set group injected state (from auto-injection) and multimode state */
1302 /* for all cases of multimode: independent mode, multimode ADC master */
1303 /* or multimode ADC slave (for devices with several ADCs): */
1304 if (ADC_NONMULTIMODE_OR_MULTIMODEMASTER(hadc
))
1306 /* Set ADC state (ADC independent or master) */
1307 CLEAR_BIT(hadc
->State
, HAL_ADC_STATE_MULTIMODE_SLAVE
);
1309 /* If conversions on group regular are also triggering group injected, */
1310 /* update ADC state. */
1311 if (READ_BIT(hadc
->Instance
->CR1
, ADC_CR1_JAUTO
) != RESET
)
1313 ADC_STATE_CLR_SET(hadc
->State
, HAL_ADC_STATE_INJ_EOC
, HAL_ADC_STATE_INJ_BUSY
);
1318 /* Set ADC state (ADC slave) */
1319 SET_BIT(hadc
->State
, HAL_ADC_STATE_MULTIMODE_SLAVE
);
1321 /* If conversions on group regular are also triggering group injected, */
1322 /* update ADC state. */
1323 if (ADC_MULTIMODE_AUTO_INJECTED(hadc
))
1325 ADC_STATE_CLR_SET(hadc
->State
, HAL_ADC_STATE_INJ_EOC
, HAL_ADC_STATE_INJ_BUSY
);
1329 /* State machine update: Check if an injected conversion is ongoing */
1330 if (HAL_IS_BIT_SET(hadc
->State
, HAL_ADC_STATE_INJ_BUSY
))
1332 /* Reset ADC error code fields related to conversions on group regular */
1333 CLEAR_BIT(hadc
->ErrorCode
, (HAL_ADC_ERROR_OVR
| HAL_ADC_ERROR_DMA
));
1337 /* Reset ADC all error code fields */
1338 ADC_CLEAR_ERRORCODE(hadc
);
1341 /* Process unlocked */
1342 /* Unlock before starting ADC conversions: in case of potential */
1343 /* interruption, to let the process to ADC IRQ Handler. */
1346 /* Set the DMA transfer complete callback */
1347 hadc
->DMA_Handle
->XferCpltCallback
= ADC_DMAConvCplt
;
1349 /* Set the DMA half transfer complete callback */
1350 hadc
->DMA_Handle
->XferHalfCpltCallback
= ADC_DMAHalfConvCplt
;
1352 /* Set the DMA error callback */
1353 hadc
->DMA_Handle
->XferErrorCallback
= ADC_DMAError
;
1356 /* Manage ADC and DMA start: ADC overrun interruption, DMA start, ADC */
1357 /* start (in case of SW start): */
1359 /* Clear regular group conversion flag and overrun flag */
1360 /* (To ensure of no unknown state from potential previous ADC */
1362 __HAL_ADC_CLEAR_FLAG(hadc
, ADC_FLAG_EOC
);
1364 /* Enable ADC DMA mode */
1365 SET_BIT(hadc
->Instance
->CR2
, ADC_CR2_DMA
);
1367 /* Start the DMA channel */
1368 HAL_DMA_Start_IT(hadc
->DMA_Handle
, (uint32_t)&hadc
->Instance
->DR
, (uint32_t)pData
, Length
);
1370 /* Enable conversion of regular group. */
1371 /* If software start has been selected, conversion starts immediately. */
1372 /* If external trigger has been selected, conversion will start at next */
1373 /* trigger event. */
1374 if (ADC_IS_SOFTWARE_START_REGULAR(hadc
))
1376 /* Start ADC conversion on regular group with SW start */
1377 SET_BIT(hadc
->Instance
->CR2
, (ADC_CR2_SWSTART
| ADC_CR2_EXTTRIG
));
1381 /* Start ADC conversion on regular group with external trigger */
1382 SET_BIT(hadc
->Instance
->CR2
, ADC_CR2_EXTTRIG
);
1387 /* Process unlocked */
1393 tmp_hal_status
= HAL_ERROR
;
1396 /* Return function status */
1397 return tmp_hal_status
;
1401 * @brief Stop ADC conversion of regular group (and injected group in
1402 * case of auto_injection mode), disable ADC DMA transfer, disable
1404 * @note: ADC peripheral disable is forcing stop of potential
1405 * conversion on injected group. If injected group is under use, it
1406 * should be preliminarily stopped using HAL_ADCEx_InjectedStop function.
1407 * @note For devices with several ADCs: This function is for single-ADC mode
1408 * only. For multimode, use the dedicated MultimodeStop function.
1409 * @note On STM32F1 devices, only ADC1 and ADC3 (ADC availability depending
1410 * on devices) have DMA capability.
1411 * @param hadc: ADC handle
1412 * @retval HAL status.
1414 HAL_StatusTypeDef
HAL_ADC_Stop_DMA(ADC_HandleTypeDef
* hadc
)
1416 HAL_StatusTypeDef tmp_hal_status
= HAL_OK
;
1418 /* Check the parameters */
1419 assert_param(IS_ADC_DMA_CAPABILITY_INSTANCE(hadc
->Instance
));
1421 /* Process locked */
1424 /* Stop potential conversion on going, on regular and injected groups */
1425 /* Disable ADC peripheral */
1426 tmp_hal_status
= ADC_ConversionStop_Disable(hadc
);
1428 /* Check if ADC is effectively disabled */
1429 if (tmp_hal_status
== HAL_OK
)
1431 /* Disable ADC DMA mode */
1432 CLEAR_BIT(hadc
->Instance
->CR2
, ADC_CR2_DMA
);
1434 /* Disable the DMA channel (in case of DMA in circular mode or stop while */
1435 /* DMA transfer is on going) */
1436 tmp_hal_status
= HAL_DMA_Abort(hadc
->DMA_Handle
);
1438 /* Check if DMA channel effectively disabled */
1439 if (tmp_hal_status
== HAL_OK
)
1442 ADC_STATE_CLR_SET(hadc
->State
,
1443 HAL_ADC_STATE_REG_BUSY
| HAL_ADC_STATE_INJ_BUSY
,
1444 HAL_ADC_STATE_READY
);
1448 /* Update ADC state machine to error */
1449 SET_BIT(hadc
->State
, HAL_ADC_STATE_ERROR_DMA
);
1453 /* Process unlocked */
1456 /* Return function status */
1457 return tmp_hal_status
;
1461 * @brief Get ADC regular group conversion result.
1462 * @note Reading register DR automatically clears ADC flag EOC
1463 * (ADC group regular end of unitary conversion).
1464 * @note This function does not clear ADC flag EOS
1465 * (ADC group regular end of sequence conversion).
1466 * Occurrence of flag EOS rising:
1467 * - If sequencer is composed of 1 rank, flag EOS is equivalent
1469 * - If sequencer is composed of several ranks, during the scan
1470 * sequence flag EOC only is raised, at the end of the scan sequence
1471 * both flags EOC and EOS are raised.
1472 * To clear this flag, either use function:
1473 * in programming model IT: @ref HAL_ADC_IRQHandler(), in programming
1474 * model polling: @ref HAL_ADC_PollForConversion()
1475 * or @ref __HAL_ADC_CLEAR_FLAG(&hadc, ADC_FLAG_EOS).
1476 * @param hadc: ADC handle
1477 * @retval ADC group regular conversion data
1479 uint32_t HAL_ADC_GetValue(ADC_HandleTypeDef
* hadc
)
1481 /* Check the parameters */
1482 assert_param(IS_ADC_ALL_INSTANCE(hadc
->Instance
));
1484 /* Note: EOC flag is not cleared here by software because automatically */
1485 /* cleared by hardware when reading register DR. */
1487 /* Return ADC converted value */
1488 return hadc
->Instance
->DR
;
1492 * @brief Handles ADC interrupt request
1493 * @param hadc: ADC handle
1496 void HAL_ADC_IRQHandler(ADC_HandleTypeDef
* hadc
)
1498 /* Check the parameters */
1499 assert_param(IS_ADC_ALL_INSTANCE(hadc
->Instance
));
1500 assert_param(IS_FUNCTIONAL_STATE(hadc
->Init
.ContinuousConvMode
));
1501 assert_param(IS_ADC_REGULAR_NB_CONV(hadc
->Init
.NbrOfConversion
));
1504 /* ========== Check End of Conversion flag for regular group ========== */
1505 if(__HAL_ADC_GET_IT_SOURCE(hadc
, ADC_IT_EOC
))
1507 if(__HAL_ADC_GET_FLAG(hadc
, ADC_FLAG_EOC
) )
1509 /* Update state machine on conversion status if not in error state */
1510 if (HAL_IS_BIT_CLR(hadc
->State
, HAL_ADC_STATE_ERROR_INTERNAL
))
1513 SET_BIT(hadc
->State
, HAL_ADC_STATE_REG_EOC
);
1516 /* Determine whether any further conversion upcoming on group regular */
1517 /* by external trigger, continuous mode or scan sequence on going. */
1518 /* Note: On STM32F1 devices, in case of sequencer enabled */
1519 /* (several ranks selected), end of conversion flag is raised */
1520 /* at the end of the sequence. */
1521 if(ADC_IS_SOFTWARE_START_REGULAR(hadc
) &&
1522 (hadc
->Init
.ContinuousConvMode
== DISABLE
) )
1524 /* Disable ADC end of conversion interrupt on group regular */
1525 __HAL_ADC_DISABLE_IT(hadc
, ADC_IT_EOC
);
1528 CLEAR_BIT(hadc
->State
, HAL_ADC_STATE_REG_BUSY
);
1530 if (HAL_IS_BIT_CLR(hadc
->State
, HAL_ADC_STATE_INJ_BUSY
))
1532 SET_BIT(hadc
->State
, HAL_ADC_STATE_READY
);
1536 /* Conversion complete callback */
1537 HAL_ADC_ConvCpltCallback(hadc
);
1539 /* Clear regular group conversion flag */
1540 __HAL_ADC_CLEAR_FLAG(hadc
, ADC_FLAG_STRT
| ADC_FLAG_EOC
);
1544 /* ========== Check End of Conversion flag for injected group ========== */
1545 if(__HAL_ADC_GET_IT_SOURCE(hadc
, ADC_IT_JEOC
))
1547 if(__HAL_ADC_GET_FLAG(hadc
, ADC_FLAG_JEOC
))
1549 /* Update state machine on conversion status if not in error state */
1550 if (HAL_IS_BIT_CLR(hadc
->State
, HAL_ADC_STATE_ERROR_INTERNAL
))
1553 SET_BIT(hadc
->State
, HAL_ADC_STATE_INJ_EOC
);
1556 /* Determine whether any further conversion upcoming on group injected */
1557 /* by external trigger, scan sequence on going or by automatic injected */
1558 /* conversion from group regular (same conditions as group regular */
1559 /* interruption disabling above). */
1560 /* Note: On STM32F1 devices, in case of sequencer enabled */
1561 /* (several ranks selected), end of conversion flag is raised */
1562 /* at the end of the sequence. */
1563 if(ADC_IS_SOFTWARE_START_INJECTED(hadc
) ||
1564 (HAL_IS_BIT_CLR(hadc
->Instance
->CR1
, ADC_CR1_JAUTO
) &&
1565 (ADC_IS_SOFTWARE_START_REGULAR(hadc
) &&
1566 (hadc
->Init
.ContinuousConvMode
== DISABLE
) ) ) )
1568 /* Disable ADC end of conversion interrupt on group injected */
1569 __HAL_ADC_DISABLE_IT(hadc
, ADC_IT_JEOC
);
1572 CLEAR_BIT(hadc
->State
, HAL_ADC_STATE_INJ_BUSY
);
1574 if (HAL_IS_BIT_CLR(hadc
->State
, HAL_ADC_STATE_REG_BUSY
))
1576 SET_BIT(hadc
->State
, HAL_ADC_STATE_READY
);
1580 /* Conversion complete callback */
1581 HAL_ADCEx_InjectedConvCpltCallback(hadc
);
1583 /* Clear injected group conversion flag */
1584 __HAL_ADC_CLEAR_FLAG(hadc
, (ADC_FLAG_JSTRT
| ADC_FLAG_JEOC
));
1588 /* ========== Check Analog watchdog flags ========== */
1589 if(__HAL_ADC_GET_IT_SOURCE(hadc
, ADC_IT_AWD
))
1591 if(__HAL_ADC_GET_FLAG(hadc
, ADC_FLAG_AWD
))
1594 SET_BIT(hadc
->State
, HAL_ADC_STATE_AWD1
);
1596 /* Level out of window callback */
1597 HAL_ADC_LevelOutOfWindowCallback(hadc
);
1599 /* Clear the ADC analog watchdog flag */
1600 __HAL_ADC_CLEAR_FLAG(hadc
, ADC_FLAG_AWD
);
1607 * @brief Conversion complete callback in non blocking mode
1608 * @param hadc: ADC handle
1611 __weak
void HAL_ADC_ConvCpltCallback(ADC_HandleTypeDef
* hadc
)
1613 /* Prevent unused argument(s) compilation warning */
1615 /* NOTE : This function should not be modified. When the callback is needed,
1616 function HAL_ADC_ConvCpltCallback must be implemented in the user file.
1621 * @brief Conversion DMA half-transfer callback in non blocking mode
1622 * @param hadc: ADC handle
1625 __weak
void HAL_ADC_ConvHalfCpltCallback(ADC_HandleTypeDef
* hadc
)
1627 /* Prevent unused argument(s) compilation warning */
1629 /* NOTE : This function should not be modified. When the callback is needed,
1630 function HAL_ADC_ConvHalfCpltCallback must be implemented in the user file.
1635 * @brief Analog watchdog callback in non blocking mode.
1636 * @param hadc: ADC handle
1639 __weak
void HAL_ADC_LevelOutOfWindowCallback(ADC_HandleTypeDef
* hadc
)
1641 /* Prevent unused argument(s) compilation warning */
1643 /* NOTE : This function should not be modified. When the callback is needed,
1644 function HAL_ADC_LevelOutOfWindowCallback must be implemented in the user file.
1649 * @brief ADC error callback in non blocking mode
1650 * (ADC conversion with interruption or transfer by DMA)
1651 * @param hadc: ADC handle
1654 __weak
void HAL_ADC_ErrorCallback(ADC_HandleTypeDef
*hadc
)
1656 /* Prevent unused argument(s) compilation warning */
1658 /* NOTE : This function should not be modified. When the callback is needed,
1659 function HAL_ADC_ErrorCallback must be implemented in the user file.
1668 /** @defgroup ADC_Exported_Functions_Group3 Peripheral Control functions
1669 * @brief Peripheral Control functions
1672 ===============================================================================
1673 ##### Peripheral Control functions #####
1674 ===============================================================================
1675 [..] This section provides functions allowing to:
1676 (+) Configure channels on regular group
1677 (+) Configure the analog watchdog
1684 * @brief Configures the the selected channel to be linked to the regular
1686 * @note In case of usage of internal measurement channels:
1687 * Vbat/VrefInt/TempSensor.
1688 * These internal paths can be be disabled using function
1690 * @note Possibility to update parameters on the fly:
1691 * This function initializes channel into regular group, following
1692 * calls to this function can be used to reconfigure some parameters
1693 * of structure "ADC_ChannelConfTypeDef" on the fly, without reseting
1695 * The setting of these parameters is conditioned to ADC state.
1696 * For parameters constraints, see comments of structure
1697 * "ADC_ChannelConfTypeDef".
1698 * @param hadc: ADC handle
1699 * @param sConfig: Structure of ADC channel for regular group.
1700 * @retval HAL status
1702 HAL_StatusTypeDef
HAL_ADC_ConfigChannel(ADC_HandleTypeDef
* hadc
, ADC_ChannelConfTypeDef
* sConfig
)
1704 HAL_StatusTypeDef tmp_hal_status
= HAL_OK
;
1705 __IO
uint32_t wait_loop_index
= 0U;
1707 /* Check the parameters */
1708 assert_param(IS_ADC_ALL_INSTANCE(hadc
->Instance
));
1709 assert_param(IS_ADC_CHANNEL(sConfig
->Channel
));
1710 assert_param(IS_ADC_REGULAR_RANK(sConfig
->Rank
));
1711 assert_param(IS_ADC_SAMPLE_TIME(sConfig
->SamplingTime
));
1713 /* Process locked */
1717 /* Regular sequence configuration */
1718 /* For Rank 1 to 6 */
1719 if (sConfig
->Rank
< 7U)
1721 MODIFY_REG(hadc
->Instance
->SQR3
,
1722 ADC_SQR3_RK(ADC_SQR3_SQ1
, sConfig
->Rank
) ,
1723 ADC_SQR3_RK(sConfig
->Channel
, sConfig
->Rank
) );
1725 /* For Rank 7 to 12 */
1726 else if (sConfig
->Rank
< 13U)
1728 MODIFY_REG(hadc
->Instance
->SQR2
,
1729 ADC_SQR2_RK(ADC_SQR2_SQ7
, sConfig
->Rank
) ,
1730 ADC_SQR2_RK(sConfig
->Channel
, sConfig
->Rank
) );
1732 /* For Rank 13 to 16 */
1735 MODIFY_REG(hadc
->Instance
->SQR1
,
1736 ADC_SQR1_RK(ADC_SQR1_SQ13
, sConfig
->Rank
) ,
1737 ADC_SQR1_RK(sConfig
->Channel
, sConfig
->Rank
) );
1741 /* Channel sampling time configuration */
1742 /* For channels 10 to 17 */
1743 if (sConfig
->Channel
>= ADC_CHANNEL_10
)
1745 MODIFY_REG(hadc
->Instance
->SMPR1
,
1746 ADC_SMPR1(ADC_SMPR1_SMP10
, sConfig
->Channel
) ,
1747 ADC_SMPR1(sConfig
->SamplingTime
, sConfig
->Channel
) );
1749 else /* For channels 0 to 9 */
1751 MODIFY_REG(hadc
->Instance
->SMPR2
,
1752 ADC_SMPR2(ADC_SMPR2_SMP0
, sConfig
->Channel
) ,
1753 ADC_SMPR2(sConfig
->SamplingTime
, sConfig
->Channel
) );
1756 /* If ADC1 Channel_16 or Channel_17 is selected, enable Temperature sensor */
1757 /* and VREFINT measurement path. */
1758 if ((sConfig
->Channel
== ADC_CHANNEL_TEMPSENSOR
) ||
1759 (sConfig
->Channel
== ADC_CHANNEL_VREFINT
) )
1761 /* For STM32F1 devices with several ADC: Only ADC1 can access internal */
1762 /* measurement channels (VrefInt/TempSensor). If these channels are */
1763 /* intended to be set on other ADC instances, an error is reported. */
1764 if (hadc
->Instance
== ADC1
)
1766 if (READ_BIT(hadc
->Instance
->CR2
, ADC_CR2_TSVREFE
) == RESET
)
1768 SET_BIT(hadc
->Instance
->CR2
, ADC_CR2_TSVREFE
);
1770 if ((sConfig
->Channel
== ADC_CHANNEL_TEMPSENSOR
))
1772 /* Delay for temperature sensor stabilization time */
1773 /* Compute number of CPU cycles to wait for */
1774 wait_loop_index
= (ADC_TEMPSENSOR_DELAY_US
* (SystemCoreClock
/ 1000000U));
1775 while(wait_loop_index
!= 0U)
1784 /* Update ADC state machine to error */
1785 SET_BIT(hadc
->State
, HAL_ADC_STATE_ERROR_CONFIG
);
1787 tmp_hal_status
= HAL_ERROR
;
1791 /* Process unlocked */
1794 /* Return function status */
1795 return tmp_hal_status
;
1799 * @brief Configures the analog watchdog.
1800 * @note Analog watchdog thresholds can be modified while ADC conversion
1802 * In this case, some constraints must be taken into account:
1803 * the programmed threshold values are effective from the next
1804 * ADC EOC (end of unitary conversion).
1805 * Considering that registers write delay may happen due to
1806 * bus activity, this might cause an uncertainty on the
1807 * effective timing of the new programmed threshold values.
1808 * @param hadc: ADC handle
1809 * @param AnalogWDGConfig: Structure of ADC analog watchdog configuration
1810 * @retval HAL status
1812 HAL_StatusTypeDef
HAL_ADC_AnalogWDGConfig(ADC_HandleTypeDef
* hadc
, ADC_AnalogWDGConfTypeDef
* AnalogWDGConfig
)
1814 /* Check the parameters */
1815 assert_param(IS_ADC_ALL_INSTANCE(hadc
->Instance
));
1816 assert_param(IS_ADC_ANALOG_WATCHDOG_MODE(AnalogWDGConfig
->WatchdogMode
));
1817 assert_param(IS_FUNCTIONAL_STATE(AnalogWDGConfig
->ITMode
));
1818 assert_param(IS_ADC_RANGE(AnalogWDGConfig
->HighThreshold
));
1819 assert_param(IS_ADC_RANGE(AnalogWDGConfig
->LowThreshold
));
1821 if((AnalogWDGConfig
->WatchdogMode
== ADC_ANALOGWATCHDOG_SINGLE_REG
) ||
1822 (AnalogWDGConfig
->WatchdogMode
== ADC_ANALOGWATCHDOG_SINGLE_INJEC
) ||
1823 (AnalogWDGConfig
->WatchdogMode
== ADC_ANALOGWATCHDOG_SINGLE_REGINJEC
) )
1825 assert_param(IS_ADC_CHANNEL(AnalogWDGConfig
->Channel
));
1828 /* Process locked */
1831 /* Analog watchdog configuration */
1833 /* Configure ADC Analog watchdog interrupt */
1834 if(AnalogWDGConfig
->ITMode
== ENABLE
)
1836 /* Enable the ADC Analog watchdog interrupt */
1837 __HAL_ADC_ENABLE_IT(hadc
, ADC_IT_AWD
);
1841 /* Disable the ADC Analog watchdog interrupt */
1842 __HAL_ADC_DISABLE_IT(hadc
, ADC_IT_AWD
);
1845 /* Configuration of analog watchdog: */
1846 /* - Set the analog watchdog enable mode: regular and/or injected groups, */
1847 /* one or all channels. */
1848 /* - Set the Analog watchdog channel (is not used if watchdog */
1849 /* mode "all channels": ADC_CFGR_AWD1SGL=0). */
1850 MODIFY_REG(hadc
->Instance
->CR1
,
1855 AnalogWDGConfig
->WatchdogMode
|
1856 AnalogWDGConfig
->Channel
);
1858 /* Set the high threshold */
1859 WRITE_REG(hadc
->Instance
->HTR
, AnalogWDGConfig
->HighThreshold
);
1861 /* Set the low threshold */
1862 WRITE_REG(hadc
->Instance
->LTR
, AnalogWDGConfig
->LowThreshold
);
1864 /* Process unlocked */
1867 /* Return function status */
1877 /** @defgroup ADC_Exported_Functions_Group4 Peripheral State functions
1878 * @brief Peripheral State functions
1881 ===============================================================================
1882 ##### Peripheral State and Errors functions #####
1883 ===============================================================================
1885 This subsection provides functions to get in run-time the status of the
1887 (+) Check the ADC state
1888 (+) Check the ADC error code
1895 * @brief return the ADC state
1896 * @param hadc: ADC handle
1899 uint32_t HAL_ADC_GetState(ADC_HandleTypeDef
* hadc
)
1901 /* Return ADC state */
1906 * @brief Return the ADC error code
1907 * @param hadc: ADC handle
1908 * @retval ADC Error Code
1910 uint32_t HAL_ADC_GetError(ADC_HandleTypeDef
*hadc
)
1912 return hadc
->ErrorCode
;
1923 /** @defgroup ADC_Private_Functions ADC Private Functions
1928 * @brief Enable the selected ADC.
1929 * @note Prerequisite condition to use this function: ADC must be disabled
1930 * and voltage regulator must be enabled (done into HAL_ADC_Init()).
1931 * @param hadc: ADC handle
1932 * @retval HAL status.
1934 HAL_StatusTypeDef
ADC_Enable(ADC_HandleTypeDef
* hadc
)
1936 uint32_t tickstart
= 0U;
1937 __IO
uint32_t wait_loop_index
= 0U;
1939 /* ADC enable and wait for ADC ready (in case of ADC is disabled or */
1940 /* enabling phase not yet completed: flag ADC ready not yet set). */
1941 /* Timeout implemented to not be stuck if ADC cannot be enabled (possible */
1942 /* causes: ADC clock not running, ...). */
1943 if (ADC_IS_ENABLE(hadc
) == RESET
)
1945 /* Enable the Peripheral */
1946 __HAL_ADC_ENABLE(hadc
);
1948 /* Delay for ADC stabilization time */
1949 /* Compute number of CPU cycles to wait for */
1950 wait_loop_index
= (ADC_STAB_DELAY_US
* (SystemCoreClock
/ 1000000U));
1951 while(wait_loop_index
!= 0U)
1956 /* Get tick count */
1957 tickstart
= HAL_GetTick();
1959 /* Wait for ADC effectively enabled */
1960 while(ADC_IS_ENABLE(hadc
) == RESET
)
1962 if((HAL_GetTick() - tickstart
) > ADC_ENABLE_TIMEOUT
)
1964 /* Update ADC state machine to error */
1965 SET_BIT(hadc
->State
, HAL_ADC_STATE_ERROR_INTERNAL
);
1967 /* Set ADC error code to ADC IP internal error */
1968 SET_BIT(hadc
->ErrorCode
, HAL_ADC_ERROR_INTERNAL
);
1970 /* Process unlocked */
1978 /* Return HAL status */
1983 * @brief Stop ADC conversion and disable the selected ADC
1984 * @note Prerequisite condition to use this function: ADC conversions must be
1985 * stopped to disable the ADC.
1986 * @param hadc: ADC handle
1987 * @retval HAL status.
1989 HAL_StatusTypeDef
ADC_ConversionStop_Disable(ADC_HandleTypeDef
* hadc
)
1991 uint32_t tickstart
= 0U;
1993 /* Verification if ADC is not already disabled */
1994 if (ADC_IS_ENABLE(hadc
) != RESET
)
1996 /* Disable the ADC peripheral */
1997 __HAL_ADC_DISABLE(hadc
);
1999 /* Get tick count */
2000 tickstart
= HAL_GetTick();
2002 /* Wait for ADC effectively disabled */
2003 while(ADC_IS_ENABLE(hadc
) != RESET
)
2005 if((HAL_GetTick() - tickstart
) > ADC_DISABLE_TIMEOUT
)
2007 /* Update ADC state machine to error */
2008 SET_BIT(hadc
->State
, HAL_ADC_STATE_ERROR_INTERNAL
);
2010 /* Set ADC error code to ADC IP internal error */
2011 SET_BIT(hadc
->ErrorCode
, HAL_ADC_ERROR_INTERNAL
);
2018 /* Return HAL status */
2023 * @brief DMA transfer complete callback.
2024 * @param hdma: pointer to DMA handle.
2027 void ADC_DMAConvCplt(DMA_HandleTypeDef
*hdma
)
2029 /* Retrieve ADC handle corresponding to current DMA handle */
2030 ADC_HandleTypeDef
* hadc
= ( ADC_HandleTypeDef
* )((DMA_HandleTypeDef
* )hdma
)->Parent
;
2032 /* Update state machine on conversion status if not in error state */
2033 if (HAL_IS_BIT_CLR(hadc
->State
, HAL_ADC_STATE_ERROR_INTERNAL
| HAL_ADC_STATE_ERROR_DMA
))
2035 /* Update ADC state machine */
2036 SET_BIT(hadc
->State
, HAL_ADC_STATE_REG_EOC
);
2038 /* Determine whether any further conversion upcoming on group regular */
2039 /* by external trigger, continuous mode or scan sequence on going. */
2040 /* Note: On STM32F1 devices, in case of sequencer enabled */
2041 /* (several ranks selected), end of conversion flag is raised */
2042 /* at the end of the sequence. */
2043 if(ADC_IS_SOFTWARE_START_REGULAR(hadc
) &&
2044 (hadc
->Init
.ContinuousConvMode
== DISABLE
) )
2047 CLEAR_BIT(hadc
->State
, HAL_ADC_STATE_REG_BUSY
);
2049 if (HAL_IS_BIT_CLR(hadc
->State
, HAL_ADC_STATE_INJ_BUSY
))
2051 SET_BIT(hadc
->State
, HAL_ADC_STATE_READY
);
2055 /* Conversion complete callback */
2056 HAL_ADC_ConvCpltCallback(hadc
);
2060 /* Call DMA error callback */
2061 hadc
->DMA_Handle
->XferErrorCallback(hdma
);
2066 * @brief DMA half transfer complete callback.
2067 * @param hdma: pointer to DMA handle.
2070 void ADC_DMAHalfConvCplt(DMA_HandleTypeDef
*hdma
)
2072 /* Retrieve ADC handle corresponding to current DMA handle */
2073 ADC_HandleTypeDef
* hadc
= ( ADC_HandleTypeDef
* )((DMA_HandleTypeDef
* )hdma
)->Parent
;
2075 /* Half conversion callback */
2076 HAL_ADC_ConvHalfCpltCallback(hadc
);
2080 * @brief DMA error callback
2081 * @param hdma: pointer to DMA handle.
2084 void ADC_DMAError(DMA_HandleTypeDef
*hdma
)
2086 /* Retrieve ADC handle corresponding to current DMA handle */
2087 ADC_HandleTypeDef
* hadc
= ( ADC_HandleTypeDef
* )((DMA_HandleTypeDef
* )hdma
)->Parent
;
2090 SET_BIT(hadc
->State
, HAL_ADC_STATE_ERROR_DMA
);
2092 /* Set ADC error code to DMA error */
2093 SET_BIT(hadc
->ErrorCode
, HAL_ADC_ERROR_DMA
);
2095 /* Error callback */
2096 HAL_ADC_ErrorCallback(hadc
);
2103 #endif /* HAL_ADC_MODULE_ENABLED */
2112 /************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/