2 ******************************************************************************
3 * @file stm32f7xx_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 "stm32f7xx_hal.h"
197 /** @addtogroup STM32F7xx_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
);
224 /* Exported functions --------------------------------------------------------*/
225 /** @defgroup ADC_Exported_Functions ADC Exported Functions
229 /** @defgroup ADC_Exported_Functions_Group1 Initialization and de-initialization functions
230 * @brief Initialization and Configuration functions
233 ===============================================================================
234 ##### Initialization and de-initialization functions #####
235 ===============================================================================
236 [..] This section provides functions allowing to:
237 (+) Initialize and configure the ADC.
238 (+) De-initialize the ADC.
245 * @brief Initializes the ADCx peripheral according to the specified parameters
246 * in the ADC_InitStruct and initializes the ADC MSP.
248 * @note This function is used to configure the global features of the ADC (
249 * ClockPrescaler, Resolution, Data Alignment and number of conversion), however,
250 * the rest of the configuration parameters are specific to the regular
251 * channels group (scan mode activation, continuous mode activation,
252 * External trigger source and edge, DMA continuous request after the
253 * last transfer and End of conversion selection).
255 * @param hadc: pointer to a ADC_HandleTypeDef structure that contains
256 * the configuration information for the specified ADC.
259 HAL_StatusTypeDef
HAL_ADC_Init(ADC_HandleTypeDef
* hadc
)
261 HAL_StatusTypeDef tmp_hal_status
= HAL_OK
;
263 /* Check ADC handle */
269 /* Check the parameters */
270 assert_param(IS_ADC_ALL_INSTANCE(hadc
->Instance
));
271 assert_param(IS_ADC_CLOCKPRESCALER(hadc
->Init
.ClockPrescaler
));
272 assert_param(IS_ADC_RESOLUTION(hadc
->Init
.Resolution
));
273 assert_param(IS_ADC_SCAN_MODE(hadc
->Init
.ScanConvMode
));
274 assert_param(IS_FUNCTIONAL_STATE(hadc
->Init
.ContinuousConvMode
));
275 assert_param(IS_ADC_EXT_TRIG(hadc
->Init
.ExternalTrigConv
));
276 assert_param(IS_ADC_DATA_ALIGN(hadc
->Init
.DataAlign
));
277 assert_param(IS_ADC_REGULAR_LENGTH(hadc
->Init
.NbrOfConversion
));
278 assert_param(IS_FUNCTIONAL_STATE(hadc
->Init
.DMAContinuousRequests
));
279 assert_param(IS_ADC_EOCSelection(hadc
->Init
.EOCSelection
));
280 assert_param(IS_FUNCTIONAL_STATE(hadc
->Init
.DiscontinuousConvMode
));
282 if(hadc
->Init
.ExternalTrigConv
!= ADC_SOFTWARE_START
)
284 assert_param(IS_ADC_EXT_TRIG_EDGE(hadc
->Init
.ExternalTrigConvEdge
));
287 if(hadc
->State
== HAL_ADC_STATE_RESET
)
289 /* Initialize ADC error code */
290 ADC_CLEAR_ERRORCODE(hadc
);
292 /* Allocate lock resource and initialize it */
293 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
= 0;
441 /* Check the parameters */
442 assert_param(IS_FUNCTIONAL_STATE(hadc
->Init
.ContinuousConvMode
));
443 assert_param(IS_ADC_EXT_TRIG_EDGE(hadc
->Init
.ExternalTrigConvEdge
));
448 /* Enable the ADC peripheral */
449 /* Check if ADC peripheral is disabled in order to enable it and wait during
450 Tstab time the ADC's stabilization */
451 if((hadc
->Instance
->CR2
& ADC_CR2_ADON
) != ADC_CR2_ADON
)
453 /* Enable the Peripheral */
454 __HAL_ADC_ENABLE(hadc
);
456 /* Delay for ADC stabilization time */
457 /* Compute number of CPU cycles to wait for */
458 counter
= (ADC_STAB_DELAY_US
* (SystemCoreClock
/ 1000000));
465 /* Start conversion if ADC is effectively enabled */
466 if(HAL_IS_BIT_SET(hadc
->Instance
->CR2
, ADC_CR2_ADON
))
469 /* - Clear state bitfield related to regular group conversion results */
470 /* - Set state bitfield related to regular group operation */
471 ADC_STATE_CLR_SET(hadc
->State
,
472 HAL_ADC_STATE_READY
| HAL_ADC_STATE_REG_EOC
| HAL_ADC_STATE_REG_OVR
,
473 HAL_ADC_STATE_REG_BUSY
);
475 /* If conversions on group regular are also triggering group injected, */
476 /* update ADC state. */
477 if (READ_BIT(hadc
->Instance
->CR1
, ADC_CR1_JAUTO
) != RESET
)
479 ADC_STATE_CLR_SET(hadc
->State
, HAL_ADC_STATE_INJ_EOC
, HAL_ADC_STATE_INJ_BUSY
);
482 /* State machine update: Check if an injected conversion is ongoing */
483 if (HAL_IS_BIT_SET(hadc
->State
, HAL_ADC_STATE_INJ_BUSY
))
485 /* Reset ADC error code fields related to conversions on group regular */
486 CLEAR_BIT(hadc
->ErrorCode
, (HAL_ADC_ERROR_OVR
| HAL_ADC_ERROR_DMA
));
490 /* Reset ADC all error code fields */
491 ADC_CLEAR_ERRORCODE(hadc
);
494 /* Process unlocked */
495 /* Unlock before starting ADC conversions: in case of potential */
496 /* interruption, to let the process to ADC IRQ Handler. */
499 /* Clear regular group conversion flag and overrun flag */
500 /* (To ensure of no unknown state from potential previous ADC operations) */
501 __HAL_ADC_CLEAR_FLAG(hadc
, ADC_FLAG_EOC
| ADC_FLAG_OVR
);
503 /* Check if Multimode enabled */
504 if(HAL_IS_BIT_CLR(ADC
->CCR
, ADC_CCR_MULTI
))
506 /* if no external trigger present enable software conversion of regular channels */
507 if((hadc
->Instance
->CR2
& ADC_CR2_EXTEN
) == RESET
)
509 /* Enable the selected ADC software conversion for regular group */
510 hadc
->Instance
->CR2
|= (uint32_t)ADC_CR2_SWSTART
;
515 /* if instance of handle correspond to ADC1 and no external trigger present enable software conversion of regular channels */
516 if((hadc
->Instance
== ADC1
) && ((hadc
->Instance
->CR2
& ADC_CR2_EXTEN
) == RESET
))
518 /* Enable the selected ADC software conversion for regular group */
519 hadc
->Instance
->CR2
|= (uint32_t)ADC_CR2_SWSTART
;
524 /* Return function status */
529 * @brief Disables ADC and stop conversion of regular channels.
531 * @note Caution: This function will stop also injected channels.
533 * @param hadc: pointer to a ADC_HandleTypeDef structure that contains
534 * the configuration information for the specified ADC.
536 * @retval HAL status.
538 HAL_StatusTypeDef
HAL_ADC_Stop(ADC_HandleTypeDef
* hadc
)
540 /* Check the parameters */
541 assert_param(IS_ADC_ALL_INSTANCE(hadc
->Instance
));
546 /* Stop potential conversion on going, on regular and injected groups */
547 /* Disable ADC peripheral */
548 __HAL_ADC_DISABLE(hadc
);
550 /* Check if ADC is effectively disabled */
551 if(HAL_IS_BIT_CLR(hadc
->Instance
->CR2
, ADC_CR2_ADON
))
554 ADC_STATE_CLR_SET(hadc
->State
,
555 HAL_ADC_STATE_REG_BUSY
| HAL_ADC_STATE_INJ_BUSY
,
556 HAL_ADC_STATE_READY
);
559 /* Process unlocked */
562 /* Return function status */
567 * @brief Poll for regular conversion complete
568 * @note ADC conversion flags EOS (end of sequence) and EOC (end of
569 * conversion) are cleared by this function.
570 * @note This function cannot be used in a particular setup: ADC configured
571 * in DMA mode and polling for end of each conversion (ADC init
572 * parameter "EOCSelection" set to ADC_EOC_SINGLE_CONV).
573 * In this case, DMA resets the flag EOC and polling cannot be
574 * performed on each conversion. Nevertheless, polling can still
575 * be performed on the complete sequence.
576 * @param hadc: pointer to a ADC_HandleTypeDef structure that contains
577 * the configuration information for the specified ADC.
578 * @param Timeout: Timeout value in millisecond.
581 HAL_StatusTypeDef
HAL_ADC_PollForConversion(ADC_HandleTypeDef
* hadc
, uint32_t Timeout
)
583 uint32_t tickstart
= 0;
585 /* Verification that ADC configuration is compliant with polling for */
586 /* each conversion: */
587 /* Particular case is ADC configured in DMA mode and ADC sequencer with */
588 /* several ranks and polling for end of each conversion. */
589 /* For code simplicity sake, this particular case is generalized to */
590 /* ADC configured in DMA mode and polling for end of each conversion. */
591 if (HAL_IS_BIT_SET(hadc
->Instance
->CR2
, ADC_CR2_EOCS
) &&
592 HAL_IS_BIT_SET(hadc
->Instance
->CR2
, ADC_CR2_DMA
) )
594 /* Update ADC state machine to error */
595 SET_BIT(hadc
->State
, HAL_ADC_STATE_ERROR_CONFIG
);
597 /* Process unlocked */
604 tickstart
= HAL_GetTick();
606 /* Check End of conversion flag */
607 while(!(__HAL_ADC_GET_FLAG(hadc
, ADC_FLAG_EOC
)))
609 /* Check if timeout is disabled (set to infinite wait) */
610 if(Timeout
!= HAL_MAX_DELAY
)
612 if((Timeout
== 0) || ((HAL_GetTick() - tickstart
) > Timeout
))
614 /* Update ADC state machine to timeout */
615 SET_BIT(hadc
->State
, HAL_ADC_STATE_TIMEOUT
);
617 /* Process unlocked */
625 /* Clear regular group conversion flag */
626 __HAL_ADC_CLEAR_FLAG(hadc
, ADC_FLAG_STRT
| ADC_FLAG_EOC
);
628 /* Update ADC state machine */
629 SET_BIT(hadc
->State
, HAL_ADC_STATE_REG_EOC
);
631 /* Determine whether any further conversion upcoming on group regular */
632 /* by external trigger, continuous mode or scan sequence on going. */
633 /* Note: On STM32F7, there is no independent flag of end of sequence. */
634 /* The test of scan sequence on going is done either with scan */
635 /* sequence disabled or with end of conversion flag set to */
636 /* of end of sequence. */
637 if(ADC_IS_SOFTWARE_START_REGULAR(hadc
) &&
638 (hadc
->Init
.ContinuousConvMode
== DISABLE
) &&
639 (HAL_IS_BIT_CLR(hadc
->Instance
->SQR1
, ADC_SQR1_L
) ||
640 HAL_IS_BIT_CLR(hadc
->Instance
->CR2
, ADC_CR2_EOCS
) ) )
643 CLEAR_BIT(hadc
->State
, HAL_ADC_STATE_REG_BUSY
);
645 if (HAL_IS_BIT_CLR(hadc
->State
, HAL_ADC_STATE_INJ_BUSY
))
647 SET_BIT(hadc
->State
, HAL_ADC_STATE_READY
);
651 /* Return ADC state */
656 * @brief Poll for conversion event
657 * @param hadc: pointer to a ADC_HandleTypeDef structure that contains
658 * the configuration information for the specified ADC.
659 * @param EventType: the ADC event type.
660 * This parameter can be one of the following values:
661 * @arg ADC_AWD_EVENT: ADC Analog watch Dog event.
662 * @arg ADC_OVR_EVENT: ADC Overrun event.
663 * @param Timeout: Timeout value in millisecond.
666 HAL_StatusTypeDef
HAL_ADC_PollForEvent(ADC_HandleTypeDef
* hadc
, uint32_t EventType
, uint32_t Timeout
)
668 uint32_t tickstart
= 0;
670 /* Check the parameters */
671 assert_param(IS_ADC_ALL_INSTANCE(hadc
->Instance
));
672 assert_param(IS_ADC_EVENT_TYPE(EventType
));
675 tickstart
= HAL_GetTick();
677 /* Check selected event flag */
678 while(!(__HAL_ADC_GET_FLAG(hadc
,EventType
)))
680 /* Check for the Timeout */
681 if(Timeout
!= HAL_MAX_DELAY
)
683 if((Timeout
== 0) || ((HAL_GetTick() - tickstart
) > Timeout
))
685 /* Update ADC state machine to timeout */
686 SET_BIT(hadc
->State
, HAL_ADC_STATE_TIMEOUT
);
688 /* Process unlocked */
696 /* Analog watchdog (level out of window) event */
697 if(EventType
== ADC_AWD_EVENT
)
700 SET_BIT(hadc
->State
, HAL_ADC_STATE_AWD1
);
702 /* Clear ADC analog watchdog flag */
703 __HAL_ADC_CLEAR_FLAG(hadc
, ADC_FLAG_AWD
);
709 SET_BIT(hadc
->State
, HAL_ADC_STATE_REG_OVR
);
710 /* Set ADC error code to overrun */
711 SET_BIT(hadc
->ErrorCode
, HAL_ADC_ERROR_OVR
);
713 /* Clear ADC overrun flag */
714 __HAL_ADC_CLEAR_FLAG(hadc
, ADC_FLAG_OVR
);
717 /* Return ADC state */
723 * @brief Enables the interrupt and starts ADC conversion of regular channels.
724 * @param hadc: pointer to a ADC_HandleTypeDef structure that contains
725 * the configuration information for the specified ADC.
726 * @retval HAL status.
728 HAL_StatusTypeDef
HAL_ADC_Start_IT(ADC_HandleTypeDef
* hadc
)
730 __IO
uint32_t counter
= 0;
732 /* Check the parameters */
733 assert_param(IS_FUNCTIONAL_STATE(hadc
->Init
.ContinuousConvMode
));
734 assert_param(IS_ADC_EXT_TRIG_EDGE(hadc
->Init
.ExternalTrigConvEdge
));
739 /* Enable the ADC peripheral */
740 /* Check if ADC peripheral is disabled in order to enable it and wait during
741 Tstab time the ADC's stabilization */
742 if((hadc
->Instance
->CR2
& ADC_CR2_ADON
) != ADC_CR2_ADON
)
744 /* Enable the Peripheral */
745 __HAL_ADC_ENABLE(hadc
);
747 /* Delay for ADC stabilization time */
748 /* Compute number of CPU cycles to wait for */
749 counter
= (ADC_STAB_DELAY_US
* (SystemCoreClock
/ 1000000));
756 /* Start conversion if ADC is effectively enabled */
757 if(HAL_IS_BIT_SET(hadc
->Instance
->CR2
, ADC_CR2_ADON
))
760 /* - Clear state bitfield related to regular group conversion results */
761 /* - Set state bitfield related to regular group operation */
762 ADC_STATE_CLR_SET(hadc
->State
,
763 HAL_ADC_STATE_READY
| HAL_ADC_STATE_REG_EOC
| HAL_ADC_STATE_REG_OVR
,
764 HAL_ADC_STATE_REG_BUSY
);
766 /* If conversions on group regular are also triggering group injected, */
767 /* update ADC state. */
768 if (READ_BIT(hadc
->Instance
->CR1
, ADC_CR1_JAUTO
) != RESET
)
770 ADC_STATE_CLR_SET(hadc
->State
, HAL_ADC_STATE_INJ_EOC
, HAL_ADC_STATE_INJ_BUSY
);
773 /* State machine update: Check if an injected conversion is ongoing */
774 if (HAL_IS_BIT_SET(hadc
->State
, HAL_ADC_STATE_INJ_BUSY
))
776 /* Reset ADC error code fields related to conversions on group regular */
777 CLEAR_BIT(hadc
->ErrorCode
, (HAL_ADC_ERROR_OVR
| HAL_ADC_ERROR_DMA
));
781 /* Reset ADC all error code fields */
782 ADC_CLEAR_ERRORCODE(hadc
);
785 /* Process unlocked */
786 /* Unlock before starting ADC conversions: in case of potential */
787 /* interruption, to let the process to ADC IRQ Handler. */
790 /* Clear regular group conversion flag and overrun flag */
791 /* (To ensure of no unknown state from potential previous ADC operations) */
792 __HAL_ADC_CLEAR_FLAG(hadc
, ADC_FLAG_EOC
| ADC_FLAG_OVR
);
794 /* Enable end of conversion interrupt for regular group */
795 __HAL_ADC_ENABLE_IT(hadc
, (ADC_IT_EOC
| ADC_IT_OVR
));
797 /* Check if Multimode enabled */
798 if(HAL_IS_BIT_CLR(ADC
->CCR
, ADC_CCR_MULTI
))
800 /* if no external trigger present enable software conversion of regular channels */
801 if((hadc
->Instance
->CR2
& ADC_CR2_EXTEN
) == RESET
)
803 /* Enable the selected ADC software conversion for regular group */
804 hadc
->Instance
->CR2
|= (uint32_t)ADC_CR2_SWSTART
;
809 /* if instance of handle correspond to ADC1 and no external trigger present enable software conversion of regular channels */
810 if((hadc
->Instance
== ADC1
) && ((hadc
->Instance
->CR2
& ADC_CR2_EXTEN
) == RESET
))
812 /* Enable the selected ADC software conversion for regular group */
813 hadc
->Instance
->CR2
|= (uint32_t)ADC_CR2_SWSTART
;
818 /* Return function status */
823 * @brief Disables the interrupt and stop ADC conversion of regular channels.
825 * @note Caution: This function will stop also injected channels.
827 * @param hadc: pointer to a ADC_HandleTypeDef structure that contains
828 * the configuration information for the specified ADC.
829 * @retval HAL status.
831 HAL_StatusTypeDef
HAL_ADC_Stop_IT(ADC_HandleTypeDef
* hadc
)
833 /* Check the parameters */
834 assert_param(IS_ADC_ALL_INSTANCE(hadc
->Instance
));
839 /* Stop potential conversion on going, on regular and injected groups */
840 /* Disable ADC peripheral */
841 __HAL_ADC_DISABLE(hadc
);
843 /* Check if ADC is effectively disabled */
844 if(HAL_IS_BIT_CLR(hadc
->Instance
->CR2
, ADC_CR2_ADON
))
846 /* Disable ADC end of conversion interrupt for regular group */
847 __HAL_ADC_DISABLE_IT(hadc
, (ADC_IT_EOC
| ADC_IT_OVR
));
850 ADC_STATE_CLR_SET(hadc
->State
,
851 HAL_ADC_STATE_REG_BUSY
| HAL_ADC_STATE_INJ_BUSY
,
852 HAL_ADC_STATE_READY
);
855 /* Process unlocked */
858 /* Return function status */
863 * @brief Handles ADC interrupt request
864 * @param hadc: pointer to a ADC_HandleTypeDef structure that contains
865 * the configuration information for the specified ADC.
868 void HAL_ADC_IRQHandler(ADC_HandleTypeDef
* hadc
)
870 uint32_t tmp1
= 0, tmp2
= 0;
872 /* Check the parameters */
873 assert_param(IS_FUNCTIONAL_STATE(hadc
->Init
.ContinuousConvMode
));
874 assert_param(IS_ADC_REGULAR_LENGTH(hadc
->Init
.NbrOfConversion
));
875 assert_param(IS_ADC_EOCSelection(hadc
->Init
.EOCSelection
));
877 tmp1
= __HAL_ADC_GET_FLAG(hadc
, ADC_FLAG_EOC
);
878 tmp2
= __HAL_ADC_GET_IT_SOURCE(hadc
, ADC_IT_EOC
);
879 /* Check End of conversion flag for regular channels */
882 /* Update state machine on conversion status if not in error state */
883 if (HAL_IS_BIT_CLR(hadc
->State
, HAL_ADC_STATE_ERROR_INTERNAL
))
886 SET_BIT(hadc
->State
, HAL_ADC_STATE_REG_EOC
);
889 /* Determine whether any further conversion upcoming on group regular */
890 /* by external trigger, continuous mode or scan sequence on going. */
891 /* Note: On STM32F7, there is no independent flag of end of sequence. */
892 /* The test of scan sequence on going is done either with scan */
893 /* sequence disabled or with end of conversion flag set to */
894 /* of end of sequence. */
895 if(ADC_IS_SOFTWARE_START_REGULAR(hadc
) &&
896 (hadc
->Init
.ContinuousConvMode
== DISABLE
) &&
897 (HAL_IS_BIT_CLR(hadc
->Instance
->SQR1
, ADC_SQR1_L
) ||
898 HAL_IS_BIT_CLR(hadc
->Instance
->CR2
, ADC_CR2_EOCS
) ) )
900 /* Disable ADC end of single conversion interrupt on group regular */
901 /* Note: Overrun interrupt was enabled with EOC interrupt in */
902 /* HAL_ADC_Start_IT(), but is not disabled here because can be used */
903 /* by overrun IRQ process below. */
904 __HAL_ADC_DISABLE_IT(hadc
, ADC_IT_EOC
);
907 CLEAR_BIT(hadc
->State
, HAL_ADC_STATE_REG_BUSY
);
909 if (HAL_IS_BIT_CLR(hadc
->State
, HAL_ADC_STATE_INJ_BUSY
))
911 SET_BIT(hadc
->State
, HAL_ADC_STATE_READY
);
915 /* Conversion complete callback */
916 HAL_ADC_ConvCpltCallback(hadc
);
918 /* Clear regular group conversion flag */
919 __HAL_ADC_CLEAR_FLAG(hadc
, ADC_FLAG_STRT
| ADC_FLAG_EOC
);
922 tmp1
= __HAL_ADC_GET_FLAG(hadc
, ADC_FLAG_JEOC
);
923 tmp2
= __HAL_ADC_GET_IT_SOURCE(hadc
, ADC_IT_JEOC
);
924 /* Check End of conversion flag for injected channels */
927 /* Update state machine on conversion status if not in error state */
928 if (HAL_IS_BIT_CLR(hadc
->State
, HAL_ADC_STATE_ERROR_INTERNAL
))
931 SET_BIT(hadc
->State
, HAL_ADC_STATE_INJ_EOC
);
934 /* Determine whether any further conversion upcoming on group injected */
935 /* by external trigger, scan sequence on going or by automatic injected */
936 /* conversion from group regular (same conditions as group regular */
937 /* interruption disabling above). */
938 if(ADC_IS_SOFTWARE_START_INJECTED(hadc
) &&
939 (HAL_IS_BIT_CLR(hadc
->Instance
->JSQR
, ADC_JSQR_JL
) ||
940 HAL_IS_BIT_CLR(hadc
->Instance
->CR2
, ADC_CR2_EOCS
)) &&
941 (HAL_IS_BIT_CLR(hadc
->Instance
->CR1
, ADC_CR1_JAUTO
) &&
942 (ADC_IS_SOFTWARE_START_REGULAR(hadc
) &&
943 (hadc
->Init
.ContinuousConvMode
== DISABLE
))))
945 /* Disable ADC end of single conversion interrupt on group injected */
946 __HAL_ADC_DISABLE_IT(hadc
, ADC_IT_JEOC
);
949 CLEAR_BIT(hadc
->State
, HAL_ADC_STATE_INJ_BUSY
);
951 if (HAL_IS_BIT_CLR(hadc
->State
, HAL_ADC_STATE_REG_BUSY
))
953 SET_BIT(hadc
->State
, HAL_ADC_STATE_READY
);
957 /* Conversion complete callback */
958 HAL_ADCEx_InjectedConvCpltCallback(hadc
);
960 /* Clear injected group conversion flag */
961 __HAL_ADC_CLEAR_FLAG(hadc
, (ADC_FLAG_JSTRT
| ADC_FLAG_JEOC
));
964 tmp1
= __HAL_ADC_GET_FLAG(hadc
, ADC_FLAG_AWD
);
965 tmp2
= __HAL_ADC_GET_IT_SOURCE(hadc
, ADC_IT_AWD
);
966 /* Check Analog watchdog flag */
969 if(__HAL_ADC_GET_FLAG(hadc
, ADC_FLAG_AWD
))
972 SET_BIT(hadc
->State
, HAL_ADC_STATE_AWD1
);
974 /* Level out of window callback */
975 HAL_ADC_LevelOutOfWindowCallback(hadc
);
977 /* Clear the ADC analog watchdog flag */
978 __HAL_ADC_CLEAR_FLAG(hadc
, ADC_FLAG_AWD
);
982 tmp1
= __HAL_ADC_GET_FLAG(hadc
, ADC_FLAG_OVR
);
983 tmp2
= __HAL_ADC_GET_IT_SOURCE(hadc
, ADC_IT_OVR
);
984 /* Check Overrun flag */
987 /* Note: On STM32F7, ADC overrun can be set through other parameters */
988 /* refer to description of parameter "EOCSelection" for more */
991 /* Set ADC error code to overrun */
992 SET_BIT(hadc
->ErrorCode
, HAL_ADC_ERROR_OVR
);
994 /* Clear ADC overrun flag */
995 __HAL_ADC_CLEAR_FLAG(hadc
, ADC_FLAG_OVR
);
998 HAL_ADC_ErrorCallback(hadc
);
1000 /* Clear the Overrun flag */
1001 __HAL_ADC_CLEAR_FLAG(hadc
, ADC_FLAG_OVR
);
1006 * @brief Enables ADC DMA request after last transfer (Single-ADC mode) and enables ADC peripheral
1007 * @param hadc: pointer to a ADC_HandleTypeDef structure that contains
1008 * the configuration information for the specified ADC.
1009 * @param pData: The destination Buffer address.
1010 * @param Length: The length of data to be transferred from ADC peripheral to memory.
1011 * @retval HAL status
1013 HAL_StatusTypeDef
HAL_ADC_Start_DMA(ADC_HandleTypeDef
* hadc
, uint32_t* pData
, uint32_t Length
)
1015 __IO
uint32_t counter
= 0;
1017 /* Check the parameters */
1018 assert_param(IS_FUNCTIONAL_STATE(hadc
->Init
.ContinuousConvMode
));
1019 assert_param(IS_ADC_EXT_TRIG_EDGE(hadc
->Init
.ExternalTrigConvEdge
));
1021 /* Process locked */
1024 /* Enable the ADC peripheral */
1025 /* Check if ADC peripheral is disabled in order to enable it and wait during
1026 Tstab time the ADC's stabilization */
1027 if((hadc
->Instance
->CR2
& ADC_CR2_ADON
) != ADC_CR2_ADON
)
1029 /* Enable the Peripheral */
1030 __HAL_ADC_ENABLE(hadc
);
1032 /* Delay for ADC stabilization time */
1033 /* Compute number of CPU cycles to wait for */
1034 counter
= (ADC_STAB_DELAY_US
* (SystemCoreClock
/ 1000000));
1041 /* Start conversion if ADC is effectively enabled */
1042 if(HAL_IS_BIT_SET(hadc
->Instance
->CR2
, ADC_CR2_ADON
))
1045 /* - Clear state bitfield related to regular group conversion results */
1046 /* - Set state bitfield related to regular group operation */
1047 ADC_STATE_CLR_SET(hadc
->State
,
1048 HAL_ADC_STATE_READY
| HAL_ADC_STATE_REG_EOC
| HAL_ADC_STATE_REG_OVR
,
1049 HAL_ADC_STATE_REG_BUSY
);
1051 /* If conversions on group regular are also triggering group injected, */
1052 /* update ADC state. */
1053 if (READ_BIT(hadc
->Instance
->CR1
, ADC_CR1_JAUTO
) != RESET
)
1055 ADC_STATE_CLR_SET(hadc
->State
, HAL_ADC_STATE_INJ_EOC
, HAL_ADC_STATE_INJ_BUSY
);
1058 /* State machine update: Check if an injected conversion is ongoing */
1059 if (HAL_IS_BIT_SET(hadc
->State
, HAL_ADC_STATE_INJ_BUSY
))
1061 /* Reset ADC error code fields related to conversions on group regular */
1062 CLEAR_BIT(hadc
->ErrorCode
, (HAL_ADC_ERROR_OVR
| HAL_ADC_ERROR_DMA
));
1066 /* Reset ADC all error code fields */
1067 ADC_CLEAR_ERRORCODE(hadc
);
1070 /* Process unlocked */
1071 /* Unlock before starting ADC conversions: in case of potential */
1072 /* interruption, to let the process to ADC IRQ Handler. */
1075 /* Set the DMA transfer complete callback */
1076 hadc
->DMA_Handle
->XferCpltCallback
= ADC_DMAConvCplt
;
1078 /* Set the DMA half transfer complete callback */
1079 hadc
->DMA_Handle
->XferHalfCpltCallback
= ADC_DMAHalfConvCplt
;
1081 /* Set the DMA error callback */
1082 hadc
->DMA_Handle
->XferErrorCallback
= ADC_DMAError
;
1085 /* Manage ADC and DMA start: ADC overrun interruption, DMA start, ADC */
1086 /* start (in case of SW start): */
1088 /* Clear regular group conversion flag and overrun flag */
1089 /* (To ensure of no unknown state from potential previous ADC operations) */
1090 __HAL_ADC_CLEAR_FLAG(hadc
, ADC_FLAG_EOC
| ADC_FLAG_OVR
);
1092 /* Enable ADC overrun interrupt */
1093 __HAL_ADC_ENABLE_IT(hadc
, ADC_IT_OVR
);
1095 /* Enable ADC DMA mode */
1096 hadc
->Instance
->CR2
|= ADC_CR2_DMA
;
1098 /* Start the DMA channel */
1099 HAL_DMA_Start_IT(hadc
->DMA_Handle
, (uint32_t)&hadc
->Instance
->DR
, (uint32_t)pData
, Length
);
1101 /* Check if Multimode enabled */
1102 if(HAL_IS_BIT_CLR(ADC
->CCR
, ADC_CCR_MULTI
))
1104 /* if no external trigger present enable software conversion of regular channels */
1105 if((hadc
->Instance
->CR2
& ADC_CR2_EXTEN
) == RESET
)
1107 /* Enable the selected ADC software conversion for regular group */
1108 hadc
->Instance
->CR2
|= (uint32_t)ADC_CR2_SWSTART
;
1113 /* if instance of handle correspond to ADC1 and no external trigger present enable software conversion of regular channels */
1114 if((hadc
->Instance
== ADC1
) && ((hadc
->Instance
->CR2
& ADC_CR2_EXTEN
) == RESET
))
1116 /* Enable the selected ADC software conversion for regular group */
1117 hadc
->Instance
->CR2
|= (uint32_t)ADC_CR2_SWSTART
;
1122 /* Return function status */
1127 * @brief Disables ADC DMA (Single-ADC mode) and disables ADC peripheral
1128 * @param hadc: pointer to a ADC_HandleTypeDef structure that contains
1129 * the configuration information for the specified ADC.
1130 * @retval HAL status
1132 HAL_StatusTypeDef
HAL_ADC_Stop_DMA(ADC_HandleTypeDef
* hadc
)
1134 HAL_StatusTypeDef tmp_hal_status
= HAL_OK
;
1136 /* Check the parameters */
1137 assert_param(IS_ADC_ALL_INSTANCE(hadc
->Instance
));
1139 /* Process locked */
1142 /* Stop potential conversion on going, on regular and injected groups */
1143 /* Disable ADC peripheral */
1144 __HAL_ADC_DISABLE(hadc
);
1146 /* Check if ADC is effectively disabled */
1147 if(HAL_IS_BIT_CLR(hadc
->Instance
->CR2
, ADC_CR2_ADON
))
1149 /* Disable the selected ADC DMA mode */
1150 hadc
->Instance
->CR2
&= ~ADC_CR2_DMA
;
1152 /* Disable the DMA channel (in case of DMA in circular mode or stop while */
1153 /* DMA transfer is on going) */
1154 tmp_hal_status
= HAL_DMA_Abort(hadc
->DMA_Handle
);
1156 /* Disable ADC overrun interrupt */
1157 __HAL_ADC_DISABLE_IT(hadc
, ADC_IT_OVR
);
1160 ADC_STATE_CLR_SET(hadc
->State
,
1161 HAL_ADC_STATE_REG_BUSY
| HAL_ADC_STATE_INJ_BUSY
,
1162 HAL_ADC_STATE_READY
);
1165 /* Process unlocked */
1168 /* Return function status */
1169 return tmp_hal_status
;
1173 * @brief Gets the converted value from data register of regular channel.
1174 * @param hadc: pointer to a ADC_HandleTypeDef structure that contains
1175 * the configuration information for the specified ADC.
1176 * @retval Converted value
1178 uint32_t HAL_ADC_GetValue(ADC_HandleTypeDef
* hadc
)
1180 /* Return the selected ADC converted value */
1181 return hadc
->Instance
->DR
;
1185 * @brief Regular conversion complete callback in non blocking mode
1186 * @param hadc: pointer to a ADC_HandleTypeDef structure that contains
1187 * the configuration information for the specified ADC.
1190 __weak
void HAL_ADC_ConvCpltCallback(ADC_HandleTypeDef
* hadc
)
1192 /* Prevent unused argument(s) compilation warning */
1194 /* NOTE : This function Should not be modified, when the callback is needed,
1195 the HAL_ADC_ConvCpltCallback could be implemented in the user file
1200 * @brief Regular conversion half DMA transfer callback in non blocking mode
1201 * @param hadc: pointer to a ADC_HandleTypeDef structure that contains
1202 * the configuration information for the specified ADC.
1205 __weak
void HAL_ADC_ConvHalfCpltCallback(ADC_HandleTypeDef
* hadc
)
1207 /* Prevent unused argument(s) compilation warning */
1209 /* NOTE : This function Should not be modified, when the callback is needed,
1210 the HAL_ADC_ConvHalfCpltCallback could be implemented in the user file
1215 * @brief Analog watchdog callback in non blocking mode
1216 * @param hadc: pointer to a ADC_HandleTypeDef structure that contains
1217 * the configuration information for the specified ADC.
1220 __weak
void HAL_ADC_LevelOutOfWindowCallback(ADC_HandleTypeDef
* hadc
)
1222 /* Prevent unused argument(s) compilation warning */
1224 /* NOTE : This function Should not be modified, when the callback is needed,
1225 the HAL_ADC_LevelOoutOfWindowCallback could be implemented in the user file
1230 * @brief Error ADC callback.
1231 * @note In case of error due to overrun when using ADC with DMA transfer
1232 * (HAL ADC handle paramater "ErrorCode" to state "HAL_ADC_ERROR_OVR"):
1233 * - Reinitialize the DMA using function "HAL_ADC_Stop_DMA()".
1234 * - If needed, restart a new ADC conversion using function
1235 * "HAL_ADC_Start_DMA()"
1236 * (this function is also clearing overrun flag)
1237 * @param hadc: pointer to a ADC_HandleTypeDef structure that contains
1238 * the configuration information for the specified ADC.
1241 __weak
void HAL_ADC_ErrorCallback(ADC_HandleTypeDef
*hadc
)
1243 /* Prevent unused argument(s) compilation warning */
1245 /* NOTE : This function Should not be modified, when the callback is needed,
1246 the HAL_ADC_ErrorCallback could be implemented in the user file
1254 /** @defgroup ADC_Exported_Functions_Group3 Peripheral Control functions
1255 * @brief Peripheral Control functions
1258 ===============================================================================
1259 ##### Peripheral Control functions #####
1260 ===============================================================================
1261 [..] This section provides functions allowing to:
1262 (+) Configure regular channels.
1263 (+) Configure injected channels.
1264 (+) Configure multimode.
1265 (+) Configure the analog watch dog.
1272 * @brief Configures for the selected ADC regular channel its corresponding
1273 * rank in the sequencer and its sample time.
1274 * @param hadc: pointer to a ADC_HandleTypeDef structure that contains
1275 * the configuration information for the specified ADC.
1276 * @param sConfig: ADC configuration structure.
1277 * @retval HAL status
1279 HAL_StatusTypeDef
HAL_ADC_ConfigChannel(ADC_HandleTypeDef
* hadc
, ADC_ChannelConfTypeDef
* sConfig
)
1281 __IO
uint32_t counter
= 0;
1283 /* Check the parameters */
1284 assert_param(IS_ADC_CHANNEL(sConfig
->Channel
));
1285 assert_param(IS_ADC_REGULAR_RANK(sConfig
->Rank
));
1286 assert_param(IS_ADC_SAMPLE_TIME(sConfig
->SamplingTime
));
1288 /* Process locked */
1291 /* if ADC_Channel_10 ... ADC_Channel_18 is selected */
1292 if (sConfig
->Channel
> ADC_CHANNEL_9
)
1294 /* Clear the old sample time */
1295 hadc
->Instance
->SMPR1
&= ~ADC_SMPR1(ADC_SMPR1_SMP10
, sConfig
->Channel
);
1297 if (sConfig
->Channel
== ADC_CHANNEL_TEMPSENSOR
)
1299 /* Set the new sample time */
1300 hadc
->Instance
->SMPR1
|= ADC_SMPR1(sConfig
->SamplingTime
, ADC_CHANNEL_18
);
1304 /* Set the new sample time */
1305 hadc
->Instance
->SMPR1
|= ADC_SMPR1(sConfig
->SamplingTime
, sConfig
->Channel
);
1308 else /* ADC_Channel include in ADC_Channel_[0..9] */
1310 /* Clear the old sample time */
1311 hadc
->Instance
->SMPR2
&= ~ADC_SMPR2(ADC_SMPR2_SMP0
, sConfig
->Channel
);
1313 /* Set the new sample time */
1314 hadc
->Instance
->SMPR2
|= ADC_SMPR2(sConfig
->SamplingTime
, sConfig
->Channel
);
1317 /* For Rank 1 to 6 */
1318 if (sConfig
->Rank
< 7)
1320 /* Clear the old SQx bits for the selected rank */
1321 hadc
->Instance
->SQR3
&= ~ADC_SQR3_RK(ADC_SQR3_SQ1
, sConfig
->Rank
);
1323 /* Set the SQx bits for the selected rank */
1324 hadc
->Instance
->SQR3
|= ADC_SQR3_RK(sConfig
->Channel
, sConfig
->Rank
);
1326 /* For Rank 7 to 12 */
1327 else if (sConfig
->Rank
< 13)
1329 /* Clear the old SQx bits for the selected rank */
1330 hadc
->Instance
->SQR2
&= ~ADC_SQR2_RK(ADC_SQR2_SQ7
, sConfig
->Rank
);
1332 /* Set the SQx bits for the selected rank */
1333 hadc
->Instance
->SQR2
|= ADC_SQR2_RK(sConfig
->Channel
, sConfig
->Rank
);
1335 /* For Rank 13 to 16 */
1338 /* Clear the old SQx bits for the selected rank */
1339 hadc
->Instance
->SQR1
&= ~ADC_SQR1_RK(ADC_SQR1_SQ13
, sConfig
->Rank
);
1341 /* Set the SQx bits for the selected rank */
1342 hadc
->Instance
->SQR1
|= ADC_SQR1_RK(sConfig
->Channel
, sConfig
->Rank
);
1345 /* if ADC1 Channel_18 is selected enable VBAT Channel */
1346 if ((hadc
->Instance
== ADC1
) && (sConfig
->Channel
== ADC_CHANNEL_VBAT
))
1348 /* Enable the VBAT channel*/
1349 ADC
->CCR
|= ADC_CCR_VBATE
;
1352 /* if ADC1 Channel_18 or Channel_17 is selected enable TSVREFE Channel(Temperature sensor and VREFINT) */
1353 if ((hadc
->Instance
== ADC1
) && ((sConfig
->Channel
== ADC_CHANNEL_TEMPSENSOR
) || (sConfig
->Channel
== ADC_CHANNEL_VREFINT
)))
1355 /* Enable the TSVREFE channel*/
1356 ADC
->CCR
|= ADC_CCR_TSVREFE
;
1358 if(sConfig
->Channel
== ADC_CHANNEL_TEMPSENSOR
)
1360 /* Delay for temperature sensor stabilization time */
1361 /* Compute number of CPU cycles to wait for */
1362 counter
= (ADC_TEMPSENSOR_DELAY_US
* (SystemCoreClock
/ 1000000));
1370 /* Process unlocked */
1373 /* Return function status */
1378 * @brief Configures the analog watchdog.
1379 * @note Analog watchdog thresholds can be modified while ADC conversion
1381 * In this case, some constraints must be taken into account:
1382 * the programmed threshold values are effective from the next
1383 * ADC EOC (end of unitary conversion).
1384 * Considering that registers write delay may happen due to
1385 * bus activity, this might cause an uncertainty on the
1386 * effective timing of the new programmed threshold values.
1387 * @param hadc: pointer to a ADC_HandleTypeDef structure that contains
1388 * the configuration information for the specified ADC.
1389 * @param AnalogWDGConfig : pointer to an ADC_AnalogWDGConfTypeDef structure
1390 * that contains the configuration information of ADC analog watchdog.
1391 * @retval HAL status
1393 HAL_StatusTypeDef
HAL_ADC_AnalogWDGConfig(ADC_HandleTypeDef
* hadc
, ADC_AnalogWDGConfTypeDef
* AnalogWDGConfig
)
1395 #ifdef USE_FULL_ASSERT
1397 #endif /* USE_FULL_ASSERT */
1399 /* Check the parameters */
1400 assert_param(IS_ADC_ANALOG_WATCHDOG(AnalogWDGConfig
->WatchdogMode
));
1401 assert_param(IS_ADC_CHANNEL(AnalogWDGConfig
->Channel
));
1402 assert_param(IS_FUNCTIONAL_STATE(AnalogWDGConfig
->ITMode
));
1404 #ifdef USE_FULL_ASSERT
1405 tmp
= ADC_GET_RESOLUTION(hadc
);
1406 assert_param(IS_ADC_RANGE(tmp
, AnalogWDGConfig
->HighThreshold
));
1407 assert_param(IS_ADC_RANGE(tmp
, AnalogWDGConfig
->LowThreshold
));
1408 #endif /* USE_FULL_ASSERT */
1410 /* Process locked */
1413 if(AnalogWDGConfig
->ITMode
== ENABLE
)
1415 /* Enable the ADC Analog watchdog interrupt */
1416 __HAL_ADC_ENABLE_IT(hadc
, ADC_IT_AWD
);
1420 /* Disable the ADC Analog watchdog interrupt */
1421 __HAL_ADC_DISABLE_IT(hadc
, ADC_IT_AWD
);
1424 /* Clear AWDEN, JAWDEN and AWDSGL bits */
1425 hadc
->Instance
->CR1
&= ~(ADC_CR1_AWDSGL
| ADC_CR1_JAWDEN
| ADC_CR1_AWDEN
);
1427 /* Set the analog watchdog enable mode */
1428 hadc
->Instance
->CR1
|= AnalogWDGConfig
->WatchdogMode
;
1430 /* Set the high threshold */
1431 hadc
->Instance
->HTR
= AnalogWDGConfig
->HighThreshold
;
1433 /* Set the low threshold */
1434 hadc
->Instance
->LTR
= AnalogWDGConfig
->LowThreshold
;
1436 /* Clear the Analog watchdog channel select bits */
1437 hadc
->Instance
->CR1
&= ~ADC_CR1_AWDCH
;
1439 /* Set the Analog watchdog channel */
1440 hadc
->Instance
->CR1
|= (uint32_t)((uint16_t)(AnalogWDGConfig
->Channel
));
1442 /* Process unlocked */
1445 /* Return function status */
1453 /** @defgroup ADC_Exported_Functions_Group4 ADC Peripheral State functions
1454 * @brief ADC Peripheral State functions
1457 ===============================================================================
1458 ##### Peripheral State and errors functions #####
1459 ===============================================================================
1461 This subsection provides functions allowing to
1462 (+) Check the ADC state
1463 (+) Check the ADC Error
1470 * @brief return the ADC state
1471 * @param hadc: pointer to a ADC_HandleTypeDef structure that contains
1472 * the configuration information for the specified ADC.
1475 uint32_t HAL_ADC_GetState(ADC_HandleTypeDef
* hadc
)
1477 /* Return ADC state */
1482 * @brief Return the ADC error code
1483 * @param hadc: pointer to a ADC_HandleTypeDef structure that contains
1484 * the configuration information for the specified ADC.
1485 * @retval ADC Error Code
1487 uint32_t HAL_ADC_GetError(ADC_HandleTypeDef
*hadc
)
1489 return hadc
->ErrorCode
;
1500 /* Private functions ---------------------------------------------------------*/
1502 /** @defgroup ADC_Private_Functions ADC Private Functions
1507 * @brief Initializes the ADCx peripheral according to the specified parameters
1508 * in the ADC_InitStruct without initializing the ADC MSP.
1509 * @param hadc: pointer to a ADC_HandleTypeDef structure that contains
1510 * the configuration information for the specified ADC.
1513 static void ADC_Init(ADC_HandleTypeDef
* hadc
)
1515 /* Set ADC parameters */
1516 /* Set the ADC clock prescaler */
1517 ADC
->CCR
&= ~(ADC_CCR_ADCPRE
);
1518 ADC
->CCR
|= hadc
->Init
.ClockPrescaler
;
1520 /* Set ADC scan mode */
1521 hadc
->Instance
->CR1
&= ~(ADC_CR1_SCAN
);
1522 hadc
->Instance
->CR1
|= ADC_CR1_SCANCONV(hadc
->Init
.ScanConvMode
);
1524 /* Set ADC resolution */
1525 hadc
->Instance
->CR1
&= ~(ADC_CR1_RES
);
1526 hadc
->Instance
->CR1
|= hadc
->Init
.Resolution
;
1528 /* Set ADC data alignment */
1529 hadc
->Instance
->CR2
&= ~(ADC_CR2_ALIGN
);
1530 hadc
->Instance
->CR2
|= hadc
->Init
.DataAlign
;
1532 /* Enable external trigger if trigger selection is different of software */
1534 /* Note: This configuration keeps the hardware feature of parameter */
1535 /* ExternalTrigConvEdge "trigger edge none" equivalent to */
1536 /* software start. */
1537 if(hadc
->Init
.ExternalTrigConv
!= ADC_SOFTWARE_START
)
1539 /* Select external trigger to start conversion */
1540 hadc
->Instance
->CR2
&= ~(ADC_CR2_EXTSEL
);
1541 hadc
->Instance
->CR2
|= hadc
->Init
.ExternalTrigConv
;
1543 /* Select external trigger polarity */
1544 hadc
->Instance
->CR2
&= ~(ADC_CR2_EXTEN
);
1545 hadc
->Instance
->CR2
|= hadc
->Init
.ExternalTrigConvEdge
;
1549 /* Reset the external trigger */
1550 hadc
->Instance
->CR2
&= ~(ADC_CR2_EXTSEL
);
1551 hadc
->Instance
->CR2
&= ~(ADC_CR2_EXTEN
);
1554 /* Enable or disable ADC continuous conversion mode */
1555 hadc
->Instance
->CR2
&= ~(ADC_CR2_CONT
);
1556 hadc
->Instance
->CR2
|= ADC_CR2_CONTINUOUS(hadc
->Init
.ContinuousConvMode
);
1558 if(hadc
->Init
.DiscontinuousConvMode
!= DISABLE
)
1560 assert_param(IS_ADC_REGULAR_DISC_NUMBER(hadc
->Init
.NbrOfDiscConversion
));
1562 /* Enable the selected ADC regular discontinuous mode */
1563 hadc
->Instance
->CR1
|= (uint32_t)ADC_CR1_DISCEN
;
1565 /* Set the number of channels to be converted in discontinuous mode */
1566 hadc
->Instance
->CR1
&= ~(ADC_CR1_DISCNUM
);
1567 hadc
->Instance
->CR1
|= ADC_CR1_DISCONTINUOUS(hadc
->Init
.NbrOfDiscConversion
);
1571 /* Disable the selected ADC regular discontinuous mode */
1572 hadc
->Instance
->CR1
&= ~(ADC_CR1_DISCEN
);
1575 /* Set ADC number of conversion */
1576 hadc
->Instance
->SQR1
&= ~(ADC_SQR1_L
);
1577 hadc
->Instance
->SQR1
|= ADC_SQR1(hadc
->Init
.NbrOfConversion
);
1579 /* Enable or disable ADC DMA continuous request */
1580 hadc
->Instance
->CR2
&= ~(ADC_CR2_DDS
);
1581 hadc
->Instance
->CR2
|= ADC_CR2_DMAContReq(hadc
->Init
.DMAContinuousRequests
);
1583 /* Enable or disable ADC end of conversion selection */
1584 hadc
->Instance
->CR2
&= ~(ADC_CR2_EOCS
);
1585 hadc
->Instance
->CR2
|= ADC_CR2_EOCSelection(hadc
->Init
.EOCSelection
);
1589 * @brief DMA transfer complete callback.
1590 * @param hdma: pointer to a DMA_HandleTypeDef structure that contains
1591 * the configuration information for the specified DMA module.
1594 static void ADC_DMAConvCplt(DMA_HandleTypeDef
*hdma
)
1596 /* Retrieve ADC handle corresponding to current DMA handle */
1597 ADC_HandleTypeDef
* hadc
= ( ADC_HandleTypeDef
* )((DMA_HandleTypeDef
* )hdma
)->Parent
;
1599 /* Update state machine on conversion status if not in error state */
1600 if (HAL_IS_BIT_CLR(hadc
->State
, HAL_ADC_STATE_ERROR_INTERNAL
| HAL_ADC_STATE_ERROR_DMA
))
1602 /* Update ADC state machine */
1603 SET_BIT(hadc
->State
, HAL_ADC_STATE_REG_EOC
);
1605 /* Determine whether any further conversion upcoming on group regular */
1606 /* by external trigger, continuous mode or scan sequence on going. */
1607 /* Note: On STM32F7, there is no independent flag of end of sequence. */
1608 /* The test of scan sequence on going is done either with scan */
1609 /* sequence disabled or with end of conversion flag set to */
1610 /* of end of sequence. */
1611 if(ADC_IS_SOFTWARE_START_REGULAR(hadc
) &&
1612 (hadc
->Init
.ContinuousConvMode
== DISABLE
) &&
1613 (HAL_IS_BIT_CLR(hadc
->Instance
->SQR1
, ADC_SQR1_L
) ||
1614 HAL_IS_BIT_CLR(hadc
->Instance
->CR2
, ADC_CR2_EOCS
) ) )
1616 /* Disable ADC end of single conversion interrupt on group regular */
1617 /* Note: Overrun interrupt was enabled with EOC interrupt in */
1618 /* HAL_ADC_Start_IT(), but is not disabled here because can be used */
1619 /* by overrun IRQ process below. */
1620 __HAL_ADC_DISABLE_IT(hadc
, ADC_IT_EOC
);
1623 CLEAR_BIT(hadc
->State
, HAL_ADC_STATE_REG_BUSY
);
1625 if (HAL_IS_BIT_CLR(hadc
->State
, HAL_ADC_STATE_INJ_BUSY
))
1627 SET_BIT(hadc
->State
, HAL_ADC_STATE_READY
);
1631 /* Conversion complete callback */
1632 HAL_ADC_ConvCpltCallback(hadc
);
1636 /* Call DMA error callback */
1637 hadc
->DMA_Handle
->XferErrorCallback(hdma
);
1642 * @brief DMA half transfer complete callback.
1643 * @param hdma: pointer to a DMA_HandleTypeDef structure that contains
1644 * the configuration information for the specified DMA module.
1647 static void ADC_DMAHalfConvCplt(DMA_HandleTypeDef
*hdma
)
1649 ADC_HandleTypeDef
* hadc
= ( ADC_HandleTypeDef
* )((DMA_HandleTypeDef
* )hdma
)->Parent
;
1650 /* Conversion complete callback */
1651 HAL_ADC_ConvHalfCpltCallback(hadc
);
1655 * @brief DMA error callback
1656 * @param hdma: pointer to a DMA_HandleTypeDef structure that contains
1657 * the configuration information for the specified DMA module.
1660 static void ADC_DMAError(DMA_HandleTypeDef
*hdma
)
1662 ADC_HandleTypeDef
* hadc
= ( ADC_HandleTypeDef
* )((DMA_HandleTypeDef
* )hdma
)->Parent
;
1663 hadc
->State
= HAL_ADC_STATE_ERROR_DMA
;
1664 /* Set ADC error code to DMA error */
1665 hadc
->ErrorCode
|= HAL_ADC_ERROR_DMA
;
1666 HAL_ADC_ErrorCallback(hadc
);
1677 #endif /* HAL_ADC_MODULE_ENABLED */
1686 /************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/