2 ******************************************************************************
3 * @file stm32f4xx_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) peripheral:
9 * + Initialization and de-initialization functions
10 * + IO operation functions
11 * + State and errors functions
14 ==============================================================================
15 ##### ADC Peripheral features #####
16 ==============================================================================
18 (#) 12-bit, 10-bit, 8-bit or 6-bit configurable resolution.
19 (#) Interrupt generation at the end of conversion, end of injected conversion,
20 and in case of analog watchdog or overrun events
21 (#) Single and continuous conversion modes.
22 (#) Scan mode for automatic conversion of channel 0 to channel x.
23 (#) Data alignment with in-built data coherency.
24 (#) Channel-wise programmable sampling time.
25 (#) External trigger option with configurable polarity for both regular and
27 (#) Dual/Triple mode (on devices with 2 ADCs or more).
28 (#) Configurable DMA data storage in Dual/Triple ADC mode.
29 (#) Configurable delay between conversions in Dual/Triple interleaved mode.
30 (#) ADC conversion type (refer to the datasheets).
31 (#) ADC supply requirements: 2.4 V to 3.6 V at full speed and down to 1.8 V at
33 (#) ADC input range: VREF(minus) = VIN = VREF(plus).
34 (#) DMA request generation during regular channel conversion.
37 ##### How to use this driver #####
38 ==============================================================================
40 (#)Initialize the ADC low level resources by implementing the HAL_ADC_MspInit():
41 (##) Enable the ADC interface clock using __HAL_RCC_ADC_CLK_ENABLE()
42 (##) ADC pins configuration
43 (+++) Enable the clock for the ADC GPIOs using the following function:
44 __HAL_RCC_GPIOx_CLK_ENABLE()
45 (+++) Configure these ADC pins in analog mode using HAL_GPIO_Init()
46 (##) In case of using interrupts (e.g. HAL_ADC_Start_IT())
47 (+++) Configure the ADC interrupt priority using HAL_NVIC_SetPriority()
48 (+++) Enable the ADC IRQ handler using HAL_NVIC_EnableIRQ()
49 (+++) In ADC IRQ handler, call HAL_ADC_IRQHandler()
50 (##) In case of using DMA to control data transfer (e.g. HAL_ADC_Start_DMA())
51 (+++) Enable the DMAx interface clock using __HAL_RCC_DMAx_CLK_ENABLE()
52 (+++) Configure and enable two DMA streams stream for managing data
53 transfer from peripheral to memory (output stream)
54 (+++) Associate the initialized DMA handle to the CRYP DMA handle
56 (+++) Configure the priority and enable the NVIC for the transfer complete
57 interrupt on the two DMA Streams. The output stream should have higher
58 priority than the input stream.
60 *** Configuration of ADC, groups regular/injected, channels parameters ***
61 ==============================================================================
63 (#) Configure the ADC parameters (resolution, data alignment, ...)
64 and regular group parameters (conversion trigger, sequencer, ...)
65 using function HAL_ADC_Init().
67 (#) Configure the channels for regular group parameters (channel number,
68 channel rank into sequencer, ..., into regular group)
69 using function HAL_ADC_ConfigChannel().
71 (#) Optionally, configure the injected group parameters (conversion trigger,
72 sequencer, ..., of injected group)
73 and the channels for injected group parameters (channel number,
74 channel rank into sequencer, ..., into injected group)
75 using function HAL_ADCEx_InjectedConfigChannel().
77 (#) Optionally, configure the analog watchdog parameters (channels
78 monitored, thresholds, ...) using function HAL_ADC_AnalogWDGConfig().
80 (#) Optionally, for devices with several ADC instances: configure the
81 multimode parameters using function HAL_ADCEx_MultiModeConfigChannel().
83 *** Execution of ADC conversions ***
84 ==============================================================================
86 (#) ADC driver can be used among three modes: polling, interruption,
89 *** Polling mode IO operation ***
90 =================================
92 (+) Start the ADC peripheral using HAL_ADC_Start()
93 (+) Wait for end of conversion using HAL_ADC_PollForConversion(), at this stage
94 user can specify the value of timeout according to his end application
95 (+) To read the ADC converted values, use the HAL_ADC_GetValue() function.
96 (+) Stop the ADC peripheral using HAL_ADC_Stop()
98 *** Interrupt mode IO operation ***
99 ===================================
101 (+) Start the ADC peripheral using HAL_ADC_Start_IT()
102 (+) Use HAL_ADC_IRQHandler() called under ADC_IRQHandler() Interrupt subroutine
103 (+) At ADC end of conversion HAL_ADC_ConvCpltCallback() function is executed and user can
104 add his own code by customization of function pointer HAL_ADC_ConvCpltCallback
105 (+) In case of ADC Error, HAL_ADC_ErrorCallback() function is executed and user can
106 add his own code by customization of function pointer HAL_ADC_ErrorCallback
107 (+) Stop the ADC peripheral using HAL_ADC_Stop_IT()
109 *** DMA mode IO operation ***
110 ==============================
112 (+) Start the ADC peripheral using HAL_ADC_Start_DMA(), at this stage the user specify the length
113 of data to be transferred at each end of conversion
114 (+) At The end of data transfer by HAL_ADC_ConvCpltCallback() function is executed and user can
115 add his own code by customization of function pointer HAL_ADC_ConvCpltCallback
116 (+) In case of transfer Error, HAL_ADC_ErrorCallback() function is executed and user can
117 add his own code by customization of function pointer HAL_ADC_ErrorCallback
118 (+) Stop the ADC peripheral using HAL_ADC_Stop_DMA()
120 *** ADC HAL driver macros list ***
121 =============================================
123 Below the list of most used macros in ADC HAL driver.
125 (+) __HAL_ADC_ENABLE : Enable the ADC peripheral
126 (+) __HAL_ADC_DISABLE : Disable the ADC peripheral
127 (+) __HAL_ADC_ENABLE_IT: Enable the ADC end of conversion interrupt
128 (+) __HAL_ADC_DISABLE_IT: Disable the ADC end of conversion interrupt
129 (+) __HAL_ADC_GET_IT_SOURCE: Check if the specified ADC interrupt source is enabled or disabled
130 (+) __HAL_ADC_CLEAR_FLAG: Clear the ADC's pending flags
131 (+) __HAL_ADC_GET_FLAG: Get the selected ADC's flag status
132 (+) ADC_GET_RESOLUTION: Return resolution bits in CR1 register
135 (@) You can refer to the ADC HAL driver header file for more useful macros
137 *** Deinitialization of ADC ***
138 ==============================================================================
140 (#) Disable the ADC interface
141 (++) ADC clock can be hard reset and disabled at RCC top level.
142 (++) Hard reset of ADC peripherals
143 using macro __HAL_RCC_ADC_FORCE_RESET(), __HAL_RCC_ADC_RELEASE_RESET().
144 (++) ADC clock disable using the equivalent macro/functions as configuration step.
146 Into HAL_ADC_MspDeInit() (recommended code location) or with
147 other device clock parameters configuration:
148 (+++) HAL_RCC_GetOscConfig(&RCC_OscInitStructure);
149 (+++) RCC_OscInitStructure.OscillatorType = RCC_OSCILLATORTYPE_HSI;
150 (+++) RCC_OscInitStructure.HSIState = RCC_HSI_OFF; (if not used for system clock)
151 (+++) HAL_RCC_OscConfig(&RCC_OscInitStructure);
153 (#) ADC pins configuration
154 (++) Disable the clock for the ADC GPIOs using macro __HAL_RCC_GPIOx_CLK_DISABLE()
156 (#) Optionally, in case of usage of ADC with interruptions:
157 (++) Disable the NVIC for ADC using function HAL_NVIC_DisableIRQ(ADCx_IRQn)
159 (#) Optionally, in case of usage of DMA:
160 (++) Deinitialize the DMA using function HAL_DMA_DeInit().
161 (++) Disable the NVIC for DMA using function HAL_NVIC_DisableIRQ(DMAx_Channelx_IRQn)
164 ******************************************************************************
167 * <h2><center>© COPYRIGHT(c) 2017 STMicroelectronics</center></h2>
169 * Redistribution and use in source and binary forms, with or without modification,
170 * are permitted provided that the following conditions are met:
171 * 1. Redistributions of source code must retain the above copyright notice,
172 * this list of conditions and the following disclaimer.
173 * 2. Redistributions in binary form must reproduce the above copyright notice,
174 * this list of conditions and the following disclaimer in the documentation
175 * and/or other materials provided with the distribution.
176 * 3. Neither the name of STMicroelectronics nor the names of its contributors
177 * may be used to endorse or promote products derived from this software
178 * without specific prior written permission.
180 * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
181 * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
182 * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE
183 * DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE
184 * FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL
185 * DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR
186 * SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
187 * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY,
188 * OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE
189 * OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
191 ******************************************************************************
194 /* Includes ------------------------------------------------------------------*/
195 #include "stm32f4xx_hal.h"
197 /** @addtogroup STM32F4xx_HAL_Driver
201 /** @defgroup ADC ADC
202 * @brief ADC driver modules
206 #ifdef HAL_ADC_MODULE_ENABLED
208 /* Private typedef -----------------------------------------------------------*/
209 /* Private define ------------------------------------------------------------*/
210 /* Private macro -------------------------------------------------------------*/
211 /* Private variables ---------------------------------------------------------*/
212 /** @addtogroup ADC_Private_Functions
215 /* Private function prototypes -----------------------------------------------*/
216 static void ADC_Init(ADC_HandleTypeDef
* hadc
);
217 static void ADC_DMAConvCplt(DMA_HandleTypeDef
*hdma
);
218 static void ADC_DMAError(DMA_HandleTypeDef
*hdma
);
219 static void ADC_DMAHalfConvCplt(DMA_HandleTypeDef
*hdma
);
223 /* Exported functions --------------------------------------------------------*/
224 /** @defgroup ADC_Exported_Functions ADC Exported Functions
228 /** @defgroup ADC_Exported_Functions_Group1 Initialization and de-initialization functions
229 * @brief Initialization and Configuration functions
232 ===============================================================================
233 ##### Initialization and de-initialization functions #####
234 ===============================================================================
235 [..] This section provides functions allowing to:
236 (+) Initialize and configure the ADC.
237 (+) De-initialize the ADC.
244 * @brief Initializes the ADCx peripheral according to the specified parameters
245 * in the ADC_InitStruct and initializes the ADC MSP.
247 * @note This function is used to configure the global features of the ADC (
248 * ClockPrescaler, Resolution, Data Alignment and number of conversion), however,
249 * the rest of the configuration parameters are specific to the regular
250 * channels group (scan mode activation, continuous mode activation,
251 * External trigger source and edge, DMA continuous request after the
252 * last transfer and End of conversion selection).
254 * @param hadc: pointer to a ADC_HandleTypeDef structure that contains
255 * the configuration information for the specified ADC.
258 HAL_StatusTypeDef
HAL_ADC_Init(ADC_HandleTypeDef
* hadc
)
260 HAL_StatusTypeDef tmp_hal_status
= HAL_OK
;
262 /* Check ADC handle */
268 /* Check the parameters */
269 assert_param(IS_ADC_ALL_INSTANCE(hadc
->Instance
));
270 assert_param(IS_ADC_CLOCKPRESCALER(hadc
->Init
.ClockPrescaler
));
271 assert_param(IS_ADC_RESOLUTION(hadc
->Init
.Resolution
));
272 assert_param(IS_FUNCTIONAL_STATE(hadc
->Init
.ScanConvMode
));
273 assert_param(IS_FUNCTIONAL_STATE(hadc
->Init
.ContinuousConvMode
));
274 assert_param(IS_ADC_EXT_TRIG(hadc
->Init
.ExternalTrigConv
));
275 assert_param(IS_ADC_DATA_ALIGN(hadc
->Init
.DataAlign
));
276 assert_param(IS_ADC_REGULAR_LENGTH(hadc
->Init
.NbrOfConversion
));
277 assert_param(IS_FUNCTIONAL_STATE(hadc
->Init
.DMAContinuousRequests
));
278 assert_param(IS_ADC_EOCSelection(hadc
->Init
.EOCSelection
));
279 assert_param(IS_FUNCTIONAL_STATE(hadc
->Init
.DiscontinuousConvMode
));
281 if(hadc
->Init
.ExternalTrigConv
!= ADC_SOFTWARE_START
)
283 assert_param(IS_ADC_EXT_TRIG_EDGE(hadc
->Init
.ExternalTrigConvEdge
));
286 if(hadc
->State
== HAL_ADC_STATE_RESET
)
288 /* Initialize ADC error code */
289 ADC_CLEAR_ERRORCODE(hadc
);
291 /* Allocate lock resource and initialize it */
292 hadc
->Lock
= HAL_UNLOCKED
;
294 /* Init the low level hardware */
295 HAL_ADC_MspInit(hadc
);
298 /* Configuration of ADC parameters if previous preliminary actions are */
299 /* correctly completed. */
300 if (HAL_IS_BIT_CLR(hadc
->State
, HAL_ADC_STATE_ERROR_INTERNAL
))
303 ADC_STATE_CLR_SET(hadc
->State
,
304 HAL_ADC_STATE_REG_BUSY
| HAL_ADC_STATE_INJ_BUSY
,
305 HAL_ADC_STATE_BUSY_INTERNAL
);
307 /* Set ADC parameters */
310 /* Set ADC error code to none */
311 ADC_CLEAR_ERRORCODE(hadc
);
313 /* Set the ADC state */
314 ADC_STATE_CLR_SET(hadc
->State
,
315 HAL_ADC_STATE_BUSY_INTERNAL
,
316 HAL_ADC_STATE_READY
);
320 tmp_hal_status
= HAL_ERROR
;
326 /* Return function status */
327 return tmp_hal_status
;
331 * @brief Deinitializes the ADCx peripheral registers to their default reset values.
332 * @param hadc: pointer to a ADC_HandleTypeDef structure that contains
333 * the configuration information for the specified ADC.
336 HAL_StatusTypeDef
HAL_ADC_DeInit(ADC_HandleTypeDef
* hadc
)
338 HAL_StatusTypeDef tmp_hal_status
= HAL_OK
;
340 /* Check ADC handle */
346 /* Check the parameters */
347 assert_param(IS_ADC_ALL_INSTANCE(hadc
->Instance
));
350 SET_BIT(hadc
->State
, HAL_ADC_STATE_BUSY_INTERNAL
);
352 /* Stop potential conversion on going, on regular and injected groups */
353 /* Disable ADC peripheral */
354 __HAL_ADC_DISABLE(hadc
);
356 /* Configuration of ADC parameters if previous preliminary actions are */
357 /* correctly completed. */
358 if(HAL_IS_BIT_CLR(hadc
->Instance
->CR2
, ADC_CR2_ADON
))
360 /* DeInit the low level hardware */
361 HAL_ADC_MspDeInit(hadc
);
363 /* Set ADC error code to none */
364 ADC_CLEAR_ERRORCODE(hadc
);
367 hadc
->State
= HAL_ADC_STATE_RESET
;
370 /* Process unlocked */
373 /* Return function status */
374 return tmp_hal_status
;
378 * @brief Initializes the ADC MSP.
379 * @param hadc: pointer to a ADC_HandleTypeDef structure that contains
380 * the configuration information for the specified ADC.
383 __weak
void HAL_ADC_MspInit(ADC_HandleTypeDef
* hadc
)
385 /* Prevent unused argument(s) compilation warning */
387 /* NOTE : This function Should not be modified, when the callback is needed,
388 the HAL_ADC_MspInit could be implemented in the user file
393 * @brief DeInitializes the ADC MSP.
394 * @param hadc: pointer to a ADC_HandleTypeDef structure that contains
395 * the configuration information for the specified ADC.
398 __weak
void HAL_ADC_MspDeInit(ADC_HandleTypeDef
* hadc
)
400 /* Prevent unused argument(s) compilation warning */
402 /* NOTE : This function Should not be modified, when the callback is needed,
403 the HAL_ADC_MspDeInit could be implemented in the user file
411 /** @defgroup ADC_Exported_Functions_Group2 IO operation functions
412 * @brief IO operation functions
415 ===============================================================================
416 ##### IO operation functions #####
417 ===============================================================================
418 [..] This section provides functions allowing to:
419 (+) Start conversion of regular channel.
420 (+) Stop conversion of regular channel.
421 (+) Start conversion of regular channel and enable interrupt.
422 (+) Stop conversion of regular channel and disable interrupt.
423 (+) Start conversion of regular channel and enable DMA transfer.
424 (+) Stop conversion of regular channel and disable DMA transfer.
425 (+) Handle ADC interrupt request.
432 * @brief Enables ADC and starts conversion of the regular channels.
433 * @param hadc: pointer to a ADC_HandleTypeDef structure that contains
434 * the configuration information for the specified ADC.
437 HAL_StatusTypeDef
HAL_ADC_Start(ADC_HandleTypeDef
* hadc
)
439 __IO
uint32_t counter
= 0U;
440 ADC_Common_TypeDef
*tmpADC_Common
;
442 /* Check the parameters */
443 assert_param(IS_FUNCTIONAL_STATE(hadc
->Init
.ContinuousConvMode
));
444 assert_param(IS_ADC_EXT_TRIG_EDGE(hadc
->Init
.ExternalTrigConvEdge
));
449 /* Enable the ADC peripheral */
450 /* Check if ADC peripheral is disabled in order to enable it and wait during
451 Tstab time the ADC's stabilization */
452 if((hadc
->Instance
->CR2
& ADC_CR2_ADON
) != ADC_CR2_ADON
)
454 /* Enable the Peripheral */
455 __HAL_ADC_ENABLE(hadc
);
457 /* Delay for ADC stabilization time */
458 /* Compute number of CPU cycles to wait for */
459 counter
= (ADC_STAB_DELAY_US
* (SystemCoreClock
/ 1000000U));
466 /* Start conversion if ADC is effectively enabled */
467 if(HAL_IS_BIT_SET(hadc
->Instance
->CR2
, ADC_CR2_ADON
))
470 /* - Clear state bitfield related to regular group conversion results */
471 /* - Set state bitfield related to regular group operation */
472 ADC_STATE_CLR_SET(hadc
->State
,
473 HAL_ADC_STATE_READY
| HAL_ADC_STATE_REG_EOC
| HAL_ADC_STATE_REG_OVR
,
474 HAL_ADC_STATE_REG_BUSY
);
476 /* If conversions on group regular are also triggering group injected, */
477 /* update ADC state. */
478 if (READ_BIT(hadc
->Instance
->CR1
, ADC_CR1_JAUTO
) != RESET
)
480 ADC_STATE_CLR_SET(hadc
->State
, HAL_ADC_STATE_INJ_EOC
, HAL_ADC_STATE_INJ_BUSY
);
483 /* State machine update: Check if an injected conversion is ongoing */
484 if (HAL_IS_BIT_SET(hadc
->State
, HAL_ADC_STATE_INJ_BUSY
))
486 /* Reset ADC error code fields related to conversions on group regular */
487 CLEAR_BIT(hadc
->ErrorCode
, (HAL_ADC_ERROR_OVR
| HAL_ADC_ERROR_DMA
));
491 /* Reset ADC all error code fields */
492 ADC_CLEAR_ERRORCODE(hadc
);
495 /* Process unlocked */
496 /* Unlock before starting ADC conversions: in case of potential */
497 /* interruption, to let the process to ADC IRQ Handler. */
500 /* Pointer to the common control register to which is belonging hadc */
501 /* (Depending on STM32F4 product, there may be up to 3 ADCs and 1 common */
502 /* control register) */
503 tmpADC_Common
= ADC_COMMON_REGISTER(hadc
);
505 /* Clear regular group conversion flag and overrun flag */
506 /* (To ensure of no unknown state from potential previous ADC operations) */
507 __HAL_ADC_CLEAR_FLAG(hadc
, ADC_FLAG_EOC
| ADC_FLAG_OVR
);
509 /* Check if Multimode enabled */
510 if(HAL_IS_BIT_CLR(tmpADC_Common
->CCR
, ADC_CCR_MULTI
))
512 /* if no external trigger present enable software conversion of regular channels */
513 if((hadc
->Instance
->CR2
& ADC_CR2_EXTEN
) == RESET
)
515 /* Enable the selected ADC software conversion for regular group */
516 hadc
->Instance
->CR2
|= (uint32_t)ADC_CR2_SWSTART
;
521 /* if instance of handle correspond to ADC1 and no external trigger present enable software conversion of regular channels */
522 if((hadc
->Instance
== ADC1
) && ((hadc
->Instance
->CR2
& ADC_CR2_EXTEN
) == RESET
))
524 /* Enable the selected ADC software conversion for regular group */
525 hadc
->Instance
->CR2
|= (uint32_t)ADC_CR2_SWSTART
;
530 /* Return function status */
535 * @brief Disables ADC and stop conversion of regular channels.
537 * @note Caution: This function will stop also injected channels.
539 * @param hadc: pointer to a ADC_HandleTypeDef structure that contains
540 * the configuration information for the specified ADC.
542 * @retval HAL status.
544 HAL_StatusTypeDef
HAL_ADC_Stop(ADC_HandleTypeDef
* hadc
)
546 /* Check the parameters */
547 assert_param(IS_ADC_ALL_INSTANCE(hadc
->Instance
));
552 /* Stop potential conversion on going, on regular and injected groups */
553 /* Disable ADC peripheral */
554 __HAL_ADC_DISABLE(hadc
);
556 /* Check if ADC is effectively disabled */
557 if(HAL_IS_BIT_CLR(hadc
->Instance
->CR2
, ADC_CR2_ADON
))
560 ADC_STATE_CLR_SET(hadc
->State
,
561 HAL_ADC_STATE_REG_BUSY
| HAL_ADC_STATE_INJ_BUSY
,
562 HAL_ADC_STATE_READY
);
565 /* Process unlocked */
568 /* Return function status */
573 * @brief Poll for regular conversion complete
574 * @note ADC conversion flags EOS (end of sequence) and EOC (end of
575 * conversion) are cleared by this function.
576 * @note This function cannot be used in a particular setup: ADC configured
577 * in DMA mode and polling for end of each conversion (ADC init
578 * parameter "EOCSelection" set to ADC_EOC_SINGLE_CONV).
579 * In this case, DMA resets the flag EOC and polling cannot be
580 * performed on each conversion. Nevertheless, polling can still
581 * be performed on the complete sequence.
582 * @param hadc: pointer to a ADC_HandleTypeDef structure that contains
583 * the configuration information for the specified ADC.
584 * @param Timeout: Timeout value in millisecond.
587 HAL_StatusTypeDef
HAL_ADC_PollForConversion(ADC_HandleTypeDef
* hadc
, uint32_t Timeout
)
589 uint32_t tickstart
= 0U;
591 /* Verification that ADC configuration is compliant with polling for */
592 /* each conversion: */
593 /* Particular case is ADC configured in DMA mode and ADC sequencer with */
594 /* several ranks and polling for end of each conversion. */
595 /* For code simplicity sake, this particular case is generalized to */
596 /* ADC configured in DMA mode and polling for end of each conversion. */
597 if (HAL_IS_BIT_SET(hadc
->Instance
->CR2
, ADC_CR2_EOCS
) &&
598 HAL_IS_BIT_SET(hadc
->Instance
->CR2
, ADC_CR2_DMA
) )
600 /* Update ADC state machine to error */
601 SET_BIT(hadc
->State
, HAL_ADC_STATE_ERROR_CONFIG
);
603 /* Process unlocked */
610 tickstart
= HAL_GetTick();
612 /* Check End of conversion flag */
613 while(!(__HAL_ADC_GET_FLAG(hadc
, ADC_FLAG_EOC
)))
615 /* Check if timeout is disabled (set to infinite wait) */
616 if(Timeout
!= HAL_MAX_DELAY
)
618 if((Timeout
== 0U) || ((HAL_GetTick() - tickstart
) > Timeout
))
620 /* Update ADC state machine to timeout */
621 SET_BIT(hadc
->State
, HAL_ADC_STATE_TIMEOUT
);
623 /* Process unlocked */
631 /* Clear regular group conversion flag */
632 __HAL_ADC_CLEAR_FLAG(hadc
, ADC_FLAG_STRT
| ADC_FLAG_EOC
);
634 /* Update ADC state machine */
635 SET_BIT(hadc
->State
, HAL_ADC_STATE_REG_EOC
);
637 /* Determine whether any further conversion upcoming on group regular */
638 /* by external trigger, continuous mode or scan sequence on going. */
639 /* Note: On STM32F4, there is no independent flag of end of sequence. */
640 /* The test of scan sequence on going is done either with scan */
641 /* sequence disabled or with end of conversion flag set to */
642 /* of end of sequence. */
643 if(ADC_IS_SOFTWARE_START_REGULAR(hadc
) &&
644 (hadc
->Init
.ContinuousConvMode
== DISABLE
) &&
645 (HAL_IS_BIT_CLR(hadc
->Instance
->SQR1
, ADC_SQR1_L
) ||
646 HAL_IS_BIT_CLR(hadc
->Instance
->CR2
, ADC_CR2_EOCS
) ) )
649 CLEAR_BIT(hadc
->State
, HAL_ADC_STATE_REG_BUSY
);
651 if (HAL_IS_BIT_CLR(hadc
->State
, HAL_ADC_STATE_INJ_BUSY
))
653 SET_BIT(hadc
->State
, HAL_ADC_STATE_READY
);
657 /* Return ADC state */
662 * @brief Poll for conversion event
663 * @param hadc: pointer to a ADC_HandleTypeDef structure that contains
664 * the configuration information for the specified ADC.
665 * @param EventType: the ADC event type.
666 * This parameter can be one of the following values:
667 * @arg ADC_AWD_EVENT: ADC Analog watch Dog event.
668 * @arg ADC_OVR_EVENT: ADC Overrun event.
669 * @param Timeout: Timeout value in millisecond.
672 HAL_StatusTypeDef
HAL_ADC_PollForEvent(ADC_HandleTypeDef
* hadc
, uint32_t EventType
, uint32_t Timeout
)
674 uint32_t tickstart
= 0U;
676 /* Check the parameters */
677 assert_param(IS_ADC_ALL_INSTANCE(hadc
->Instance
));
678 assert_param(IS_ADC_EVENT_TYPE(EventType
));
681 tickstart
= HAL_GetTick();
683 /* Check selected event flag */
684 while(!(__HAL_ADC_GET_FLAG(hadc
,EventType
)))
686 /* Check for the Timeout */
687 if(Timeout
!= HAL_MAX_DELAY
)
689 if((Timeout
== 0U) || ((HAL_GetTick() - tickstart
) > Timeout
))
691 /* Update ADC state machine to timeout */
692 SET_BIT(hadc
->State
, HAL_ADC_STATE_TIMEOUT
);
694 /* Process unlocked */
702 /* Analog watchdog (level out of window) event */
703 if(EventType
== ADC_AWD_EVENT
)
706 SET_BIT(hadc
->State
, HAL_ADC_STATE_AWD1
);
708 /* Clear ADC analog watchdog flag */
709 __HAL_ADC_CLEAR_FLAG(hadc
, ADC_FLAG_AWD
);
715 SET_BIT(hadc
->State
, HAL_ADC_STATE_REG_OVR
);
716 /* Set ADC error code to overrun */
717 SET_BIT(hadc
->ErrorCode
, HAL_ADC_ERROR_OVR
);
719 /* Clear ADC overrun flag */
720 __HAL_ADC_CLEAR_FLAG(hadc
, ADC_FLAG_OVR
);
723 /* Return ADC state */
729 * @brief Enables the interrupt and starts ADC conversion of regular channels.
730 * @param hadc: pointer to a ADC_HandleTypeDef structure that contains
731 * the configuration information for the specified ADC.
732 * @retval HAL status.
734 HAL_StatusTypeDef
HAL_ADC_Start_IT(ADC_HandleTypeDef
* hadc
)
736 __IO
uint32_t counter
= 0U;
737 ADC_Common_TypeDef
*tmpADC_Common
;
739 /* Check the parameters */
740 assert_param(IS_FUNCTIONAL_STATE(hadc
->Init
.ContinuousConvMode
));
741 assert_param(IS_ADC_EXT_TRIG_EDGE(hadc
->Init
.ExternalTrigConvEdge
));
746 /* Enable the ADC peripheral */
747 /* Check if ADC peripheral is disabled in order to enable it and wait during
748 Tstab time the ADC's stabilization */
749 if((hadc
->Instance
->CR2
& ADC_CR2_ADON
) != ADC_CR2_ADON
)
751 /* Enable the Peripheral */
752 __HAL_ADC_ENABLE(hadc
);
754 /* Delay for ADC stabilization time */
755 /* Compute number of CPU cycles to wait for */
756 counter
= (ADC_STAB_DELAY_US
* (SystemCoreClock
/ 1000000U));
763 /* Start conversion if ADC is effectively enabled */
764 if(HAL_IS_BIT_SET(hadc
->Instance
->CR2
, ADC_CR2_ADON
))
767 /* - Clear state bitfield related to regular group conversion results */
768 /* - Set state bitfield related to regular group operation */
769 ADC_STATE_CLR_SET(hadc
->State
,
770 HAL_ADC_STATE_READY
| HAL_ADC_STATE_REG_EOC
| HAL_ADC_STATE_REG_OVR
,
771 HAL_ADC_STATE_REG_BUSY
);
773 /* If conversions on group regular are also triggering group injected, */
774 /* update ADC state. */
775 if (READ_BIT(hadc
->Instance
->CR1
, ADC_CR1_JAUTO
) != RESET
)
777 ADC_STATE_CLR_SET(hadc
->State
, HAL_ADC_STATE_INJ_EOC
, HAL_ADC_STATE_INJ_BUSY
);
780 /* State machine update: Check if an injected conversion is ongoing */
781 if (HAL_IS_BIT_SET(hadc
->State
, HAL_ADC_STATE_INJ_BUSY
))
783 /* Reset ADC error code fields related to conversions on group regular */
784 CLEAR_BIT(hadc
->ErrorCode
, (HAL_ADC_ERROR_OVR
| HAL_ADC_ERROR_DMA
));
788 /* Reset ADC all error code fields */
789 ADC_CLEAR_ERRORCODE(hadc
);
792 /* Process unlocked */
793 /* Unlock before starting ADC conversions: in case of potential */
794 /* interruption, to let the process to ADC IRQ Handler. */
797 /* Pointer to the common control register to which is belonging hadc */
798 /* (Depending on STM32F4 product, there may be up to 3 ADCs and 1 common */
799 /* control register) */
800 tmpADC_Common
= ADC_COMMON_REGISTER(hadc
);
802 /* Clear regular group conversion flag and overrun flag */
803 /* (To ensure of no unknown state from potential previous ADC operations) */
804 __HAL_ADC_CLEAR_FLAG(hadc
, ADC_FLAG_EOC
| ADC_FLAG_OVR
);
806 /* Enable end of conversion interrupt for regular group */
807 __HAL_ADC_ENABLE_IT(hadc
, (ADC_IT_EOC
| ADC_IT_OVR
));
809 /* Check if Multimode enabled */
810 if(HAL_IS_BIT_CLR(tmpADC_Common
->CCR
, ADC_CCR_MULTI
))
812 /* if no external trigger present enable software conversion of regular channels */
813 if((hadc
->Instance
->CR2
& ADC_CR2_EXTEN
) == RESET
)
815 /* Enable the selected ADC software conversion for regular group */
816 hadc
->Instance
->CR2
|= (uint32_t)ADC_CR2_SWSTART
;
821 /* if instance of handle correspond to ADC1 and no external trigger present enable software conversion of regular channels */
822 if((hadc
->Instance
== ADC1
) && ((hadc
->Instance
->CR2
& ADC_CR2_EXTEN
) == RESET
))
824 /* Enable the selected ADC software conversion for regular group */
825 hadc
->Instance
->CR2
|= (uint32_t)ADC_CR2_SWSTART
;
830 /* Return function status */
835 * @brief Disables the interrupt and stop ADC conversion of regular channels.
837 * @note Caution: This function will stop also injected channels.
839 * @param hadc: pointer to a ADC_HandleTypeDef structure that contains
840 * the configuration information for the specified ADC.
841 * @retval HAL status.
843 HAL_StatusTypeDef
HAL_ADC_Stop_IT(ADC_HandleTypeDef
* hadc
)
845 /* Check the parameters */
846 assert_param(IS_ADC_ALL_INSTANCE(hadc
->Instance
));
851 /* Stop potential conversion on going, on regular and injected groups */
852 /* Disable ADC peripheral */
853 __HAL_ADC_DISABLE(hadc
);
855 /* Check if ADC is effectively disabled */
856 if(HAL_IS_BIT_CLR(hadc
->Instance
->CR2
, ADC_CR2_ADON
))
858 /* Disable ADC end of conversion interrupt for regular group */
859 __HAL_ADC_DISABLE_IT(hadc
, (ADC_IT_EOC
| ADC_IT_OVR
));
862 ADC_STATE_CLR_SET(hadc
->State
,
863 HAL_ADC_STATE_REG_BUSY
| HAL_ADC_STATE_INJ_BUSY
,
864 HAL_ADC_STATE_READY
);
867 /* Process unlocked */
870 /* Return function status */
875 * @brief Handles ADC interrupt request
876 * @param hadc: pointer to a ADC_HandleTypeDef structure that contains
877 * the configuration information for the specified ADC.
880 void HAL_ADC_IRQHandler(ADC_HandleTypeDef
* hadc
)
882 uint32_t tmp1
= 0U, tmp2
= 0U;
884 /* Check the parameters */
885 assert_param(IS_FUNCTIONAL_STATE(hadc
->Init
.ContinuousConvMode
));
886 assert_param(IS_ADC_REGULAR_LENGTH(hadc
->Init
.NbrOfConversion
));
887 assert_param(IS_ADC_EOCSelection(hadc
->Init
.EOCSelection
));
889 tmp1
= __HAL_ADC_GET_FLAG(hadc
, ADC_FLAG_EOC
);
890 tmp2
= __HAL_ADC_GET_IT_SOURCE(hadc
, ADC_IT_EOC
);
891 /* Check End of conversion flag for regular channels */
894 /* Update state machine on conversion status if not in error state */
895 if (HAL_IS_BIT_CLR(hadc
->State
, HAL_ADC_STATE_ERROR_INTERNAL
))
898 SET_BIT(hadc
->State
, HAL_ADC_STATE_REG_EOC
);
901 /* Determine whether any further conversion upcoming on group regular */
902 /* by external trigger, continuous mode or scan sequence on going. */
903 /* Note: On STM32F4, there is no independent flag of end of sequence. */
904 /* The test of scan sequence on going is done either with scan */
905 /* sequence disabled or with end of conversion flag set to */
906 /* of end of sequence. */
907 if(ADC_IS_SOFTWARE_START_REGULAR(hadc
) &&
908 (hadc
->Init
.ContinuousConvMode
== DISABLE
) &&
909 (HAL_IS_BIT_CLR(hadc
->Instance
->SQR1
, ADC_SQR1_L
) ||
910 HAL_IS_BIT_CLR(hadc
->Instance
->CR2
, ADC_CR2_EOCS
) ) )
912 /* Disable ADC end of single conversion interrupt on group regular */
913 /* Note: Overrun interrupt was enabled with EOC interrupt in */
914 /* HAL_ADC_Start_IT(), but is not disabled here because can be used */
915 /* by overrun IRQ process below. */
916 __HAL_ADC_DISABLE_IT(hadc
, ADC_IT_EOC
);
919 CLEAR_BIT(hadc
->State
, HAL_ADC_STATE_REG_BUSY
);
921 if (HAL_IS_BIT_CLR(hadc
->State
, HAL_ADC_STATE_INJ_BUSY
))
923 SET_BIT(hadc
->State
, HAL_ADC_STATE_READY
);
927 /* Conversion complete callback */
928 HAL_ADC_ConvCpltCallback(hadc
);
930 /* Clear regular group conversion flag */
931 __HAL_ADC_CLEAR_FLAG(hadc
, ADC_FLAG_STRT
| ADC_FLAG_EOC
);
934 tmp1
= __HAL_ADC_GET_FLAG(hadc
, ADC_FLAG_JEOC
);
935 tmp2
= __HAL_ADC_GET_IT_SOURCE(hadc
, ADC_IT_JEOC
);
936 /* Check End of conversion flag for injected channels */
939 /* Update state machine on conversion status if not in error state */
940 if (HAL_IS_BIT_CLR(hadc
->State
, HAL_ADC_STATE_ERROR_INTERNAL
))
943 SET_BIT(hadc
->State
, HAL_ADC_STATE_INJ_EOC
);
946 /* Determine whether any further conversion upcoming on group injected */
947 /* by external trigger, scan sequence on going or by automatic injected */
948 /* conversion from group regular (same conditions as group regular */
949 /* interruption disabling above). */
950 if(ADC_IS_SOFTWARE_START_INJECTED(hadc
) &&
951 (HAL_IS_BIT_CLR(hadc
->Instance
->JSQR
, ADC_JSQR_JL
) ||
952 HAL_IS_BIT_CLR(hadc
->Instance
->CR2
, ADC_CR2_EOCS
) ) &&
953 (HAL_IS_BIT_CLR(hadc
->Instance
->CR1
, ADC_CR1_JAUTO
) &&
954 (ADC_IS_SOFTWARE_START_REGULAR(hadc
) &&
955 (hadc
->Init
.ContinuousConvMode
== DISABLE
) ) ) )
957 /* Disable ADC end of single conversion interrupt on group injected */
958 __HAL_ADC_DISABLE_IT(hadc
, ADC_IT_JEOC
);
961 CLEAR_BIT(hadc
->State
, HAL_ADC_STATE_INJ_BUSY
);
963 if (HAL_IS_BIT_CLR(hadc
->State
, HAL_ADC_STATE_REG_BUSY
))
965 SET_BIT(hadc
->State
, HAL_ADC_STATE_READY
);
969 /* Conversion complete callback */
970 HAL_ADCEx_InjectedConvCpltCallback(hadc
);
972 /* Clear injected group conversion flag */
973 __HAL_ADC_CLEAR_FLAG(hadc
, (ADC_FLAG_JSTRT
| ADC_FLAG_JEOC
));
976 tmp1
= __HAL_ADC_GET_FLAG(hadc
, ADC_FLAG_AWD
);
977 tmp2
= __HAL_ADC_GET_IT_SOURCE(hadc
, ADC_IT_AWD
);
978 /* Check Analog watchdog flag */
981 if(__HAL_ADC_GET_FLAG(hadc
, ADC_FLAG_AWD
))
984 SET_BIT(hadc
->State
, HAL_ADC_STATE_AWD1
);
986 /* Level out of window callback */
987 HAL_ADC_LevelOutOfWindowCallback(hadc
);
989 /* Clear the ADC analog watchdog flag */
990 __HAL_ADC_CLEAR_FLAG(hadc
, ADC_FLAG_AWD
);
994 tmp1
= __HAL_ADC_GET_FLAG(hadc
, ADC_FLAG_OVR
);
995 tmp2
= __HAL_ADC_GET_IT_SOURCE(hadc
, ADC_IT_OVR
);
996 /* Check Overrun flag */
999 /* Note: On STM32F4, ADC overrun can be set through other parameters */
1000 /* refer to description of parameter "EOCSelection" for more */
1003 /* Set ADC error code to overrun */
1004 SET_BIT(hadc
->ErrorCode
, HAL_ADC_ERROR_OVR
);
1006 /* Clear ADC overrun flag */
1007 __HAL_ADC_CLEAR_FLAG(hadc
, ADC_FLAG_OVR
);
1009 /* Error callback */
1010 HAL_ADC_ErrorCallback(hadc
);
1012 /* Clear the Overrun flag */
1013 __HAL_ADC_CLEAR_FLAG(hadc
, ADC_FLAG_OVR
);
1018 * @brief Enables ADC DMA request after last transfer (Single-ADC mode) and enables ADC peripheral
1019 * @param hadc: pointer to a ADC_HandleTypeDef structure that contains
1020 * the configuration information for the specified ADC.
1021 * @param pData: The destination Buffer address.
1022 * @param Length: The length of data to be transferred from ADC peripheral to memory.
1023 * @retval HAL status
1025 HAL_StatusTypeDef
HAL_ADC_Start_DMA(ADC_HandleTypeDef
* hadc
, uint32_t* pData
, uint32_t Length
)
1027 __IO
uint32_t counter
= 0U;
1028 ADC_Common_TypeDef
*tmpADC_Common
;
1030 /* Check the parameters */
1031 assert_param(IS_FUNCTIONAL_STATE(hadc
->Init
.ContinuousConvMode
));
1032 assert_param(IS_ADC_EXT_TRIG_EDGE(hadc
->Init
.ExternalTrigConvEdge
));
1034 /* Process locked */
1037 /* Enable the ADC peripheral */
1038 /* Check if ADC peripheral is disabled in order to enable it and wait during
1039 Tstab time the ADC's stabilization */
1040 if((hadc
->Instance
->CR2
& ADC_CR2_ADON
) != ADC_CR2_ADON
)
1042 /* Enable the Peripheral */
1043 __HAL_ADC_ENABLE(hadc
);
1045 /* Delay for ADC stabilization time */
1046 /* Compute number of CPU cycles to wait for */
1047 counter
= (ADC_STAB_DELAY_US
* (SystemCoreClock
/ 1000000U));
1048 while(counter
!= 0U)
1054 /* Start conversion if ADC is effectively enabled */
1055 if(HAL_IS_BIT_SET(hadc
->Instance
->CR2
, ADC_CR2_ADON
))
1058 /* - Clear state bitfield related to regular group conversion results */
1059 /* - Set state bitfield related to regular group operation */
1060 ADC_STATE_CLR_SET(hadc
->State
,
1061 HAL_ADC_STATE_READY
| HAL_ADC_STATE_REG_EOC
| HAL_ADC_STATE_REG_OVR
,
1062 HAL_ADC_STATE_REG_BUSY
);
1064 /* If conversions on group regular are also triggering group injected, */
1065 /* update ADC state. */
1066 if (READ_BIT(hadc
->Instance
->CR1
, ADC_CR1_JAUTO
) != RESET
)
1068 ADC_STATE_CLR_SET(hadc
->State
, HAL_ADC_STATE_INJ_EOC
, HAL_ADC_STATE_INJ_BUSY
);
1071 /* State machine update: Check if an injected conversion is ongoing */
1072 if (HAL_IS_BIT_SET(hadc
->State
, HAL_ADC_STATE_INJ_BUSY
))
1074 /* Reset ADC error code fields related to conversions on group regular */
1075 CLEAR_BIT(hadc
->ErrorCode
, (HAL_ADC_ERROR_OVR
| HAL_ADC_ERROR_DMA
));
1079 /* Reset ADC all error code fields */
1080 ADC_CLEAR_ERRORCODE(hadc
);
1083 /* Process unlocked */
1084 /* Unlock before starting ADC conversions: in case of potential */
1085 /* interruption, to let the process to ADC IRQ Handler. */
1088 /* Pointer to the common control register to which is belonging hadc */
1089 /* (Depending on STM32F4 product, there may be up to 3 ADCs and 1 common */
1090 /* control register) */
1091 tmpADC_Common
= ADC_COMMON_REGISTER(hadc
);
1093 /* Set the DMA transfer complete callback */
1094 hadc
->DMA_Handle
->XferCpltCallback
= ADC_DMAConvCplt
;
1096 /* Set the DMA half transfer complete callback */
1097 hadc
->DMA_Handle
->XferHalfCpltCallback
= ADC_DMAHalfConvCplt
;
1099 /* Set the DMA error callback */
1100 hadc
->DMA_Handle
->XferErrorCallback
= ADC_DMAError
;
1103 /* Manage ADC and DMA start: ADC overrun interruption, DMA start, ADC */
1104 /* start (in case of SW start): */
1106 /* Clear regular group conversion flag and overrun flag */
1107 /* (To ensure of no unknown state from potential previous ADC operations) */
1108 __HAL_ADC_CLEAR_FLAG(hadc
, ADC_FLAG_EOC
| ADC_FLAG_OVR
);
1110 /* Enable ADC overrun interrupt */
1111 __HAL_ADC_ENABLE_IT(hadc
, ADC_IT_OVR
);
1113 /* Enable ADC DMA mode */
1114 hadc
->Instance
->CR2
|= ADC_CR2_DMA
;
1116 /* Start the DMA channel */
1117 HAL_DMA_Start_IT(hadc
->DMA_Handle
, (uint32_t)&hadc
->Instance
->DR
, (uint32_t)pData
, Length
);
1119 /* Check if Multimode enabled */
1120 if(HAL_IS_BIT_CLR(tmpADC_Common
->CCR
, ADC_CCR_MULTI
))
1122 /* if no external trigger present enable software conversion of regular channels */
1123 if((hadc
->Instance
->CR2
& ADC_CR2_EXTEN
) == RESET
)
1125 /* Enable the selected ADC software conversion for regular group */
1126 hadc
->Instance
->CR2
|= (uint32_t)ADC_CR2_SWSTART
;
1131 /* if instance of handle correspond to ADC1 and no external trigger present enable software conversion of regular channels */
1132 if((hadc
->Instance
== ADC1
) && ((hadc
->Instance
->CR2
& ADC_CR2_EXTEN
) == RESET
))
1134 /* Enable the selected ADC software conversion for regular group */
1135 hadc
->Instance
->CR2
|= (uint32_t)ADC_CR2_SWSTART
;
1140 /* Return function status */
1145 * @brief Disables ADC DMA (Single-ADC mode) and disables ADC peripheral
1146 * @param hadc: pointer to a ADC_HandleTypeDef structure that contains
1147 * the configuration information for the specified ADC.
1148 * @retval HAL status
1150 HAL_StatusTypeDef
HAL_ADC_Stop_DMA(ADC_HandleTypeDef
* hadc
)
1152 HAL_StatusTypeDef tmp_hal_status
= HAL_OK
;
1154 /* Check the parameters */
1155 assert_param(IS_ADC_ALL_INSTANCE(hadc
->Instance
));
1157 /* Process locked */
1160 /* Stop potential conversion on going, on regular and injected groups */
1161 /* Disable ADC peripheral */
1162 __HAL_ADC_DISABLE(hadc
);
1164 /* Check if ADC is effectively disabled */
1165 if(HAL_IS_BIT_CLR(hadc
->Instance
->CR2
, ADC_CR2_ADON
))
1167 /* Disable the selected ADC DMA mode */
1168 hadc
->Instance
->CR2
&= ~ADC_CR2_DMA
;
1170 /* Disable the DMA channel (in case of DMA in circular mode or stop while */
1171 /* DMA transfer is on going) */
1172 tmp_hal_status
= HAL_DMA_Abort(hadc
->DMA_Handle
);
1174 /* Disable ADC overrun interrupt */
1175 __HAL_ADC_DISABLE_IT(hadc
, ADC_IT_OVR
);
1178 ADC_STATE_CLR_SET(hadc
->State
,
1179 HAL_ADC_STATE_REG_BUSY
| HAL_ADC_STATE_INJ_BUSY
,
1180 HAL_ADC_STATE_READY
);
1183 /* Process unlocked */
1186 /* Return function status */
1187 return tmp_hal_status
;
1191 * @brief Gets the converted value from data register of regular channel.
1192 * @param hadc: pointer to a ADC_HandleTypeDef structure that contains
1193 * the configuration information for the specified ADC.
1194 * @retval Converted value
1196 uint32_t HAL_ADC_GetValue(ADC_HandleTypeDef
* hadc
)
1198 /* Return the selected ADC converted value */
1199 return hadc
->Instance
->DR
;
1203 * @brief Regular conversion complete callback in non blocking mode
1204 * @param hadc: pointer to a ADC_HandleTypeDef structure that contains
1205 * the configuration information for the specified ADC.
1208 __weak
void HAL_ADC_ConvCpltCallback(ADC_HandleTypeDef
* hadc
)
1210 /* Prevent unused argument(s) compilation warning */
1212 /* NOTE : This function Should not be modified, when the callback is needed,
1213 the HAL_ADC_ConvCpltCallback could be implemented in the user file
1218 * @brief Regular conversion half DMA transfer callback in non blocking mode
1219 * @param hadc: pointer to a ADC_HandleTypeDef structure that contains
1220 * the configuration information for the specified ADC.
1223 __weak
void HAL_ADC_ConvHalfCpltCallback(ADC_HandleTypeDef
* hadc
)
1225 /* Prevent unused argument(s) compilation warning */
1227 /* NOTE : This function Should not be modified, when the callback is needed,
1228 the HAL_ADC_ConvHalfCpltCallback could be implemented in the user file
1233 * @brief Analog watchdog callback in non blocking mode
1234 * @param hadc: pointer to a ADC_HandleTypeDef structure that contains
1235 * the configuration information for the specified ADC.
1238 __weak
void HAL_ADC_LevelOutOfWindowCallback(ADC_HandleTypeDef
* hadc
)
1240 /* Prevent unused argument(s) compilation warning */
1242 /* NOTE : This function Should not be modified, when the callback is needed,
1243 the HAL_ADC_LevelOoutOfWindowCallback could be implemented in the user file
1248 * @brief Error ADC callback.
1249 * @note In case of error due to overrun when using ADC with DMA transfer
1250 * (HAL ADC handle paramater "ErrorCode" to state "HAL_ADC_ERROR_OVR"):
1251 * - Reinitialize the DMA using function "HAL_ADC_Stop_DMA()".
1252 * - If needed, restart a new ADC conversion using function
1253 * "HAL_ADC_Start_DMA()"
1254 * (this function is also clearing overrun flag)
1255 * @param hadc: pointer to a ADC_HandleTypeDef structure that contains
1256 * the configuration information for the specified ADC.
1259 __weak
void HAL_ADC_ErrorCallback(ADC_HandleTypeDef
*hadc
)
1261 /* Prevent unused argument(s) compilation warning */
1263 /* NOTE : This function Should not be modified, when the callback is needed,
1264 the HAL_ADC_ErrorCallback could be implemented in the user file
1272 /** @defgroup ADC_Exported_Functions_Group3 Peripheral Control functions
1273 * @brief Peripheral Control functions
1276 ===============================================================================
1277 ##### Peripheral Control functions #####
1278 ===============================================================================
1279 [..] This section provides functions allowing to:
1280 (+) Configure regular channels.
1281 (+) Configure injected channels.
1282 (+) Configure multimode.
1283 (+) Configure the analog watch dog.
1290 * @brief Configures for the selected ADC regular channel its corresponding
1291 * rank in the sequencer and its sample time.
1292 * @param hadc: pointer to a ADC_HandleTypeDef structure that contains
1293 * the configuration information for the specified ADC.
1294 * @param sConfig: ADC configuration structure.
1295 * @retval HAL status
1297 HAL_StatusTypeDef
HAL_ADC_ConfigChannel(ADC_HandleTypeDef
* hadc
, ADC_ChannelConfTypeDef
* sConfig
)
1299 __IO
uint32_t counter
= 0U;
1300 ADC_Common_TypeDef
*tmpADC_Common
;
1302 /* Check the parameters */
1303 assert_param(IS_ADC_CHANNEL(sConfig
->Channel
));
1304 assert_param(IS_ADC_REGULAR_RANK(sConfig
->Rank
));
1305 assert_param(IS_ADC_SAMPLE_TIME(sConfig
->SamplingTime
));
1307 /* Process locked */
1310 /* if ADC_Channel_10 ... ADC_Channel_18 is selected */
1311 if (sConfig
->Channel
> ADC_CHANNEL_9
)
1313 /* Clear the old sample time */
1314 hadc
->Instance
->SMPR1
&= ~ADC_SMPR1(ADC_SMPR1_SMP10
, sConfig
->Channel
);
1316 /* Set the new sample time */
1317 hadc
->Instance
->SMPR1
|= ADC_SMPR1(sConfig
->SamplingTime
, sConfig
->Channel
);
1319 else /* ADC_Channel include in ADC_Channel_[0..9] */
1321 /* Clear the old sample time */
1322 hadc
->Instance
->SMPR2
&= ~ADC_SMPR2(ADC_SMPR2_SMP0
, sConfig
->Channel
);
1324 /* Set the new sample time */
1325 hadc
->Instance
->SMPR2
|= ADC_SMPR2(sConfig
->SamplingTime
, sConfig
->Channel
);
1328 /* For Rank 1 to 6 */
1329 if (sConfig
->Rank
< 7U)
1331 /* Clear the old SQx bits for the selected rank */
1332 hadc
->Instance
->SQR3
&= ~ADC_SQR3_RK(ADC_SQR3_SQ1
, sConfig
->Rank
);
1334 /* Set the SQx bits for the selected rank */
1335 hadc
->Instance
->SQR3
|= ADC_SQR3_RK(sConfig
->Channel
, sConfig
->Rank
);
1337 /* For Rank 7 to 12 */
1338 else if (sConfig
->Rank
< 13U)
1340 /* Clear the old SQx bits for the selected rank */
1341 hadc
->Instance
->SQR2
&= ~ADC_SQR2_RK(ADC_SQR2_SQ7
, sConfig
->Rank
);
1343 /* Set the SQx bits for the selected rank */
1344 hadc
->Instance
->SQR2
|= ADC_SQR2_RK(sConfig
->Channel
, sConfig
->Rank
);
1346 /* For Rank 13 to 16 */
1349 /* Clear the old SQx bits for the selected rank */
1350 hadc
->Instance
->SQR1
&= ~ADC_SQR1_RK(ADC_SQR1_SQ13
, sConfig
->Rank
);
1352 /* Set the SQx bits for the selected rank */
1353 hadc
->Instance
->SQR1
|= ADC_SQR1_RK(sConfig
->Channel
, sConfig
->Rank
);
1356 /* Pointer to the common control register to which is belonging hadc */
1357 /* (Depending on STM32F4 product, there may be up to 3 ADCs and 1 common */
1358 /* control register) */
1359 tmpADC_Common
= ADC_COMMON_REGISTER(hadc
);
1361 /* if ADC1 Channel_18 is selected enable VBAT Channel */
1362 if ((hadc
->Instance
== ADC1
) && (sConfig
->Channel
== ADC_CHANNEL_VBAT
))
1364 /* Enable the VBAT channel*/
1365 tmpADC_Common
->CCR
|= ADC_CCR_VBATE
;
1368 /* if ADC1 Channel_16 or Channel_17 is selected enable TSVREFE Channel(Temperature sensor and VREFINT) */
1369 if ((hadc
->Instance
== ADC1
) && ((sConfig
->Channel
== ADC_CHANNEL_TEMPSENSOR
) || (sConfig
->Channel
== ADC_CHANNEL_VREFINT
)))
1371 /* Enable the TSVREFE channel*/
1372 tmpADC_Common
->CCR
|= ADC_CCR_TSVREFE
;
1374 if((sConfig
->Channel
== ADC_CHANNEL_TEMPSENSOR
))
1376 /* Delay for temperature sensor stabilization time */
1377 /* Compute number of CPU cycles to wait for */
1378 counter
= (ADC_TEMPSENSOR_DELAY_US
* (SystemCoreClock
/ 1000000U));
1379 while(counter
!= 0U)
1386 /* Process unlocked */
1389 /* Return function status */
1394 * @brief Configures the analog watchdog.
1395 * @note Analog watchdog thresholds can be modified while ADC conversion
1397 * In this case, some constraints must be taken into account:
1398 * The programmed threshold values are effective from the next
1399 * ADC EOC (end of unitary conversion).
1400 * Considering that registers write delay may happen due to
1401 * bus activity, this might cause an uncertainty on the
1402 * effective timing of the new programmed threshold values.
1403 * @param hadc: pointer to a ADC_HandleTypeDef structure that contains
1404 * the configuration information for the specified ADC.
1405 * @param AnalogWDGConfig : pointer to an ADC_AnalogWDGConfTypeDef structure
1406 * that contains the configuration information of ADC analog watchdog.
1407 * @retval HAL status
1409 HAL_StatusTypeDef
HAL_ADC_AnalogWDGConfig(ADC_HandleTypeDef
* hadc
, ADC_AnalogWDGConfTypeDef
* AnalogWDGConfig
)
1411 #ifdef USE_FULL_ASSERT
1413 #endif /* USE_FULL_ASSERT */
1415 /* Check the parameters */
1416 assert_param(IS_ADC_ANALOG_WATCHDOG(AnalogWDGConfig
->WatchdogMode
));
1417 assert_param(IS_ADC_CHANNEL(AnalogWDGConfig
->Channel
));
1418 assert_param(IS_FUNCTIONAL_STATE(AnalogWDGConfig
->ITMode
));
1420 #ifdef USE_FULL_ASSERT
1421 tmp
= ADC_GET_RESOLUTION(hadc
);
1422 assert_param(IS_ADC_RANGE(tmp
, AnalogWDGConfig
->HighThreshold
));
1423 assert_param(IS_ADC_RANGE(tmp
, AnalogWDGConfig
->LowThreshold
));
1424 #endif /* USE_FULL_ASSERT */
1426 /* Process locked */
1429 if(AnalogWDGConfig
->ITMode
== ENABLE
)
1431 /* Enable the ADC Analog watchdog interrupt */
1432 __HAL_ADC_ENABLE_IT(hadc
, ADC_IT_AWD
);
1436 /* Disable the ADC Analog watchdog interrupt */
1437 __HAL_ADC_DISABLE_IT(hadc
, ADC_IT_AWD
);
1440 /* Clear AWDEN, JAWDEN and AWDSGL bits */
1441 hadc
->Instance
->CR1
&= ~(ADC_CR1_AWDSGL
| ADC_CR1_JAWDEN
| ADC_CR1_AWDEN
);
1443 /* Set the analog watchdog enable mode */
1444 hadc
->Instance
->CR1
|= AnalogWDGConfig
->WatchdogMode
;
1446 /* Set the high threshold */
1447 hadc
->Instance
->HTR
= AnalogWDGConfig
->HighThreshold
;
1449 /* Set the low threshold */
1450 hadc
->Instance
->LTR
= AnalogWDGConfig
->LowThreshold
;
1452 /* Clear the Analog watchdog channel select bits */
1453 hadc
->Instance
->CR1
&= ~ADC_CR1_AWDCH
;
1455 /* Set the Analog watchdog channel */
1456 hadc
->Instance
->CR1
|= (uint32_t)((uint16_t)(AnalogWDGConfig
->Channel
));
1458 /* Process unlocked */
1461 /* Return function status */
1469 /** @defgroup ADC_Exported_Functions_Group4 ADC Peripheral State functions
1470 * @brief ADC Peripheral State functions
1473 ===============================================================================
1474 ##### Peripheral State and errors functions #####
1475 ===============================================================================
1477 This subsection provides functions allowing to
1478 (+) Check the ADC state
1479 (+) Check the ADC Error
1486 * @brief return the ADC state
1487 * @param hadc: pointer to a ADC_HandleTypeDef structure that contains
1488 * the configuration information for the specified ADC.
1491 uint32_t HAL_ADC_GetState(ADC_HandleTypeDef
* hadc
)
1493 /* Return ADC state */
1498 * @brief Return the ADC error code
1499 * @param hadc: pointer to a ADC_HandleTypeDef structure that contains
1500 * the configuration information for the specified ADC.
1501 * @retval ADC Error Code
1503 uint32_t HAL_ADC_GetError(ADC_HandleTypeDef
*hadc
)
1505 return hadc
->ErrorCode
;
1512 /** @addtogroup ADC_Private_Functions
1517 * @brief Initializes the ADCx peripheral according to the specified parameters
1518 * in the ADC_InitStruct without initializing the ADC MSP.
1519 * @param hadc: pointer to a ADC_HandleTypeDef structure that contains
1520 * the configuration information for the specified ADC.
1523 static void ADC_Init(ADC_HandleTypeDef
* hadc
)
1525 ADC_Common_TypeDef
*tmpADC_Common
;
1527 /* Set ADC parameters */
1528 /* Pointer to the common control register to which is belonging hadc */
1529 /* (Depending on STM32F4 product, there may be up to 3 ADCs and 1 common */
1530 /* control register) */
1531 tmpADC_Common
= ADC_COMMON_REGISTER(hadc
);
1533 /* Set the ADC clock prescaler */
1534 tmpADC_Common
->CCR
&= ~(ADC_CCR_ADCPRE
);
1535 tmpADC_Common
->CCR
|= hadc
->Init
.ClockPrescaler
;
1537 /* Set ADC scan mode */
1538 hadc
->Instance
->CR1
&= ~(ADC_CR1_SCAN
);
1539 hadc
->Instance
->CR1
|= ADC_CR1_SCANCONV(hadc
->Init
.ScanConvMode
);
1541 /* Set ADC resolution */
1542 hadc
->Instance
->CR1
&= ~(ADC_CR1_RES
);
1543 hadc
->Instance
->CR1
|= hadc
->Init
.Resolution
;
1545 /* Set ADC data alignment */
1546 hadc
->Instance
->CR2
&= ~(ADC_CR2_ALIGN
);
1547 hadc
->Instance
->CR2
|= hadc
->Init
.DataAlign
;
1549 /* Enable external trigger if trigger selection is different of software */
1551 /* Note: This configuration keeps the hardware feature of parameter */
1552 /* ExternalTrigConvEdge "trigger edge none" equivalent to */
1553 /* software start. */
1554 if(hadc
->Init
.ExternalTrigConv
!= ADC_SOFTWARE_START
)
1556 /* Select external trigger to start conversion */
1557 hadc
->Instance
->CR2
&= ~(ADC_CR2_EXTSEL
);
1558 hadc
->Instance
->CR2
|= hadc
->Init
.ExternalTrigConv
;
1560 /* Select external trigger polarity */
1561 hadc
->Instance
->CR2
&= ~(ADC_CR2_EXTEN
);
1562 hadc
->Instance
->CR2
|= hadc
->Init
.ExternalTrigConvEdge
;
1566 /* Reset the external trigger */
1567 hadc
->Instance
->CR2
&= ~(ADC_CR2_EXTSEL
);
1568 hadc
->Instance
->CR2
&= ~(ADC_CR2_EXTEN
);
1571 /* Enable or disable ADC continuous conversion mode */
1572 hadc
->Instance
->CR2
&= ~(ADC_CR2_CONT
);
1573 hadc
->Instance
->CR2
|= ADC_CR2_CONTINUOUS(hadc
->Init
.ContinuousConvMode
);
1575 if(hadc
->Init
.DiscontinuousConvMode
!= DISABLE
)
1577 assert_param(IS_ADC_REGULAR_DISC_NUMBER(hadc
->Init
.NbrOfDiscConversion
));
1579 /* Enable the selected ADC regular discontinuous mode */
1580 hadc
->Instance
->CR1
|= (uint32_t)ADC_CR1_DISCEN
;
1582 /* Set the number of channels to be converted in discontinuous mode */
1583 hadc
->Instance
->CR1
&= ~(ADC_CR1_DISCNUM
);
1584 hadc
->Instance
->CR1
|= ADC_CR1_DISCONTINUOUS(hadc
->Init
.NbrOfDiscConversion
);
1588 /* Disable the selected ADC regular discontinuous mode */
1589 hadc
->Instance
->CR1
&= ~(ADC_CR1_DISCEN
);
1592 /* Set ADC number of conversion */
1593 hadc
->Instance
->SQR1
&= ~(ADC_SQR1_L
);
1594 hadc
->Instance
->SQR1
|= ADC_SQR1(hadc
->Init
.NbrOfConversion
);
1596 /* Enable or disable ADC DMA continuous request */
1597 hadc
->Instance
->CR2
&= ~(ADC_CR2_DDS
);
1598 hadc
->Instance
->CR2
|= ADC_CR2_DMAContReq(hadc
->Init
.DMAContinuousRequests
);
1600 /* Enable or disable ADC end of conversion selection */
1601 hadc
->Instance
->CR2
&= ~(ADC_CR2_EOCS
);
1602 hadc
->Instance
->CR2
|= ADC_CR2_EOCSelection(hadc
->Init
.EOCSelection
);
1606 * @brief DMA transfer complete callback.
1607 * @param hdma: pointer to a DMA_HandleTypeDef structure that contains
1608 * the configuration information for the specified DMA module.
1611 static void ADC_DMAConvCplt(DMA_HandleTypeDef
*hdma
)
1613 /* Retrieve ADC handle corresponding to current DMA handle */
1614 ADC_HandleTypeDef
* hadc
= ( ADC_HandleTypeDef
* )((DMA_HandleTypeDef
* )hdma
)->Parent
;
1616 /* Update state machine on conversion status if not in error state */
1617 if (HAL_IS_BIT_CLR(hadc
->State
, HAL_ADC_STATE_ERROR_INTERNAL
| HAL_ADC_STATE_ERROR_DMA
))
1619 /* Update ADC state machine */
1620 SET_BIT(hadc
->State
, HAL_ADC_STATE_REG_EOC
);
1622 /* Determine whether any further conversion upcoming on group regular */
1623 /* by external trigger, continuous mode or scan sequence on going. */
1624 /* Note: On STM32F4, there is no independent flag of end of sequence. */
1625 /* The test of scan sequence on going is done either with scan */
1626 /* sequence disabled or with end of conversion flag set to */
1627 /* of end of sequence. */
1628 if(ADC_IS_SOFTWARE_START_REGULAR(hadc
) &&
1629 (hadc
->Init
.ContinuousConvMode
== DISABLE
) &&
1630 (HAL_IS_BIT_CLR(hadc
->Instance
->SQR1
, ADC_SQR1_L
) ||
1631 HAL_IS_BIT_CLR(hadc
->Instance
->CR2
, ADC_CR2_EOCS
) ) )
1633 /* Disable ADC end of single conversion interrupt on group regular */
1634 /* Note: Overrun interrupt was enabled with EOC interrupt in */
1635 /* HAL_ADC_Start_IT(), but is not disabled here because can be used */
1636 /* by overrun IRQ process below. */
1637 __HAL_ADC_DISABLE_IT(hadc
, ADC_IT_EOC
);
1640 CLEAR_BIT(hadc
->State
, HAL_ADC_STATE_REG_BUSY
);
1642 if (HAL_IS_BIT_CLR(hadc
->State
, HAL_ADC_STATE_INJ_BUSY
))
1644 SET_BIT(hadc
->State
, HAL_ADC_STATE_READY
);
1648 /* Conversion complete callback */
1649 HAL_ADC_ConvCpltCallback(hadc
);
1653 /* Call DMA error callback */
1654 hadc
->DMA_Handle
->XferErrorCallback(hdma
);
1659 * @brief DMA half transfer complete callback.
1660 * @param hdma: pointer to a DMA_HandleTypeDef structure that contains
1661 * the configuration information for the specified DMA module.
1664 static void ADC_DMAHalfConvCplt(DMA_HandleTypeDef
*hdma
)
1666 ADC_HandleTypeDef
* hadc
= ( ADC_HandleTypeDef
* )((DMA_HandleTypeDef
* )hdma
)->Parent
;
1667 /* Conversion complete callback */
1668 HAL_ADC_ConvHalfCpltCallback(hadc
);
1672 * @brief DMA error callback
1673 * @param hdma: pointer to a DMA_HandleTypeDef structure that contains
1674 * the configuration information for the specified DMA module.
1677 static void ADC_DMAError(DMA_HandleTypeDef
*hdma
)
1679 ADC_HandleTypeDef
* hadc
= ( ADC_HandleTypeDef
* )((DMA_HandleTypeDef
* )hdma
)->Parent
;
1680 hadc
->State
= HAL_ADC_STATE_ERROR_DMA
;
1681 /* Set ADC error code to DMA error */
1682 hadc
->ErrorCode
|= HAL_ADC_ERROR_DMA
;
1683 HAL_ADC_ErrorCallback(hadc
);
1694 #endif /* HAL_ADC_MODULE_ENABLED */
1703 /************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/