F1 and F3 HAL / LL libraries
[betaflight.git] / lib / main / STM32F1 / Drivers / STM32F1xx_HAL_Driver / Src / stm32f1xx_hal_adc_ex.c
blob6f04c41dbbdd04336b270f9d5a91faa0b39edcb8
1 /**
2 ******************************************************************************
3 * @file stm32f1xx_hal_adc_ex.c
4 * @author MCD Application Team
5 * @version V1.1.1
6 * @date 12-May-2017
7 * @brief This file provides firmware functions to manage the following
8 * functionalities of the Analog to Digital Convertor (ADC)
9 * peripheral:
10 * + Operation functions
11 * ++ Start, stop, get result of conversions of injected
12 * group, using 2 possible modes: polling, interruption.
13 * ++ Multimode feature (available on devices with 2 ADCs or more)
14 * ++ Calibration (ADC automatic self-calibration)
15 * + Control functions
16 * ++ Channels configuration on injected group
17 * Other functions (generic functions) are available in file
18 * "stm32f1xx_hal_adc.c".
20 @verbatim
21 [..]
22 (@) Sections "ADC peripheral features" and "How to use this driver" are
23 available in file of generic functions "stm32f1xx_hal_adc.c".
24 [..]
25 @endverbatim
26 ******************************************************************************
27 * @attention
29 * <h2><center>&copy; COPYRIGHT(c) 2016 STMicroelectronics</center></h2>
31 * Redistribution and use in source and binary forms, with or without modification,
32 * are permitted provided that the following conditions are met:
33 * 1. Redistributions of source code must retain the above copyright notice,
34 * this list of conditions and the following disclaimer.
35 * 2. Redistributions in binary form must reproduce the above copyright notice,
36 * this list of conditions and the following disclaimer in the documentation
37 * and/or other materials provided with the distribution.
38 * 3. Neither the name of STMicroelectronics nor the names of its contributors
39 * may be used to endorse or promote products derived from this software
40 * without specific prior written permission.
42 * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
43 * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
44 * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE
45 * DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE
46 * FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL
47 * DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR
48 * SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
49 * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY,
50 * OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE
51 * OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
53 ******************************************************************************
56 /* Includes ------------------------------------------------------------------*/
57 #include "stm32f1xx_hal.h"
59 /** @addtogroup STM32F1xx_HAL_Driver
60 * @{
63 /** @defgroup ADCEx ADCEx
64 * @brief ADC Extension HAL module driver
65 * @{
68 #ifdef HAL_ADC_MODULE_ENABLED
70 /* Private typedef -----------------------------------------------------------*/
71 /* Private define ------------------------------------------------------------*/
72 /** @defgroup ADCEx_Private_Constants ADCEx Private Constants
73 * @{
76 /* Delay for ADC calibration: */
77 /* Hardware prerequisite before starting a calibration: the ADC must have */
78 /* been in power-on state for at least two ADC clock cycles. */
79 /* Unit: ADC clock cycles */
80 #define ADC_PRECALIBRATION_DELAY_ADCCLOCKCYCLES 2U
82 /* Timeout value for ADC calibration */
83 /* Value defined to be higher than worst cases: low clocks freq, */
84 /* maximum prescaler. */
85 /* Ex of profile low frequency : Clock source at 0.1 MHz, ADC clock */
86 /* prescaler 4, sampling time 12.5 ADC clock cycles, resolution 12 bits. */
87 /* Unit: ms */
88 #define ADC_CALIBRATION_TIMEOUT 10U
90 /* Delay for temperature sensor stabilization time. */
91 /* Maximum delay is 10us (refer to device datasheet, parameter tSTART). */
92 /* Unit: us */
93 #define ADC_TEMPSENSOR_DELAY_US 10U
95 /**
96 * @}
99 /* Private macro -------------------------------------------------------------*/
100 /* Private variables ---------------------------------------------------------*/
101 /* Private function prototypes -----------------------------------------------*/
102 /* Private functions ---------------------------------------------------------*/
104 /** @defgroup ADCEx_Exported_Functions ADCEx Exported Functions
105 * @{
108 /** @defgroup ADCEx_Exported_Functions_Group1 Extended Extended IO operation functions
109 * @brief Extended Extended Input and Output operation functions
111 @verbatim
112 ===============================================================================
113 ##### IO operation functions #####
114 ===============================================================================
115 [..] This section provides functions allowing to:
116 (+) Start conversion of injected group.
117 (+) Stop conversion of injected group.
118 (+) Poll for conversion complete on injected group.
119 (+) Get result of injected channel conversion.
120 (+) Start conversion of injected group and enable interruptions.
121 (+) Stop conversion of injected group and disable interruptions.
123 (+) Start multimode and enable DMA transfer.
124 (+) Stop multimode and disable ADC DMA transfer.
125 (+) Get result of multimode conversion.
127 (+) Perform the ADC self-calibration for single or differential ending.
128 (+) Get calibration factors for single or differential ending.
129 (+) Set calibration factors for single or differential ending.
131 @endverbatim
132 * @{
136 * @brief Perform an ADC automatic self-calibration
137 * Calibration prerequisite: ADC must be disabled (execute this
138 * function before HAL_ADC_Start() or after HAL_ADC_Stop() ).
139 * During calibration process, ADC is enabled. ADC is let enabled at
140 * the completion of this function.
141 * @param hadc: ADC handle
142 * @retval HAL status
144 HAL_StatusTypeDef HAL_ADCEx_Calibration_Start(ADC_HandleTypeDef* hadc)
146 HAL_StatusTypeDef tmp_hal_status = HAL_OK;
147 uint32_t tickstart;
148 __IO uint32_t wait_loop_index = 0U;
150 /* Check the parameters */
151 assert_param(IS_ADC_ALL_INSTANCE(hadc->Instance));
153 /* Process locked */
154 __HAL_LOCK(hadc);
156 /* 1. Calibration prerequisite: */
157 /* - ADC must be disabled for at least two ADC clock cycles in disable */
158 /* mode before ADC enable */
159 /* Stop potential conversion on going, on regular and injected groups */
160 /* Disable ADC peripheral */
161 tmp_hal_status = ADC_ConversionStop_Disable(hadc);
163 /* Check if ADC is effectively disabled */
164 if (tmp_hal_status == HAL_OK)
166 /* Set ADC state */
167 ADC_STATE_CLR_SET(hadc->State,
168 HAL_ADC_STATE_REG_BUSY | HAL_ADC_STATE_INJ_BUSY,
169 HAL_ADC_STATE_BUSY_INTERNAL);
171 /* Hardware prerequisite: delay before starting the calibration. */
172 /* - Computation of CPU clock cycles corresponding to ADC clock cycles. */
173 /* - Wait for the expected ADC clock cycles delay */
174 wait_loop_index = ((SystemCoreClock
175 / HAL_RCCEx_GetPeriphCLKFreq(RCC_PERIPHCLK_ADC))
176 * ADC_PRECALIBRATION_DELAY_ADCCLOCKCYCLES );
178 while(wait_loop_index != 0U)
180 wait_loop_index--;
183 /* 2. Enable the ADC peripheral */
184 ADC_Enable(hadc);
186 /* 3. Resets ADC calibration registers */
187 SET_BIT(hadc->Instance->CR2, ADC_CR2_RSTCAL);
189 tickstart = HAL_GetTick();
191 /* Wait for calibration reset completion */
192 while(HAL_IS_BIT_SET(hadc->Instance->CR2, ADC_CR2_RSTCAL))
194 if((HAL_GetTick() - tickstart) > ADC_CALIBRATION_TIMEOUT)
196 /* Update ADC state machine to error */
197 ADC_STATE_CLR_SET(hadc->State,
198 HAL_ADC_STATE_BUSY_INTERNAL,
199 HAL_ADC_STATE_ERROR_INTERNAL);
201 /* Process unlocked */
202 __HAL_UNLOCK(hadc);
204 return HAL_ERROR;
209 /* 4. Start ADC calibration */
210 SET_BIT(hadc->Instance->CR2, ADC_CR2_CAL);
212 tickstart = HAL_GetTick();
214 /* Wait for calibration completion */
215 while(HAL_IS_BIT_SET(hadc->Instance->CR2, ADC_CR2_CAL))
217 if((HAL_GetTick() - tickstart) > ADC_CALIBRATION_TIMEOUT)
219 /* Update ADC state machine to error */
220 ADC_STATE_CLR_SET(hadc->State,
221 HAL_ADC_STATE_BUSY_INTERNAL,
222 HAL_ADC_STATE_ERROR_INTERNAL);
224 /* Process unlocked */
225 __HAL_UNLOCK(hadc);
227 return HAL_ERROR;
231 /* Set ADC state */
232 ADC_STATE_CLR_SET(hadc->State,
233 HAL_ADC_STATE_BUSY_INTERNAL,
234 HAL_ADC_STATE_READY);
237 /* Process unlocked */
238 __HAL_UNLOCK(hadc);
240 /* Return function status */
241 return tmp_hal_status;
245 * @brief Enables ADC, starts conversion of injected group.
246 * Interruptions enabled in this function: None.
247 * @param hadc: ADC handle
248 * @retval HAL status
250 HAL_StatusTypeDef HAL_ADCEx_InjectedStart(ADC_HandleTypeDef* hadc)
252 HAL_StatusTypeDef tmp_hal_status = HAL_OK;
254 /* Check the parameters */
255 assert_param(IS_ADC_ALL_INSTANCE(hadc->Instance));
257 /* Process locked */
258 __HAL_LOCK(hadc);
260 /* Enable the ADC peripheral */
261 tmp_hal_status = ADC_Enable(hadc);
263 /* Start conversion if ADC is effectively enabled */
264 if (tmp_hal_status == HAL_OK)
266 /* Set ADC state */
267 /* - Clear state bitfield related to injected group conversion results */
268 /* - Set state bitfield related to injected operation */
269 ADC_STATE_CLR_SET(hadc->State,
270 HAL_ADC_STATE_READY | HAL_ADC_STATE_INJ_EOC,
271 HAL_ADC_STATE_INJ_BUSY);
273 /* Case of independent mode or multimode (for devices with several ADCs): */
274 /* Set multimode state. */
275 if (ADC_NONMULTIMODE_OR_MULTIMODEMASTER(hadc))
277 CLEAR_BIT(hadc->State, HAL_ADC_STATE_MULTIMODE_SLAVE);
279 else
281 SET_BIT(hadc->State, HAL_ADC_STATE_MULTIMODE_SLAVE);
284 /* Check if a regular conversion is ongoing */
285 /* Note: On this device, there is no ADC error code fields related to */
286 /* conversions on group injected only. In case of conversion on */
287 /* going on group regular, no error code is reset. */
288 if (HAL_IS_BIT_CLR(hadc->State, HAL_ADC_STATE_REG_BUSY))
290 /* Reset ADC all error code fields */
291 ADC_CLEAR_ERRORCODE(hadc);
294 /* Process unlocked */
295 /* Unlock before starting ADC conversions: in case of potential */
296 /* interruption, to let the process to ADC IRQ Handler. */
297 __HAL_UNLOCK(hadc);
299 /* Clear injected group conversion flag */
300 /* (To ensure of no unknown state from potential previous ADC operations) */
301 __HAL_ADC_CLEAR_FLAG(hadc, ADC_FLAG_JEOC);
303 /* Enable conversion of injected group. */
304 /* If software start has been selected, conversion starts immediately. */
305 /* If external trigger has been selected, conversion will start at next */
306 /* trigger event. */
307 /* If automatic injected conversion is enabled, conversion will start */
308 /* after next regular group conversion. */
309 /* Case of multimode enabled (for devices with several ADCs): if ADC is */
310 /* slave, ADC is enabled only (conversion is not started). If ADC is */
311 /* master, ADC is enabled and conversion is started. */
312 if (HAL_IS_BIT_CLR(hadc->Instance->CR1, ADC_CR1_JAUTO))
314 if (ADC_IS_SOFTWARE_START_INJECTED(hadc) &&
315 ADC_NONMULTIMODE_OR_MULTIMODEMASTER(hadc) )
317 /* Start ADC conversion on injected group with SW start */
318 SET_BIT(hadc->Instance->CR2, (ADC_CR2_JSWSTART | ADC_CR2_JEXTTRIG));
320 else
322 /* Start ADC conversion on injected group with external trigger */
323 SET_BIT(hadc->Instance->CR2, ADC_CR2_JEXTTRIG);
327 else
329 /* Process unlocked */
330 __HAL_UNLOCK(hadc);
333 /* Return function status */
334 return tmp_hal_status;
338 * @brief Stop conversion of injected channels. Disable ADC peripheral if
339 * no regular conversion is on going.
340 * @note If ADC must be disabled and if conversion is on going on
341 * regular group, function HAL_ADC_Stop must be used to stop both
342 * injected and regular groups, and disable the ADC.
343 * @note If injected group mode auto-injection is enabled,
344 * function HAL_ADC_Stop must be used.
345 * @note In case of auto-injection mode, HAL_ADC_Stop must be used.
346 * @param hadc: ADC handle
347 * @retval None
349 HAL_StatusTypeDef HAL_ADCEx_InjectedStop(ADC_HandleTypeDef* hadc)
351 HAL_StatusTypeDef tmp_hal_status = HAL_OK;
353 /* Check the parameters */
354 assert_param(IS_ADC_ALL_INSTANCE(hadc->Instance));
356 /* Process locked */
357 __HAL_LOCK(hadc);
359 /* Stop potential conversion and disable ADC peripheral */
360 /* Conditioned to: */
361 /* - No conversion on the other group (regular group) is intended to */
362 /* continue (injected and regular groups stop conversion and ADC disable */
363 /* are common) */
364 /* - In case of auto-injection mode, HAL_ADC_Stop must be used. */
365 if(((hadc->State & HAL_ADC_STATE_REG_BUSY) == RESET) &&
366 HAL_IS_BIT_CLR(hadc->Instance->CR1, ADC_CR1_JAUTO) )
368 /* Stop potential conversion on going, on regular and injected groups */
369 /* Disable ADC peripheral */
370 tmp_hal_status = ADC_ConversionStop_Disable(hadc);
372 /* Check if ADC is effectively disabled */
373 if (tmp_hal_status == HAL_OK)
375 /* Set ADC state */
376 ADC_STATE_CLR_SET(hadc->State,
377 HAL_ADC_STATE_REG_BUSY | HAL_ADC_STATE_INJ_BUSY,
378 HAL_ADC_STATE_READY);
381 else
383 /* Update ADC state machine to error */
384 SET_BIT(hadc->State, HAL_ADC_STATE_ERROR_CONFIG);
386 tmp_hal_status = HAL_ERROR;
389 /* Process unlocked */
390 __HAL_UNLOCK(hadc);
392 /* Return function status */
393 return tmp_hal_status;
397 * @brief Wait for injected group conversion to be completed.
398 * @param hadc: ADC handle
399 * @param Timeout: Timeout value in millisecond.
400 * @retval HAL status
402 HAL_StatusTypeDef HAL_ADCEx_InjectedPollForConversion(ADC_HandleTypeDef* hadc, uint32_t Timeout)
404 uint32_t tickstart;
406 /* Variables for polling in case of scan mode enabled and polling for each */
407 /* conversion. */
408 __IO uint32_t Conversion_Timeout_CPU_cycles = 0U;
409 uint32_t Conversion_Timeout_CPU_cycles_max = 0U;
411 /* Check the parameters */
412 assert_param(IS_ADC_ALL_INSTANCE(hadc->Instance));
414 /* Get timeout */
415 tickstart = HAL_GetTick();
417 /* Polling for end of conversion: differentiation if single/sequence */
418 /* conversion. */
419 /* For injected group, flag JEOC is set only at the end of the sequence, */
420 /* not for each conversion within the sequence. */
421 /* - If single conversion for injected group (scan mode disabled or */
422 /* InjectedNbrOfConversion ==1), flag JEOC is used to determine the */
423 /* conversion completion. */
424 /* - If sequence conversion for injected group (scan mode enabled and */
425 /* InjectedNbrOfConversion >=2), flag JEOC is set only at the end of the */
426 /* sequence. */
427 /* To poll for each conversion, the maximum conversion time is computed */
428 /* from ADC conversion time (selected sampling time + conversion time of */
429 /* 12.5 ADC clock cycles) and APB2/ADC clock prescalers (depending on */
430 /* settings, conversion time range can be from 28 to 32256 CPU cycles). */
431 /* As flag JEOC is not set after each conversion, no timeout status can */
432 /* be set. */
433 if ((hadc->Instance->JSQR & ADC_JSQR_JL) == RESET)
435 /* Wait until End of Conversion flag is raised */
436 while(HAL_IS_BIT_CLR(hadc->Instance->SR, ADC_FLAG_JEOC))
438 /* Check if timeout is disabled (set to infinite wait) */
439 if(Timeout != HAL_MAX_DELAY)
441 if((Timeout == 0U) || ((HAL_GetTick() - tickstart ) > Timeout))
443 /* Update ADC state machine to timeout */
444 SET_BIT(hadc->State, HAL_ADC_STATE_TIMEOUT);
446 /* Process unlocked */
447 __HAL_UNLOCK(hadc);
449 return HAL_TIMEOUT;
454 else
456 /* Replace polling by wait for maximum conversion time */
457 /* - Computation of CPU clock cycles corresponding to ADC clock cycles */
458 /* and ADC maximum conversion cycles on all channels. */
459 /* - Wait for the expected ADC clock cycles delay */
460 Conversion_Timeout_CPU_cycles_max = ((SystemCoreClock
461 / HAL_RCCEx_GetPeriphCLKFreq(RCC_PERIPHCLK_ADC))
462 * ADC_CONVCYCLES_MAX_RANGE(hadc) );
464 while(Conversion_Timeout_CPU_cycles < Conversion_Timeout_CPU_cycles_max)
466 /* Check if timeout is disabled (set to infinite wait) */
467 if(Timeout != HAL_MAX_DELAY)
469 if((Timeout == 0)||((HAL_GetTick() - tickstart ) > Timeout))
471 /* Update ADC state machine to timeout */
472 SET_BIT(hadc->State, HAL_ADC_STATE_TIMEOUT);
474 /* Process unlocked */
475 __HAL_UNLOCK(hadc);
477 return HAL_TIMEOUT;
480 Conversion_Timeout_CPU_cycles ++;
484 /* Clear injected group conversion flag */
485 /* Note: On STM32F1 ADC, clear regular conversion flag raised */
486 /* simultaneously. */
487 __HAL_ADC_CLEAR_FLAG(hadc, ADC_FLAG_JSTRT | ADC_FLAG_JEOC | ADC_FLAG_EOC);
489 /* Update ADC state machine */
490 SET_BIT(hadc->State, HAL_ADC_STATE_INJ_EOC);
492 /* Determine whether any further conversion upcoming on group injected */
493 /* by external trigger or by automatic injected conversion */
494 /* from group regular. */
495 if(ADC_IS_SOFTWARE_START_INJECTED(hadc) ||
496 (HAL_IS_BIT_CLR(hadc->Instance->CR1, ADC_CR1_JAUTO) &&
497 (ADC_IS_SOFTWARE_START_REGULAR(hadc) &&
498 (hadc->Init.ContinuousConvMode == DISABLE) ) ) )
500 /* Set ADC state */
501 CLEAR_BIT(hadc->State, HAL_ADC_STATE_INJ_BUSY);
503 if (HAL_IS_BIT_CLR(hadc->State, HAL_ADC_STATE_REG_BUSY))
505 SET_BIT(hadc->State, HAL_ADC_STATE_READY);
509 /* Return ADC state */
510 return HAL_OK;
514 * @brief Enables ADC, starts conversion of injected group with interruption.
515 * - JEOC (end of conversion of injected group)
516 * Each of these interruptions has its dedicated callback function.
517 * @param hadc: ADC handle
518 * @retval HAL status.
520 HAL_StatusTypeDef HAL_ADCEx_InjectedStart_IT(ADC_HandleTypeDef* hadc)
522 HAL_StatusTypeDef tmp_hal_status = HAL_OK;
524 /* Check the parameters */
525 assert_param(IS_ADC_ALL_INSTANCE(hadc->Instance));
527 /* Process locked */
528 __HAL_LOCK(hadc);
530 /* Enable the ADC peripheral */
531 tmp_hal_status = ADC_Enable(hadc);
533 /* Start conversion if ADC is effectively enabled */
534 if (tmp_hal_status == HAL_OK)
536 /* Set ADC state */
537 /* - Clear state bitfield related to injected group conversion results */
538 /* - Set state bitfield related to injected operation */
539 ADC_STATE_CLR_SET(hadc->State,
540 HAL_ADC_STATE_READY | HAL_ADC_STATE_INJ_EOC,
541 HAL_ADC_STATE_INJ_BUSY);
543 /* Case of independent mode or multimode (for devices with several ADCs): */
544 /* Set multimode state. */
545 if (ADC_NONMULTIMODE_OR_MULTIMODEMASTER(hadc))
547 CLEAR_BIT(hadc->State, HAL_ADC_STATE_MULTIMODE_SLAVE);
549 else
551 SET_BIT(hadc->State, HAL_ADC_STATE_MULTIMODE_SLAVE);
554 /* Check if a regular conversion is ongoing */
555 /* Note: On this device, there is no ADC error code fields related to */
556 /* conversions on group injected only. In case of conversion on */
557 /* going on group regular, no error code is reset. */
558 if (HAL_IS_BIT_CLR(hadc->State, HAL_ADC_STATE_REG_BUSY))
560 /* Reset ADC all error code fields */
561 ADC_CLEAR_ERRORCODE(hadc);
564 /* Process unlocked */
565 /* Unlock before starting ADC conversions: in case of potential */
566 /* interruption, to let the process to ADC IRQ Handler. */
567 __HAL_UNLOCK(hadc);
569 /* Clear injected group conversion flag */
570 /* (To ensure of no unknown state from potential previous ADC operations) */
571 __HAL_ADC_CLEAR_FLAG(hadc, ADC_FLAG_JEOC);
573 /* Enable end of conversion interrupt for injected channels */
574 __HAL_ADC_ENABLE_IT(hadc, ADC_IT_JEOC);
576 /* Start conversion of injected group if software start has been selected */
577 /* and if automatic injected conversion is disabled. */
578 /* If external trigger has been selected, conversion will start at next */
579 /* trigger event. */
580 /* If automatic injected conversion is enabled, conversion will start */
581 /* after next regular group conversion. */
582 if (HAL_IS_BIT_CLR(hadc->Instance->CR1, ADC_CR1_JAUTO))
584 if (ADC_IS_SOFTWARE_START_INJECTED(hadc) &&
585 ADC_NONMULTIMODE_OR_MULTIMODEMASTER(hadc) )
587 /* Start ADC conversion on injected group with SW start */
588 SET_BIT(hadc->Instance->CR2, (ADC_CR2_JSWSTART | ADC_CR2_JEXTTRIG));
590 else
592 /* Start ADC conversion on injected group with external trigger */
593 SET_BIT(hadc->Instance->CR2, ADC_CR2_JEXTTRIG);
597 else
599 /* Process unlocked */
600 __HAL_UNLOCK(hadc);
603 /* Return function status */
604 return tmp_hal_status;
608 * @brief Stop conversion of injected channels, disable interruption of
609 * end-of-conversion. Disable ADC peripheral if no regular conversion
610 * is on going.
611 * @note If ADC must be disabled and if conversion is on going on
612 * regular group, function HAL_ADC_Stop must be used to stop both
613 * injected and regular groups, and disable the ADC.
614 * @note If injected group mode auto-injection is enabled,
615 * function HAL_ADC_Stop must be used.
616 * @param hadc: ADC handle
617 * @retval None
619 HAL_StatusTypeDef HAL_ADCEx_InjectedStop_IT(ADC_HandleTypeDef* hadc)
621 HAL_StatusTypeDef tmp_hal_status = HAL_OK;
623 /* Check the parameters */
624 assert_param(IS_ADC_ALL_INSTANCE(hadc->Instance));
626 /* Process locked */
627 __HAL_LOCK(hadc);
629 /* Stop potential conversion and disable ADC peripheral */
630 /* Conditioned to: */
631 /* - No conversion on the other group (regular group) is intended to */
632 /* continue (injected and regular groups stop conversion and ADC disable */
633 /* are common) */
634 /* - In case of auto-injection mode, HAL_ADC_Stop must be used. */
635 if(((hadc->State & HAL_ADC_STATE_REG_BUSY) == RESET) &&
636 HAL_IS_BIT_CLR(hadc->Instance->CR1, ADC_CR1_JAUTO) )
638 /* Stop potential conversion on going, on regular and injected groups */
639 /* Disable ADC peripheral */
640 tmp_hal_status = ADC_ConversionStop_Disable(hadc);
642 /* Check if ADC is effectively disabled */
643 if (tmp_hal_status == HAL_OK)
645 /* Disable ADC end of conversion interrupt for injected channels */
646 __HAL_ADC_DISABLE_IT(hadc, ADC_IT_JEOC);
648 /* Set ADC state */
649 ADC_STATE_CLR_SET(hadc->State,
650 HAL_ADC_STATE_REG_BUSY | HAL_ADC_STATE_INJ_BUSY,
651 HAL_ADC_STATE_READY);
654 else
656 /* Update ADC state machine to error */
657 SET_BIT(hadc->State, HAL_ADC_STATE_ERROR_CONFIG);
659 tmp_hal_status = HAL_ERROR;
662 /* Process unlocked */
663 __HAL_UNLOCK(hadc);
665 /* Return function status */
666 return tmp_hal_status;
669 #if defined (STM32F103x6) || defined (STM32F103xB) || defined (STM32F105xC) || defined (STM32F107xC) || defined (STM32F103xE) || defined (STM32F103xG)
671 * @brief Enables ADC, starts conversion of regular group and transfers result
672 * through DMA.
673 * Multimode must have been previously configured using
674 * HAL_ADCEx_MultiModeConfigChannel() function.
675 * Interruptions enabled in this function:
676 * - DMA transfer complete
677 * - DMA half transfer
678 * Each of these interruptions has its dedicated callback function.
679 * @note: On STM32F1 devices, ADC slave regular group must be configured
680 * with conversion trigger ADC_SOFTWARE_START.
681 * @note: ADC slave can be enabled preliminarily using single-mode
682 * HAL_ADC_Start() function.
683 * @param hadc: ADC handle of ADC master (handle of ADC slave must not be used)
684 * @param pData: The destination Buffer address.
685 * @param Length: The length of data to be transferred from ADC peripheral to memory.
686 * @retval None
688 HAL_StatusTypeDef HAL_ADCEx_MultiModeStart_DMA(ADC_HandleTypeDef* hadc, uint32_t* pData, uint32_t Length)
690 HAL_StatusTypeDef tmp_hal_status = HAL_OK;
691 ADC_HandleTypeDef tmphadcSlave;
693 /* Check the parameters */
694 assert_param(IS_ADC_MULTIMODE_MASTER_INSTANCE(hadc->Instance));
695 assert_param(IS_FUNCTIONAL_STATE(hadc->Init.ContinuousConvMode));
697 /* Process locked */
698 __HAL_LOCK(hadc);
700 /* Set a temporary handle of the ADC slave associated to the ADC master */
701 ADC_MULTI_SLAVE(hadc, &tmphadcSlave);
703 /* On STM32F1 devices, ADC slave regular group must be configured with */
704 /* conversion trigger ADC_SOFTWARE_START. */
705 /* Note: External trigger of ADC slave must be enabled, it is already done */
706 /* into function "HAL_ADC_Init()". */
707 if(!ADC_IS_SOFTWARE_START_REGULAR(&tmphadcSlave))
709 /* Update ADC state machine to error */
710 SET_BIT(hadc->State, HAL_ADC_STATE_ERROR_CONFIG);
712 /* Process unlocked */
713 __HAL_UNLOCK(hadc);
715 return HAL_ERROR;
718 /* Enable the ADC peripherals: master and slave (in case if not already */
719 /* enabled previously) */
720 tmp_hal_status = ADC_Enable(hadc);
721 if (tmp_hal_status == HAL_OK)
723 tmp_hal_status = ADC_Enable(&tmphadcSlave);
726 /* Start conversion if all ADCs of multimode are effectively enabled */
727 if (tmp_hal_status == HAL_OK)
729 /* Set ADC state (ADC master) */
730 /* - Clear state bitfield related to regular group conversion results */
731 /* - Set state bitfield related to regular operation */
732 ADC_STATE_CLR_SET(hadc->State,
733 HAL_ADC_STATE_READY | HAL_ADC_STATE_REG_EOC | HAL_ADC_STATE_MULTIMODE_SLAVE,
734 HAL_ADC_STATE_REG_BUSY);
736 /* If conversions on group regular are also triggering group injected, */
737 /* update ADC state. */
738 if (READ_BIT(hadc->Instance->CR1, ADC_CR1_JAUTO) != RESET)
740 ADC_STATE_CLR_SET(hadc->State, HAL_ADC_STATE_INJ_EOC, HAL_ADC_STATE_INJ_BUSY);
743 /* Process unlocked */
744 /* Unlock before starting ADC conversions: in case of potential */
745 /* interruption, to let the process to ADC IRQ Handler. */
746 __HAL_UNLOCK(hadc);
748 /* Set ADC error code to none */
749 ADC_CLEAR_ERRORCODE(hadc);
752 /* Set the DMA transfer complete callback */
753 hadc->DMA_Handle->XferCpltCallback = ADC_DMAConvCplt;
755 /* Set the DMA half transfer complete callback */
756 hadc->DMA_Handle->XferHalfCpltCallback = ADC_DMAHalfConvCplt;
758 /* Set the DMA error callback */
759 hadc->DMA_Handle->XferErrorCallback = ADC_DMAError;
762 /* Manage ADC and DMA start: ADC overrun interruption, DMA start, ADC */
763 /* start (in case of SW start): */
765 /* Clear regular group conversion flag and overrun flag */
766 /* (To ensure of no unknown state from potential previous ADC operations) */
767 __HAL_ADC_CLEAR_FLAG(hadc, ADC_FLAG_EOC);
769 /* Enable ADC DMA mode of ADC master */
770 SET_BIT(hadc->Instance->CR2, ADC_CR2_DMA);
772 /* Start the DMA channel */
773 HAL_DMA_Start_IT(hadc->DMA_Handle, (uint32_t)&hadc->Instance->DR, (uint32_t)pData, Length);
775 /* Start conversion of regular group if software start has been selected. */
776 /* If external trigger has been selected, conversion will start at next */
777 /* trigger event. */
778 /* Note: Alternate trigger for single conversion could be to force an */
779 /* additional set of bit ADON "hadc->Instance->CR2 |= ADC_CR2_ADON;"*/
780 if (ADC_IS_SOFTWARE_START_REGULAR(hadc))
782 /* Start ADC conversion on regular group with SW start */
783 SET_BIT(hadc->Instance->CR2, (ADC_CR2_SWSTART | ADC_CR2_EXTTRIG));
785 else
787 /* Start ADC conversion on regular group with external trigger */
788 SET_BIT(hadc->Instance->CR2, ADC_CR2_EXTTRIG);
791 else
793 /* Process unlocked */
794 __HAL_UNLOCK(hadc);
797 /* Return function status */
798 return tmp_hal_status;
802 * @brief Stop ADC conversion of regular group (and injected channels in
803 * case of auto_injection mode), disable ADC DMA transfer, disable
804 * ADC peripheral.
805 * @note Multimode is kept enabled after this function. To disable multimode
806 * (set with HAL_ADCEx_MultiModeConfigChannel(), ADC must be
807 * reinitialized using HAL_ADC_Init() or HAL_ADC_ReInit().
808 * @note In case of DMA configured in circular mode, function
809 * HAL_ADC_Stop_DMA must be called after this function with handle of
810 * ADC slave, to properly disable the DMA channel.
811 * @param hadc: ADC handle of ADC master (handle of ADC slave must not be used)
812 * @retval None
814 HAL_StatusTypeDef HAL_ADCEx_MultiModeStop_DMA(ADC_HandleTypeDef* hadc)
816 HAL_StatusTypeDef tmp_hal_status = HAL_OK;
817 ADC_HandleTypeDef tmphadcSlave;
819 /* Check the parameters */
820 assert_param(IS_ADC_MULTIMODE_MASTER_INSTANCE(hadc->Instance));
822 /* Process locked */
823 __HAL_LOCK(hadc);
826 /* Stop potential conversion on going, on regular and injected groups */
827 /* Disable ADC master peripheral */
828 tmp_hal_status = ADC_ConversionStop_Disable(hadc);
830 /* Check if ADC is effectively disabled */
831 if(tmp_hal_status == HAL_OK)
833 /* Set a temporary handle of the ADC slave associated to the ADC master */
834 ADC_MULTI_SLAVE(hadc, &tmphadcSlave);
836 /* Disable ADC slave peripheral */
837 tmp_hal_status = ADC_ConversionStop_Disable(&tmphadcSlave);
839 /* Check if ADC is effectively disabled */
840 if(tmp_hal_status != HAL_OK)
842 /* Update ADC state machine to error */
843 SET_BIT(hadc->State, HAL_ADC_STATE_ERROR_INTERNAL);
845 /* Process unlocked */
846 __HAL_UNLOCK(hadc);
848 return HAL_ERROR;
851 /* Disable ADC DMA mode */
852 CLEAR_BIT(hadc->Instance->CR2, ADC_CR2_DMA);
854 /* Reset configuration of ADC DMA continuous request for dual mode */
855 CLEAR_BIT(hadc->Instance->CR1, ADC_CR1_DUALMOD);
857 /* Disable the DMA channel (in case of DMA in circular mode or stop while */
858 /* while DMA transfer is on going) */
859 tmp_hal_status = HAL_DMA_Abort(hadc->DMA_Handle);
861 /* Change ADC state (ADC master) */
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 */
868 __HAL_UNLOCK(hadc);
870 /* Return function status */
871 return tmp_hal_status;
873 #endif /* defined STM32F103x6 || defined STM32F103xB || defined STM32F105xC || defined STM32F107xC || defined STM32F103xE || defined STM32F103xG */
876 * @brief Get ADC injected group conversion result.
877 * @note Reading register JDRx automatically clears ADC flag JEOC
878 * (ADC group injected end of unitary conversion).
879 * @note This function does not clear ADC flag JEOS
880 * (ADC group injected end of sequence conversion)
881 * Occurrence of flag JEOS rising:
882 * - If sequencer is composed of 1 rank, flag JEOS is equivalent
883 * to flag JEOC.
884 * - If sequencer is composed of several ranks, during the scan
885 * sequence flag JEOC only is raised, at the end of the scan sequence
886 * both flags JEOC and EOS are raised.
887 * Flag JEOS must not be cleared by this function because
888 * it would not be compliant with low power features
889 * (feature low power auto-wait, not available on all STM32 families).
890 * To clear this flag, either use function:
891 * in programming model IT: @ref HAL_ADC_IRQHandler(), in programming
892 * model polling: @ref HAL_ADCEx_InjectedPollForConversion()
893 * or @ref __HAL_ADC_CLEAR_FLAG(&hadc, ADC_FLAG_JEOS).
894 * @param hadc: ADC handle
895 * @param InjectedRank: the converted ADC injected rank.
896 * This parameter can be one of the following values:
897 * @arg ADC_INJECTED_RANK_1: Injected Channel1 selected
898 * @arg ADC_INJECTED_RANK_2: Injected Channel2 selected
899 * @arg ADC_INJECTED_RANK_3: Injected Channel3 selected
900 * @arg ADC_INJECTED_RANK_4: Injected Channel4 selected
901 * @retval ADC group injected conversion data
903 uint32_t HAL_ADCEx_InjectedGetValue(ADC_HandleTypeDef* hadc, uint32_t InjectedRank)
905 uint32_t tmp_jdr = 0U;
907 /* Check the parameters */
908 assert_param(IS_ADC_ALL_INSTANCE(hadc->Instance));
909 assert_param(IS_ADC_INJECTED_RANK(InjectedRank));
911 /* Get ADC converted value */
912 switch(InjectedRank)
914 case ADC_INJECTED_RANK_4:
915 tmp_jdr = hadc->Instance->JDR4;
916 break;
917 case ADC_INJECTED_RANK_3:
918 tmp_jdr = hadc->Instance->JDR3;
919 break;
920 case ADC_INJECTED_RANK_2:
921 tmp_jdr = hadc->Instance->JDR2;
922 break;
923 case ADC_INJECTED_RANK_1:
924 default:
925 tmp_jdr = hadc->Instance->JDR1;
926 break;
929 /* Return ADC converted value */
930 return tmp_jdr;
933 #if defined (STM32F103x6) || defined (STM32F103xB) || defined (STM32F105xC) || defined (STM32F107xC) || defined (STM32F103xE) || defined (STM32F103xG)
935 * @brief Returns the last ADC Master&Slave regular conversions results data
936 * in the selected multi mode.
937 * @param hadc: ADC handle of ADC master (handle of ADC slave must not be used)
938 * @retval The converted data value.
940 uint32_t HAL_ADCEx_MultiModeGetValue(ADC_HandleTypeDef* hadc)
942 uint32_t tmpDR = 0U;
944 /* Check the parameters */
945 assert_param(IS_ADC_MULTIMODE_MASTER_INSTANCE(hadc->Instance));
947 /* Check the parameters */
948 assert_param(IS_ADC_ALL_INSTANCE(hadc->Instance));
950 /* Note: EOC flag is not cleared here by software because automatically */
951 /* cleared by hardware when reading register DR. */
953 /* On STM32F1 devices, ADC1 data register DR contains ADC2 conversions */
954 /* only if ADC1 DMA mode is enabled. */
955 tmpDR = hadc->Instance->DR;
957 if (HAL_IS_BIT_CLR(ADC1->CR2, ADC_CR2_DMA))
959 tmpDR |= (ADC2->DR << 16U);
962 /* Return ADC converted value */
963 return tmpDR;
965 #endif /* defined STM32F103x6 || defined STM32F103xB || defined STM32F105xC || defined STM32F107xC || defined STM32F103xE || defined STM32F103xG */
968 * @brief Injected conversion complete callback in non blocking mode
969 * @param hadc: ADC handle
970 * @retval None
972 __weak void HAL_ADCEx_InjectedConvCpltCallback(ADC_HandleTypeDef* hadc)
974 /* Prevent unused argument(s) compilation warning */
975 UNUSED(hadc);
976 /* NOTE : This function Should not be modified, when the callback is needed,
977 the HAL_ADCEx_InjectedConvCpltCallback could be implemented in the user file
982 * @}
985 /** @defgroup ADCEx_Exported_Functions_Group2 Extended Peripheral Control functions
986 * @brief Extended Peripheral Control functions
988 @verbatim
989 ===============================================================================
990 ##### Peripheral Control functions #####
991 ===============================================================================
992 [..] This section provides functions allowing to:
993 (+) Configure channels on injected group
994 (+) Configure multimode
996 @endverbatim
997 * @{
1001 * @brief Configures the ADC injected group and the selected channel to be
1002 * linked to the injected group.
1003 * @note Possibility to update parameters on the fly:
1004 * This function initializes injected group, following calls to this
1005 * function can be used to reconfigure some parameters of structure
1006 * "ADC_InjectionConfTypeDef" on the fly, without reseting the ADC.
1007 * The setting of these parameters is conditioned to ADC state:
1008 * this function must be called when ADC is not under conversion.
1009 * @param hadc: ADC handle
1010 * @param sConfigInjected: Structure of ADC injected group and ADC channel for
1011 * injected group.
1012 * @retval None
1014 HAL_StatusTypeDef HAL_ADCEx_InjectedConfigChannel(ADC_HandleTypeDef* hadc, ADC_InjectionConfTypeDef* sConfigInjected)
1016 HAL_StatusTypeDef tmp_hal_status = HAL_OK;
1017 __IO uint32_t wait_loop_index = 0U;
1019 /* Check the parameters */
1020 assert_param(IS_ADC_ALL_INSTANCE(hadc->Instance));
1021 assert_param(IS_ADC_CHANNEL(sConfigInjected->InjectedChannel));
1022 assert_param(IS_ADC_SAMPLE_TIME(sConfigInjected->InjectedSamplingTime));
1023 assert_param(IS_FUNCTIONAL_STATE(sConfigInjected->AutoInjectedConv));
1024 assert_param(IS_ADC_EXTTRIGINJEC(sConfigInjected->ExternalTrigInjecConv));
1025 assert_param(IS_ADC_RANGE(sConfigInjected->InjectedOffset));
1027 if(hadc->Init.ScanConvMode != ADC_SCAN_DISABLE)
1029 assert_param(IS_ADC_INJECTED_RANK(sConfigInjected->InjectedRank));
1030 assert_param(IS_ADC_INJECTED_NB_CONV(sConfigInjected->InjectedNbrOfConversion));
1031 assert_param(IS_FUNCTIONAL_STATE(sConfigInjected->InjectedDiscontinuousConvMode));
1034 /* Process locked */
1035 __HAL_LOCK(hadc);
1037 /* Configuration of injected group sequencer: */
1038 /* - if scan mode is disabled, injected channels sequence length is set to */
1039 /* 0x00: 1 channel converted (channel on regular rank 1) */
1040 /* Parameter "InjectedNbrOfConversion" is discarded. */
1041 /* Note: Scan mode is present by hardware on this device and, if */
1042 /* disabled, discards automatically nb of conversions. Anyway, nb of */
1043 /* conversions is forced to 0x00 for alignment over all STM32 devices. */
1044 /* - if scan mode is enabled, injected channels sequence length is set to */
1045 /* parameter "InjectedNbrOfConversion". */
1046 if (hadc->Init.ScanConvMode == ADC_SCAN_DISABLE)
1048 if (sConfigInjected->InjectedRank == ADC_INJECTED_RANK_1)
1050 /* Clear the old SQx bits for all injected ranks */
1051 MODIFY_REG(hadc->Instance->JSQR ,
1052 ADC_JSQR_JL |
1053 ADC_JSQR_JSQ4 |
1054 ADC_JSQR_JSQ3 |
1055 ADC_JSQR_JSQ2 |
1056 ADC_JSQR_JSQ1 ,
1057 ADC_JSQR_RK_JL(sConfigInjected->InjectedChannel,
1058 ADC_INJECTED_RANK_1,
1059 0x01U));
1061 /* If another injected rank than rank1 was intended to be set, and could */
1062 /* not due to ScanConvMode disabled, error is reported. */
1063 else
1065 /* Update ADC state machine to error */
1066 SET_BIT(hadc->State, HAL_ADC_STATE_ERROR_CONFIG);
1068 tmp_hal_status = HAL_ERROR;
1071 else
1073 /* Since injected channels rank conv. order depends on total number of */
1074 /* injected conversions, selected rank must be below or equal to total */
1075 /* number of injected conversions to be updated. */
1076 if (sConfigInjected->InjectedRank <= sConfigInjected->InjectedNbrOfConversion)
1078 /* Clear the old SQx bits for the selected rank */
1079 /* Set the SQx bits for the selected rank */
1080 MODIFY_REG(hadc->Instance->JSQR ,
1082 ADC_JSQR_JL |
1083 ADC_JSQR_RK_JL(ADC_JSQR_JSQ1,
1084 sConfigInjected->InjectedRank,
1085 sConfigInjected->InjectedNbrOfConversion) ,
1087 ADC_JSQR_JL_SHIFT(sConfigInjected->InjectedNbrOfConversion) |
1088 ADC_JSQR_RK_JL(sConfigInjected->InjectedChannel,
1089 sConfigInjected->InjectedRank,
1090 sConfigInjected->InjectedNbrOfConversion) );
1092 else
1094 /* Clear the old SQx bits for the selected rank */
1095 MODIFY_REG(hadc->Instance->JSQR ,
1097 ADC_JSQR_JL |
1098 ADC_JSQR_RK_JL(ADC_JSQR_JSQ1,
1099 sConfigInjected->InjectedRank,
1100 sConfigInjected->InjectedNbrOfConversion) ,
1102 0x00000000U);
1106 /* Configuration of injected group */
1107 /* Parameters update conditioned to ADC state: */
1108 /* Parameters that can be updated only when ADC is disabled: */
1109 /* - external trigger to start conversion */
1110 /* Parameters update not conditioned to ADC state: */
1111 /* - Automatic injected conversion */
1112 /* - Injected discontinuous mode */
1113 /* Note: In case of ADC already enabled, caution to not launch an unwanted */
1114 /* conversion while modifying register CR2 by writing 1 to bit ADON. */
1115 if (ADC_IS_ENABLE(hadc) == RESET)
1117 MODIFY_REG(hadc->Instance->CR2 ,
1118 ADC_CR2_JEXTSEL |
1119 ADC_CR2_ADON ,
1120 ADC_CFGR_JEXTSEL(hadc, sConfigInjected->ExternalTrigInjecConv) );
1124 /* Configuration of injected group */
1125 /* - Automatic injected conversion */
1126 /* - Injected discontinuous mode */
1128 /* Automatic injected conversion can be enabled if injected group */
1129 /* external triggers are disabled. */
1130 if (sConfigInjected->AutoInjectedConv == ENABLE)
1132 if (sConfigInjected->ExternalTrigInjecConv == ADC_INJECTED_SOFTWARE_START)
1134 SET_BIT(hadc->Instance->CR1, ADC_CR1_JAUTO);
1136 else
1138 /* Update ADC state machine to error */
1139 SET_BIT(hadc->State, HAL_ADC_STATE_ERROR_CONFIG);
1141 tmp_hal_status = HAL_ERROR;
1145 /* Injected discontinuous can be enabled only if auto-injected mode is */
1146 /* disabled. */
1147 if (sConfigInjected->InjectedDiscontinuousConvMode == ENABLE)
1149 if (sConfigInjected->AutoInjectedConv == DISABLE)
1151 SET_BIT(hadc->Instance->CR1, ADC_CR1_JDISCEN);
1153 else
1155 /* Update ADC state machine to error */
1156 SET_BIT(hadc->State, HAL_ADC_STATE_ERROR_CONFIG);
1158 tmp_hal_status = HAL_ERROR;
1163 /* InjectedChannel sampling time configuration */
1164 /* For channels 10 to 17 */
1165 if (sConfigInjected->InjectedChannel >= ADC_CHANNEL_10)
1167 MODIFY_REG(hadc->Instance->SMPR1 ,
1168 ADC_SMPR1(ADC_SMPR1_SMP10, sConfigInjected->InjectedChannel) ,
1169 ADC_SMPR1(sConfigInjected->InjectedSamplingTime, sConfigInjected->InjectedChannel) );
1171 else /* For channels 0 to 9 */
1173 MODIFY_REG(hadc->Instance->SMPR2 ,
1174 ADC_SMPR2(ADC_SMPR2_SMP0, sConfigInjected->InjectedChannel) ,
1175 ADC_SMPR2(sConfigInjected->InjectedSamplingTime, sConfigInjected->InjectedChannel) );
1178 /* If ADC1 InjectedChannel_16 or InjectedChannel_17 is selected, enable Temperature sensor */
1179 /* and VREFINT measurement path. */
1180 if ((sConfigInjected->InjectedChannel == ADC_CHANNEL_TEMPSENSOR) ||
1181 (sConfigInjected->InjectedChannel == ADC_CHANNEL_VREFINT) )
1183 SET_BIT(hadc->Instance->CR2, ADC_CR2_TSVREFE);
1187 /* Configure the offset: offset enable/disable, InjectedChannel, offset value */
1188 switch(sConfigInjected->InjectedRank)
1190 case 1:
1191 /* Set injected channel 1 offset */
1192 MODIFY_REG(hadc->Instance->JOFR1,
1193 ADC_JOFR1_JOFFSET1,
1194 sConfigInjected->InjectedOffset);
1195 break;
1196 case 2:
1197 /* Set injected channel 2 offset */
1198 MODIFY_REG(hadc->Instance->JOFR2,
1199 ADC_JOFR2_JOFFSET2,
1200 sConfigInjected->InjectedOffset);
1201 break;
1202 case 3:
1203 /* Set injected channel 3 offset */
1204 MODIFY_REG(hadc->Instance->JOFR3,
1205 ADC_JOFR3_JOFFSET3,
1206 sConfigInjected->InjectedOffset);
1207 break;
1208 case 4:
1209 default:
1210 MODIFY_REG(hadc->Instance->JOFR4,
1211 ADC_JOFR4_JOFFSET4,
1212 sConfigInjected->InjectedOffset);
1213 break;
1216 /* If ADC1 Channel_16 or Channel_17 is selected, enable Temperature sensor */
1217 /* and VREFINT measurement path. */
1218 if ((sConfigInjected->InjectedChannel == ADC_CHANNEL_TEMPSENSOR) ||
1219 (sConfigInjected->InjectedChannel == ADC_CHANNEL_VREFINT) )
1221 /* For STM32F1 devices with several ADC: Only ADC1 can access internal */
1222 /* measurement channels (VrefInt/TempSensor). If these channels are */
1223 /* intended to be set on other ADC instances, an error is reported. */
1224 if (hadc->Instance == ADC1)
1226 if (READ_BIT(hadc->Instance->CR2, ADC_CR2_TSVREFE) == RESET)
1228 SET_BIT(hadc->Instance->CR2, ADC_CR2_TSVREFE);
1230 if ((sConfigInjected->InjectedChannel == ADC_CHANNEL_TEMPSENSOR))
1232 /* Delay for temperature sensor stabilization time */
1233 /* Compute number of CPU cycles to wait for */
1234 wait_loop_index = (ADC_TEMPSENSOR_DELAY_US * (SystemCoreClock / 1000000U));
1235 while(wait_loop_index != 0U)
1237 wait_loop_index--;
1242 else
1244 /* Update ADC state machine to error */
1245 SET_BIT(hadc->State, HAL_ADC_STATE_ERROR_CONFIG);
1247 tmp_hal_status = HAL_ERROR;
1251 /* Process unlocked */
1252 __HAL_UNLOCK(hadc);
1254 /* Return function status */
1255 return tmp_hal_status;
1258 #if defined (STM32F103x6) || defined (STM32F103xB) || defined (STM32F105xC) || defined (STM32F107xC) || defined (STM32F103xE) || defined (STM32F103xG)
1260 * @brief Enable ADC multimode and configure multimode parameters
1261 * @note Possibility to update parameters on the fly:
1262 * This function initializes multimode parameters, following
1263 * calls to this function can be used to reconfigure some parameters
1264 * of structure "ADC_MultiModeTypeDef" on the fly, without reseting
1265 * the ADCs (both ADCs of the common group).
1266 * The setting of these parameters is conditioned to ADC state.
1267 * For parameters constraints, see comments of structure
1268 * "ADC_MultiModeTypeDef".
1269 * @note To change back configuration from multimode to single mode, ADC must
1270 * be reset (using function HAL_ADC_Init() ).
1271 * @param hadc: ADC handle
1272 * @param multimode: Structure of ADC multimode configuration
1273 * @retval HAL status
1275 HAL_StatusTypeDef HAL_ADCEx_MultiModeConfigChannel(ADC_HandleTypeDef* hadc, ADC_MultiModeTypeDef* multimode)
1277 HAL_StatusTypeDef tmp_hal_status = HAL_OK;
1278 ADC_HandleTypeDef tmphadcSlave;
1280 /* Check the parameters */
1281 assert_param(IS_ADC_MULTIMODE_MASTER_INSTANCE(hadc->Instance));
1282 assert_param(IS_ADC_MODE(multimode->Mode));
1284 /* Process locked */
1285 __HAL_LOCK(hadc);
1287 /* Set a temporary handle of the ADC slave associated to the ADC master */
1288 ADC_MULTI_SLAVE(hadc, &tmphadcSlave);
1290 /* Parameters update conditioned to ADC state: */
1291 /* Parameters that can be updated when ADC is disabled or enabled without */
1292 /* conversion on going on regular group: */
1293 /* - ADC master and ADC slave DMA configuration */
1294 /* Parameters that can be updated only when ADC is disabled: */
1295 /* - Multimode mode selection */
1296 /* To optimize code, all multimode settings can be set when both ADCs of */
1297 /* the common group are in state: disabled. */
1298 if ((ADC_IS_ENABLE(hadc) == RESET) &&
1299 (ADC_IS_ENABLE(&tmphadcSlave) == RESET) &&
1300 (IS_ADC_MULTIMODE_MASTER_INSTANCE(hadc->Instance)) )
1302 MODIFY_REG(hadc->Instance->CR1,
1303 ADC_CR1_DUALMOD ,
1304 multimode->Mode );
1306 /* If one of the ADC sharing the same common group is enabled, no update */
1307 /* could be done on neither of the multimode structure parameters. */
1308 else
1310 /* Update ADC state machine to error */
1311 SET_BIT(hadc->State, HAL_ADC_STATE_ERROR_CONFIG);
1313 tmp_hal_status = HAL_ERROR;
1317 /* Process unlocked */
1318 __HAL_UNLOCK(hadc);
1320 /* Return function status */
1321 return tmp_hal_status;
1323 #endif /* defined STM32F103x6 || defined STM32F103xB || defined STM32F105xC || defined STM32F107xC || defined STM32F103xE || defined STM32F103xG */
1325 * @}
1329 * @}
1332 #endif /* HAL_ADC_MODULE_ENABLED */
1334 * @}
1338 * @}
1341 /************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/