2 ******************************************************************************
3 * @file stm32f1xx_ll_adc.h
4 * @author MCD Application Team
7 * @brief Header file of ADC LL module.
8 ******************************************************************************
11 * <h2><center>© COPYRIGHT(c) 2017 STMicroelectronics</center></h2>
13 * Redistribution and use in source and binary forms, with or without modification,
14 * are permitted provided that the following conditions are met:
15 * 1. Redistributions of source code must retain the above copyright notice,
16 * this list of conditions and the following disclaimer.
17 * 2. Redistributions in binary form must reproduce the above copyright notice,
18 * this list of conditions and the following disclaimer in the documentation
19 * and/or other materials provided with the distribution.
20 * 3. Neither the name of STMicroelectronics nor the names of its contributors
21 * may be used to endorse or promote products derived from this software
22 * without specific prior written permission.
24 * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
25 * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
26 * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE
27 * DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE
28 * FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL
29 * DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR
30 * SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
31 * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY,
32 * OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE
33 * OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
35 ******************************************************************************
38 /* Define to prevent recursive inclusion -------------------------------------*/
39 #ifndef __STM32F1xx_LL_ADC_H
40 #define __STM32F1xx_LL_ADC_H
46 /* Includes ------------------------------------------------------------------*/
47 #include "stm32f1xx.h"
49 /** @addtogroup STM32F1xx_LL_Driver
53 #if defined (ADC1) || defined (ADC2) || defined (ADC3)
55 /** @defgroup ADC_LL ADC
59 /* Private types -------------------------------------------------------------*/
60 /* Private variables ---------------------------------------------------------*/
62 /* Private constants ---------------------------------------------------------*/
63 /** @defgroup ADC_LL_Private_Constants ADC Private Constants
67 /* Internal mask for ADC group regular sequencer: */
68 /* To select into literal LL_ADC_REG_RANK_x the relevant bits for: */
69 /* - sequencer register offset */
70 /* - sequencer rank bits position into the selected register */
72 /* Internal register offset for ADC group regular sequencer configuration */
73 /* (offset placed into a spare area of literal definition) */
74 #define ADC_SQR1_REGOFFSET 0x00000000U
75 #define ADC_SQR2_REGOFFSET 0x00000100U
76 #define ADC_SQR3_REGOFFSET 0x00000200U
77 #define ADC_SQR4_REGOFFSET 0x00000300U
79 #define ADC_REG_SQRX_REGOFFSET_MASK (ADC_SQR1_REGOFFSET | ADC_SQR2_REGOFFSET | ADC_SQR3_REGOFFSET | ADC_SQR4_REGOFFSET)
80 #define ADC_REG_RANK_ID_SQRX_MASK (ADC_CHANNEL_ID_NUMBER_MASK_POSBIT0)
82 /* Definition of ADC group regular sequencer bits information to be inserted */
83 /* into ADC group regular sequencer ranks literals definition. */
84 #define ADC_REG_RANK_1_SQRX_BITOFFSET_POS ( 0U) /* Value equivalent to POSITION_VAL(ADC_SQR3_SQ1) */
85 #define ADC_REG_RANK_2_SQRX_BITOFFSET_POS ( 5U) /* Value equivalent to POSITION_VAL(ADC_SQR3_SQ2) */
86 #define ADC_REG_RANK_3_SQRX_BITOFFSET_POS (10U) /* Value equivalent to POSITION_VAL(ADC_SQR3_SQ3) */
87 #define ADC_REG_RANK_4_SQRX_BITOFFSET_POS (15U) /* Value equivalent to POSITION_VAL(ADC_SQR3_SQ4) */
88 #define ADC_REG_RANK_5_SQRX_BITOFFSET_POS (20U) /* Value equivalent to POSITION_VAL(ADC_SQR3_SQ5) */
89 #define ADC_REG_RANK_6_SQRX_BITOFFSET_POS (25U) /* Value equivalent to POSITION_VAL(ADC_SQR3_SQ6) */
90 #define ADC_REG_RANK_7_SQRX_BITOFFSET_POS ( 0U) /* Value equivalent to POSITION_VAL(ADC_SQR2_SQ7) */
91 #define ADC_REG_RANK_8_SQRX_BITOFFSET_POS ( 5U) /* Value equivalent to POSITION_VAL(ADC_SQR2_SQ8) */
92 #define ADC_REG_RANK_9_SQRX_BITOFFSET_POS (10U) /* Value equivalent to POSITION_VAL(ADC_SQR2_SQ9) */
93 #define ADC_REG_RANK_10_SQRX_BITOFFSET_POS (15U) /* Value equivalent to POSITION_VAL(ADC_SQR2_SQ10) */
94 #define ADC_REG_RANK_11_SQRX_BITOFFSET_POS (20U) /* Value equivalent to POSITION_VAL(ADC_SQR2_SQ11) */
95 #define ADC_REG_RANK_12_SQRX_BITOFFSET_POS (25U) /* Value equivalent to POSITION_VAL(ADC_SQR2_SQ12) */
96 #define ADC_REG_RANK_13_SQRX_BITOFFSET_POS ( 0U) /* Value equivalent to POSITION_VAL(ADC_SQR1_SQ13) */
97 #define ADC_REG_RANK_14_SQRX_BITOFFSET_POS ( 5U) /* Value equivalent to POSITION_VAL(ADC_SQR1_SQ14) */
98 #define ADC_REG_RANK_15_SQRX_BITOFFSET_POS (10U) /* Value equivalent to POSITION_VAL(ADC_SQR1_SQ15) */
99 #define ADC_REG_RANK_16_SQRX_BITOFFSET_POS (15U) /* Value equivalent to POSITION_VAL(ADC_SQR1_SQ16) */
101 /* Internal mask for ADC group injected sequencer: */
102 /* To select into literal LL_ADC_INJ_RANK_x the relevant bits for: */
103 /* - data register offset */
104 /* - offset register offset */
105 /* - sequencer rank bits position into the selected register */
107 /* Internal register offset for ADC group injected data register */
108 /* (offset placed into a spare area of literal definition) */
109 #define ADC_JDR1_REGOFFSET 0x00000000U
110 #define ADC_JDR2_REGOFFSET 0x00000100U
111 #define ADC_JDR3_REGOFFSET 0x00000200U
112 #define ADC_JDR4_REGOFFSET 0x00000300U
114 /* Internal register offset for ADC group injected offset configuration */
115 /* (offset placed into a spare area of literal definition) */
116 #define ADC_JOFR1_REGOFFSET 0x00000000U
117 #define ADC_JOFR2_REGOFFSET 0x00001000U
118 #define ADC_JOFR3_REGOFFSET 0x00002000U
119 #define ADC_JOFR4_REGOFFSET 0x00003000U
121 #define ADC_INJ_JDRX_REGOFFSET_MASK (ADC_JDR1_REGOFFSET | ADC_JDR2_REGOFFSET | ADC_JDR3_REGOFFSET | ADC_JDR4_REGOFFSET)
122 #define ADC_INJ_JOFRX_REGOFFSET_MASK (ADC_JOFR1_REGOFFSET | ADC_JOFR2_REGOFFSET | ADC_JOFR3_REGOFFSET | ADC_JOFR4_REGOFFSET)
123 #define ADC_INJ_RANK_ID_JSQR_MASK (ADC_CHANNEL_ID_NUMBER_MASK_POSBIT0)
125 /* Internal mask for ADC channel: */
126 /* To select into literal LL_ADC_CHANNEL_x the relevant bits for: */
127 /* - channel identifier defined by number */
128 /* - channel differentiation between external channels (connected to */
129 /* GPIO pins) and internal channels (connected to internal paths) */
130 /* - channel sampling time defined by SMPRx register offset */
131 /* and SMPx bits positions into SMPRx register */
132 #define ADC_CHANNEL_ID_NUMBER_MASK (ADC_CR1_AWDCH)
133 #define ADC_CHANNEL_ID_NUMBER_BITOFFSET_POS ( 0U)/* Value equivalent to POSITION_VAL(ADC_CHANNEL_ID_NUMBER_MASK) */
134 #define ADC_CHANNEL_ID_MASK (ADC_CHANNEL_ID_NUMBER_MASK | ADC_CHANNEL_ID_INTERNAL_CH_MASK)
135 /* Equivalent mask of ADC_CHANNEL_NUMBER_MASK aligned on register LSB (bit 0) */
136 #define ADC_CHANNEL_ID_NUMBER_MASK_POSBIT0 0x0000001FU /* Equivalent to shift: (ADC_CHANNEL_NUMBER_MASK >> POSITION_VAL(ADC_CHANNEL_NUMBER_MASK)) */
138 /* Channel differentiation between external and internal channels */
139 #define ADC_CHANNEL_ID_INTERNAL_CH 0x80000000U /* Marker of internal channel */
140 #define ADC_CHANNEL_ID_INTERNAL_CH_2 0x40000000U /* Marker of internal channel for other ADC instances, in case of different ADC internal channels mapped on same channel number on different ADC instances */
141 #define ADC_CHANNEL_ID_INTERNAL_CH_MASK (ADC_CHANNEL_ID_INTERNAL_CH | ADC_CHANNEL_ID_INTERNAL_CH_2)
143 /* Internal register offset for ADC channel sampling time configuration */
144 /* (offset placed into a spare area of literal definition) */
145 #define ADC_SMPR1_REGOFFSET 0x00000000U
146 #define ADC_SMPR2_REGOFFSET 0x02000000U
147 #define ADC_CHANNEL_SMPRX_REGOFFSET_MASK (ADC_SMPR1_REGOFFSET | ADC_SMPR2_REGOFFSET)
149 #define ADC_CHANNEL_SMPx_BITOFFSET_MASK 0x01F00000U
150 #define ADC_CHANNEL_SMPx_BITOFFSET_POS (20U) /* Value equivalent to POSITION_VAL(ADC_CHANNEL_SMPx_BITOFFSET_MASK) */
152 /* Definition of channels ID number information to be inserted into */
153 /* channels literals definition. */
154 #define ADC_CHANNEL_0_NUMBER 0x00000000U
155 #define ADC_CHANNEL_1_NUMBER ( ADC_CR1_AWDCH_0)
156 #define ADC_CHANNEL_2_NUMBER ( ADC_CR1_AWDCH_1 )
157 #define ADC_CHANNEL_3_NUMBER ( ADC_CR1_AWDCH_1 | ADC_CR1_AWDCH_0)
158 #define ADC_CHANNEL_4_NUMBER ( ADC_CR1_AWDCH_2 )
159 #define ADC_CHANNEL_5_NUMBER ( ADC_CR1_AWDCH_2 | ADC_CR1_AWDCH_0)
160 #define ADC_CHANNEL_6_NUMBER ( ADC_CR1_AWDCH_2 | ADC_CR1_AWDCH_1 )
161 #define ADC_CHANNEL_7_NUMBER ( ADC_CR1_AWDCH_2 | ADC_CR1_AWDCH_1 | ADC_CR1_AWDCH_0)
162 #define ADC_CHANNEL_8_NUMBER ( ADC_CR1_AWDCH_3 )
163 #define ADC_CHANNEL_9_NUMBER ( ADC_CR1_AWDCH_3 | ADC_CR1_AWDCH_0)
164 #define ADC_CHANNEL_10_NUMBER ( ADC_CR1_AWDCH_3 | ADC_CR1_AWDCH_1 )
165 #define ADC_CHANNEL_11_NUMBER ( ADC_CR1_AWDCH_3 | ADC_CR1_AWDCH_1 | ADC_CR1_AWDCH_0)
166 #define ADC_CHANNEL_12_NUMBER ( ADC_CR1_AWDCH_3 | ADC_CR1_AWDCH_2 )
167 #define ADC_CHANNEL_13_NUMBER ( ADC_CR1_AWDCH_3 | ADC_CR1_AWDCH_2 | ADC_CR1_AWDCH_0)
168 #define ADC_CHANNEL_14_NUMBER ( ADC_CR1_AWDCH_3 | ADC_CR1_AWDCH_2 | ADC_CR1_AWDCH_1 )
169 #define ADC_CHANNEL_15_NUMBER ( ADC_CR1_AWDCH_3 | ADC_CR1_AWDCH_2 | ADC_CR1_AWDCH_1 | ADC_CR1_AWDCH_0)
170 #define ADC_CHANNEL_16_NUMBER (ADC_CR1_AWDCH_4 )
171 #define ADC_CHANNEL_17_NUMBER (ADC_CR1_AWDCH_4 | ADC_CR1_AWDCH_0)
173 /* Definition of channels sampling time information to be inserted into */
174 /* channels literals definition. */
175 #define ADC_CHANNEL_0_SMP (ADC_SMPR2_REGOFFSET | (( 0U) << ADC_CHANNEL_SMPx_BITOFFSET_POS)) /* Value shifted is equivalent to POSITION_VAL(ADC_SMPR2_SMP0) */
176 #define ADC_CHANNEL_1_SMP (ADC_SMPR2_REGOFFSET | (( 3U) << ADC_CHANNEL_SMPx_BITOFFSET_POS)) /* Value shifted is equivalent to POSITION_VAL(ADC_SMPR2_SMP1) */
177 #define ADC_CHANNEL_2_SMP (ADC_SMPR2_REGOFFSET | (( 6U) << ADC_CHANNEL_SMPx_BITOFFSET_POS)) /* Value shifted is equivalent to POSITION_VAL(ADC_SMPR2_SMP2) */
178 #define ADC_CHANNEL_3_SMP (ADC_SMPR2_REGOFFSET | (( 9U) << ADC_CHANNEL_SMPx_BITOFFSET_POS)) /* Value shifted is equivalent to POSITION_VAL(ADC_SMPR2_SMP3) */
179 #define ADC_CHANNEL_4_SMP (ADC_SMPR2_REGOFFSET | ((12U) << ADC_CHANNEL_SMPx_BITOFFSET_POS)) /* Value shifted is equivalent to POSITION_VAL(ADC_SMPR2_SMP4) */
180 #define ADC_CHANNEL_5_SMP (ADC_SMPR2_REGOFFSET | ((15U) << ADC_CHANNEL_SMPx_BITOFFSET_POS)) /* Value shifted is equivalent to POSITION_VAL(ADC_SMPR2_SMP5) */
181 #define ADC_CHANNEL_6_SMP (ADC_SMPR2_REGOFFSET | ((18U) << ADC_CHANNEL_SMPx_BITOFFSET_POS)) /* Value shifted is equivalent to POSITION_VAL(ADC_SMPR2_SMP6) */
182 #define ADC_CHANNEL_7_SMP (ADC_SMPR2_REGOFFSET | ((21U) << ADC_CHANNEL_SMPx_BITOFFSET_POS)) /* Value shifted is equivalent to POSITION_VAL(ADC_SMPR2_SMP7) */
183 #define ADC_CHANNEL_8_SMP (ADC_SMPR2_REGOFFSET | ((24U) << ADC_CHANNEL_SMPx_BITOFFSET_POS)) /* Value shifted is equivalent to POSITION_VAL(ADC_SMPR2_SMP8) */
184 #define ADC_CHANNEL_9_SMP (ADC_SMPR2_REGOFFSET | ((27U) << ADC_CHANNEL_SMPx_BITOFFSET_POS)) /* Value shifted is equivalent to POSITION_VAL(ADC_SMPR2_SMP9) */
185 #define ADC_CHANNEL_10_SMP (ADC_SMPR1_REGOFFSET | (( 0U) << ADC_CHANNEL_SMPx_BITOFFSET_POS)) /* Value shifted is equivalent to POSITION_VAL(ADC_SMPR1_SMP10) */
186 #define ADC_CHANNEL_11_SMP (ADC_SMPR1_REGOFFSET | (( 3U) << ADC_CHANNEL_SMPx_BITOFFSET_POS)) /* Value shifted is equivalent to POSITION_VAL(ADC_SMPR1_SMP11) */
187 #define ADC_CHANNEL_12_SMP (ADC_SMPR1_REGOFFSET | (( 6U) << ADC_CHANNEL_SMPx_BITOFFSET_POS)) /* Value shifted is equivalent to POSITION_VAL(ADC_SMPR1_SMP12) */
188 #define ADC_CHANNEL_13_SMP (ADC_SMPR1_REGOFFSET | (( 9U) << ADC_CHANNEL_SMPx_BITOFFSET_POS)) /* Value shifted is equivalent to POSITION_VAL(ADC_SMPR1_SMP13) */
189 #define ADC_CHANNEL_14_SMP (ADC_SMPR1_REGOFFSET | ((12U) << ADC_CHANNEL_SMPx_BITOFFSET_POS)) /* Value shifted is equivalent to POSITION_VAL(ADC_SMPR1_SMP14) */
190 #define ADC_CHANNEL_15_SMP (ADC_SMPR1_REGOFFSET | ((15U) << ADC_CHANNEL_SMPx_BITOFFSET_POS)) /* Value shifted is equivalent to POSITION_VAL(ADC_SMPR1_SMP15) */
191 #define ADC_CHANNEL_16_SMP (ADC_SMPR1_REGOFFSET | ((18U) << ADC_CHANNEL_SMPx_BITOFFSET_POS)) /* Value shifted is equivalent to POSITION_VAL(ADC_SMPR1_SMP16) */
192 #define ADC_CHANNEL_17_SMP (ADC_SMPR1_REGOFFSET | ((21U) << ADC_CHANNEL_SMPx_BITOFFSET_POS)) /* Value shifted is equivalent to POSITION_VAL(ADC_SMPR1_SMP17) */
194 /* Internal mask for ADC analog watchdog: */
195 /* To select into literals LL_ADC_AWD_CHANNELx_xxx the relevant bits for: */
196 /* (concatenation of multiple bits used in different analog watchdogs, */
197 /* (feature of several watchdogs not available on all STM32 families)). */
198 /* - analog watchdog 1: monitored channel defined by number, */
199 /* selection of ADC group (ADC groups regular and-or injected). */
201 /* Internal register offset for ADC analog watchdog channel configuration */
202 #define ADC_AWD_CR1_REGOFFSET 0x00000000U
204 #define ADC_AWD_CRX_REGOFFSET_MASK (ADC_AWD_CR1_REGOFFSET)
206 #define ADC_AWD_CR1_CHANNEL_MASK (ADC_CR1_AWDCH | ADC_CR1_JAWDEN | ADC_CR1_AWDEN | ADC_CR1_AWDSGL)
207 #define ADC_AWD_CR_ALL_CHANNEL_MASK (ADC_AWD_CR1_CHANNEL_MASK)
209 /* Internal register offset for ADC analog watchdog threshold configuration */
210 #define ADC_AWD_TR1_HIGH_REGOFFSET 0x00000000U
211 #define ADC_AWD_TR1_LOW_REGOFFSET 0x00000001U
212 #define ADC_AWD_TRX_REGOFFSET_MASK (ADC_AWD_TR1_HIGH_REGOFFSET | ADC_AWD_TR1_LOW_REGOFFSET)
214 /* ADC registers bits positions */
215 #define ADC_CR1_DUALMOD_BITOFFSET_POS (16U) /* Value equivalent to POSITION_VAL(ADC_CR1_DUALMOD) */
222 /* Private macros ------------------------------------------------------------*/
223 /** @defgroup ADC_LL_Private_Macros ADC Private Macros
228 * @brief Driver macro reserved for internal use: isolate bits with the
229 * selected mask and shift them to the register LSB
230 * (shift mask on register position bit 0).
231 * @param __BITS__ Bits in register 32 bits
232 * @param __MASK__ Mask in register 32 bits
233 * @retval Bits in register 32 bits
235 #define __ADC_MASK_SHIFT(__BITS__, __MASK__) \
236 (((__BITS__) & (__MASK__)) >> POSITION_VAL((__MASK__)))
239 * @brief Driver macro reserved for internal use: set a pointer to
240 * a register from a register basis from which an offset
242 * @param __REG__ Register basis from which the offset is applied.
243 * @param __REG_OFFFSET__ Offset to be applied (unit: number of registers).
244 * @retval Pointer to register address
246 #define __ADC_PTR_REG_OFFSET(__REG__, __REG_OFFFSET__) \
247 ((uint32_t *)((uint32_t) ((uint32_t)(&(__REG__)) + ((__REG_OFFFSET__) << 2U))))
254 /* Exported types ------------------------------------------------------------*/
255 #if defined(USE_FULL_LL_DRIVER)
256 /** @defgroup ADC_LL_ES_INIT ADC Exported Init structure
261 * @brief Structure definition of some features of ADC common parameters
263 * (all ADC instances belonging to the same ADC common instance).
264 * @note The setting of these parameters by function @ref LL_ADC_CommonInit()
265 * is conditioned to ADC instances state (all ADC instances
266 * sharing the same ADC common instance):
267 * All ADC instances sharing the same ADC common instance must be
272 uint32_t Multimode
; /*!< Set ADC multimode configuration to operate in independent mode or multimode (for devices with several ADC instances).
273 This parameter can be a value of @ref ADC_LL_EC_MULTI_MODE
275 This feature can be modified afterwards using unitary function @ref LL_ADC_SetMultimode(). */
276 } LL_ADC_CommonInitTypeDef
;
278 * @brief Structure definition of some features of ADC instance.
279 * @note These parameters have an impact on ADC scope: ADC instance.
280 * Affects both group regular and group injected (availability
281 * of ADC group injected depends on STM32 families).
282 * Refer to corresponding unitary functions into
283 * @ref ADC_LL_EF_Configuration_ADC_Instance .
284 * @note The setting of these parameters by function @ref LL_ADC_Init()
285 * is conditioned to ADC state:
286 * ADC instance must be disabled.
287 * This condition is applied to all ADC features, for efficiency
288 * and compatibility over all STM32 families. However, the different
289 * features can be set under different ADC state conditions
290 * (setting possible with ADC enabled without conversion on going,
291 * ADC enabled with conversion on going, ...)
292 * Each feature can be updated afterwards with a unitary function
293 * and potentially with ADC in a different state than disabled,
294 * refer to description of each function for setting
295 * conditioned to ADC state.
299 uint32_t DataAlignment
; /*!< Set ADC conversion data alignment.
300 This parameter can be a value of @ref ADC_LL_EC_DATA_ALIGN
302 This feature can be modified afterwards using unitary function @ref LL_ADC_SetDataAlignment(). */
304 uint32_t SequencersScanMode
; /*!< Set ADC scan selection.
305 This parameter can be a value of @ref ADC_LL_EC_SCAN_SELECTION
307 This feature can be modified afterwards using unitary function @ref LL_ADC_SetSequencersScanMode(). */
309 } LL_ADC_InitTypeDef
;
312 * @brief Structure definition of some features of ADC group regular.
313 * @note These parameters have an impact on ADC scope: ADC group regular.
314 * Refer to corresponding unitary functions into
315 * @ref ADC_LL_EF_Configuration_ADC_Group_Regular
316 * (functions with prefix "REG").
317 * @note The setting of these parameters by function @ref LL_ADC_REG_Init()
318 * is conditioned to ADC state:
319 * ADC instance must be disabled.
320 * This condition is applied to all ADC features, for efficiency
321 * and compatibility over all STM32 families. However, the different
322 * features can be set under different ADC state conditions
323 * (setting possible with ADC enabled without conversion on going,
324 * ADC enabled with conversion on going, ...)
325 * Each feature can be updated afterwards with a unitary function
326 * and potentially with ADC in a different state than disabled,
327 * refer to description of each function for setting
328 * conditioned to ADC state.
332 uint32_t TriggerSource
; /*!< Set ADC group regular conversion trigger source: internal (SW start) or from external IP (timer event, external interrupt line).
333 This parameter can be a value of @ref ADC_LL_EC_REG_TRIGGER_SOURCE
334 @note On this STM32 serie, external trigger is set with trigger polarity: rising edge
335 (only trigger polarity available on this STM32 serie).
337 This feature can be modified afterwards using unitary function @ref LL_ADC_REG_SetTriggerSource(). */
339 uint32_t SequencerLength
; /*!< Set ADC group regular sequencer length.
340 This parameter can be a value of @ref ADC_LL_EC_REG_SEQ_SCAN_LENGTH
341 @note This parameter is discarded if scan mode is disabled (refer to parameter 'ADC_SequencersScanMode').
343 This feature can be modified afterwards using unitary function @ref LL_ADC_REG_SetSequencerLength(). */
345 uint32_t SequencerDiscont
; /*!< Set ADC group regular sequencer discontinuous mode: sequence subdivided and scan conversions interrupted every selected number of ranks.
346 This parameter can be a value of @ref ADC_LL_EC_REG_SEQ_DISCONT_MODE
347 @note This parameter has an effect only if group regular sequencer is enabled
348 (scan length of 2 ranks or more).
350 This feature can be modified afterwards using unitary function @ref LL_ADC_REG_SetSequencerDiscont(). */
352 uint32_t ContinuousMode
; /*!< Set ADC continuous conversion mode on ADC group regular, whether ADC conversions are performed in single mode (one conversion per trigger) or in continuous mode (after the first trigger, following conversions launched successively automatically).
353 This parameter can be a value of @ref ADC_LL_EC_REG_CONTINUOUS_MODE
354 Note: It is not possible to enable both ADC group regular continuous mode and discontinuous mode.
356 This feature can be modified afterwards using unitary function @ref LL_ADC_REG_SetContinuousMode(). */
358 uint32_t DMATransfer
; /*!< Set ADC group regular conversion data transfer: no transfer or transfer by DMA, and DMA requests mode.
359 This parameter can be a value of @ref ADC_LL_EC_REG_DMA_TRANSFER
361 This feature can be modified afterwards using unitary function @ref LL_ADC_REG_SetDMATransfer(). */
363 } LL_ADC_REG_InitTypeDef
;
366 * @brief Structure definition of some features of ADC group injected.
367 * @note These parameters have an impact on ADC scope: ADC group injected.
368 * Refer to corresponding unitary functions into
369 * @ref ADC_LL_EF_Configuration_ADC_Group_Regular
370 * (functions with prefix "INJ").
371 * @note The setting of these parameters by function @ref LL_ADC_INJ_Init()
372 * is conditioned to ADC state:
373 * ADC instance must be disabled.
374 * This condition is applied to all ADC features, for efficiency
375 * and compatibility over all STM32 families. However, the different
376 * features can be set under different ADC state conditions
377 * (setting possible with ADC enabled without conversion on going,
378 * ADC enabled with conversion on going, ...)
379 * Each feature can be updated afterwards with a unitary function
380 * and potentially with ADC in a different state than disabled,
381 * refer to description of each function for setting
382 * conditioned to ADC state.
386 uint32_t TriggerSource
; /*!< Set ADC group injected conversion trigger source: internal (SW start) or from external IP (timer event, external interrupt line).
387 This parameter can be a value of @ref ADC_LL_EC_INJ_TRIGGER_SOURCE
388 @note On this STM32 serie, external trigger is set with trigger polarity: rising edge
389 (only trigger polarity available on this STM32 serie).
391 This feature can be modified afterwards using unitary function @ref LL_ADC_INJ_SetTriggerSource(). */
393 uint32_t SequencerLength
; /*!< Set ADC group injected sequencer length.
394 This parameter can be a value of @ref ADC_LL_EC_INJ_SEQ_SCAN_LENGTH
395 @note This parameter is discarded if scan mode is disabled (refer to parameter 'ADC_SequencersScanMode').
397 This feature can be modified afterwards using unitary function @ref LL_ADC_INJ_SetSequencerLength(). */
399 uint32_t SequencerDiscont
; /*!< Set ADC group injected sequencer discontinuous mode: sequence subdivided and scan conversions interrupted every selected number of ranks.
400 This parameter can be a value of @ref ADC_LL_EC_INJ_SEQ_DISCONT_MODE
401 @note This parameter has an effect only if group injected sequencer is enabled
402 (scan length of 2 ranks or more).
404 This feature can be modified afterwards using unitary function @ref LL_ADC_INJ_SetSequencerDiscont(). */
406 uint32_t TrigAuto
; /*!< Set ADC group injected conversion trigger: independent or from ADC group regular.
407 This parameter can be a value of @ref ADC_LL_EC_INJ_TRIG_AUTO
408 Note: This parameter must be set to set to independent trigger if injected trigger source is set to an external trigger.
410 This feature can be modified afterwards using unitary function @ref LL_ADC_INJ_SetTrigAuto(). */
412 } LL_ADC_INJ_InitTypeDef
;
417 #endif /* USE_FULL_LL_DRIVER */
419 /* Exported constants --------------------------------------------------------*/
420 /** @defgroup ADC_LL_Exported_Constants ADC Exported Constants
424 /** @defgroup ADC_LL_EC_FLAG ADC flags
425 * @brief Flags defines which can be used with LL_ADC_ReadReg function
428 #define LL_ADC_FLAG_STRT ADC_SR_STRT /*!< ADC flag ADC group regular conversion start */
429 #define LL_ADC_FLAG_EOS ADC_SR_EOC /*!< ADC flag ADC group regular end of sequence conversions (Note: on this STM32 serie, there is no flag ADC group regular end of unitary conversion. Flag noted as "EOC" is corresponding to flag "EOS" in other STM32 families) */
430 #define LL_ADC_FLAG_JSTRT ADC_SR_JSTRT /*!< ADC flag ADC group injected conversion start */
431 #define LL_ADC_FLAG_JEOS ADC_SR_JEOC /*!< ADC flag ADC group injected end of sequence conversions (Note: on this STM32 serie, there is no flag ADC group injected end of unitary conversion. Flag noted as "JEOC" is corresponding to flag "JEOS" in other STM32 families) */
432 #define LL_ADC_FLAG_AWD1 ADC_SR_AWD /*!< ADC flag ADC analog watchdog 1 */
433 #if defined(ADC_MULTIMODE_SUPPORT)
434 #define LL_ADC_FLAG_EOS_MST ADC_SR_EOC /*!< ADC flag ADC multimode master group regular end of sequence conversions (Note: on this STM32 serie, there is no flag ADC group regular end of unitary conversion. Flag noted as "EOC" is corresponding to flag "EOS" in other STM32 families) */
435 #define LL_ADC_FLAG_EOS_SLV ADC_SR_EOC /*!< ADC flag ADC multimode slave group regular end of sequence conversions (Note: on this STM32 serie, there is no flag ADC group regular end of unitary conversion. Flag noted as "EOC" is corresponding to flag "EOS" in other STM32 families) (on STM32F1, this flag must be read from ADC instance slave: ADC2) */
436 #define LL_ADC_FLAG_JEOS_MST ADC_SR_JEOC /*!< ADC flag ADC multimode master group injected end of sequence conversions (Note: on this STM32 serie, there is no flag ADC group injected end of unitary conversion. Flag noted as "JEOC" is corresponding to flag "JEOS" in other STM32 families) */
437 #define LL_ADC_FLAG_JEOS_SLV ADC_SR_JEOC /*!< ADC flag ADC multimode slave group injected end of sequence conversions (Note: on this STM32 serie, there is no flag ADC group injected end of unitary conversion. Flag noted as "JEOC" is corresponding to flag "JEOS" in other STM32 families) (on STM32F1, this flag must be read from ADC instance slave: ADC2) */
438 #define LL_ADC_FLAG_AWD1_MST ADC_SR_AWD /*!< ADC flag ADC multimode master analog watchdog 1 of the ADC master */
439 #define LL_ADC_FLAG_AWD1_SLV ADC_SR_AWD /*!< ADC flag ADC multimode slave analog watchdog 1 of the ADC slave (on STM32F1, this flag must be read from ADC instance slave: ADC2) */
445 /** @defgroup ADC_LL_EC_IT ADC interruptions for configuration (interruption enable or disable)
446 * @brief IT defines which can be used with LL_ADC_ReadReg and LL_ADC_WriteReg functions
449 #define LL_ADC_IT_EOS ADC_CR1_EOCIE /*!< ADC interruption ADC group regular end of sequence conversions (Note: on this STM32 serie, there is no flag ADC group regular end of unitary conversion. Flag noted as "EOC" is corresponding to flag "EOS" in other STM32 families) */
450 #define LL_ADC_IT_JEOS ADC_CR1_JEOCIE /*!< ADC interruption ADC group injected end of sequence conversions (Note: on this STM32 serie, there is no flag ADC group injected end of unitary conversion. Flag noted as "JEOC" is corresponding to flag "JEOS" in other STM32 families) */
451 #define LL_ADC_IT_AWD1 ADC_CR1_AWDIE /*!< ADC interruption ADC analog watchdog 1 */
456 /** @defgroup ADC_LL_EC_REGISTERS ADC registers compliant with specific purpose
459 /* List of ADC registers intended to be used (most commonly) with */
461 /* Refer to function @ref LL_ADC_DMA_GetRegAddr(). */
462 #define LL_ADC_DMA_REG_REGULAR_DATA 0x00000000U /* ADC group regular conversion data register (corresponding to register DR) to be used with ADC configured in independent mode. Without DMA transfer, register accessed by LL function @ref LL_ADC_REG_ReadConversionData32() and other functions @ref LL_ADC_REG_ReadConversionDatax() */
463 #if defined(ADC_MULTIMODE_SUPPORT)
464 #define LL_ADC_DMA_REG_REGULAR_DATA_MULTI 0x00000001U /* ADC group regular conversion data register (corresponding to register CDR) to be used with ADC configured in multimode (available on STM32 devices with several ADC instances). Without DMA transfer, register accessed by LL function @ref LL_ADC_REG_ReadMultiConversionData32() */
470 /** @defgroup ADC_LL_EC_COMMON_PATH_INTERNAL ADC common - Measurement path to internal channels
473 /* Note: Other measurement paths to internal channels may be available */
474 /* (connections to other peripherals). */
475 /* If they are not listed below, they do not require any specific */
476 /* path enable. In this case, Access to measurement path is done */
477 /* only by selecting the corresponding ADC internal channel. */
478 #define LL_ADC_PATH_INTERNAL_NONE 0x00000000U /*!< ADC measurement pathes all disabled */
479 #define LL_ADC_PATH_INTERNAL_VREFINT (ADC_CR2_TSVREFE) /*!< ADC measurement path to internal channel VrefInt */
480 #define LL_ADC_PATH_INTERNAL_TEMPSENSOR (ADC_CR2_TSVREFE) /*!< ADC measurement path to internal channel temperature sensor */
485 /** @defgroup ADC_LL_EC_RESOLUTION ADC instance - Resolution
488 #define LL_ADC_RESOLUTION_12B 0x00000000U /*!< ADC resolution 12 bits */
493 /** @defgroup ADC_LL_EC_DATA_ALIGN ADC instance - Data alignment
496 #define LL_ADC_DATA_ALIGN_RIGHT 0x00000000U /*!< ADC conversion data alignment: right aligned (alignment on data register LSB bit 0)*/
497 #define LL_ADC_DATA_ALIGN_LEFT (ADC_CR2_ALIGN) /*!< ADC conversion data alignment: left aligned (aligment on data register MSB bit 15)*/
502 /** @defgroup ADC_LL_EC_SCAN_SELECTION ADC instance - Scan selection
505 #define LL_ADC_SEQ_SCAN_DISABLE 0x00000000U /*!< ADC conversion is performed in unitary conversion mode (one channel converted, that defined in rank 1). Configuration of both groups regular and injected sequencers (sequence length, ...) is discarded: equivalent to length of 1 rank.*/
506 #define LL_ADC_SEQ_SCAN_ENABLE (ADC_CR1_SCAN) /*!< ADC conversions are performed in sequence conversions mode, according to configuration of both groups regular and injected sequencers (sequence length, ...). */
511 /** @defgroup ADC_LL_EC_GROUPS ADC instance - Groups
514 #define LL_ADC_GROUP_REGULAR 0x00000001U /*!< ADC group regular (available on all STM32 devices) */
515 #define LL_ADC_GROUP_INJECTED 0x00000002U /*!< ADC group injected (not available on all STM32 devices)*/
516 #define LL_ADC_GROUP_REGULAR_INJECTED 0x00000003U /*!< ADC both groups regular and injected */
521 /** @defgroup ADC_LL_EC_CHANNEL ADC instance - Channel number
524 #define LL_ADC_CHANNEL_0 (ADC_CHANNEL_0_NUMBER | ADC_CHANNEL_0_SMP) /*!< ADC external channel (channel connected to GPIO pin) ADCx_IN0 */
525 #define LL_ADC_CHANNEL_1 (ADC_CHANNEL_1_NUMBER | ADC_CHANNEL_1_SMP) /*!< ADC external channel (channel connected to GPIO pin) ADCx_IN1 */
526 #define LL_ADC_CHANNEL_2 (ADC_CHANNEL_2_NUMBER | ADC_CHANNEL_2_SMP) /*!< ADC external channel (channel connected to GPIO pin) ADCx_IN2 */
527 #define LL_ADC_CHANNEL_3 (ADC_CHANNEL_3_NUMBER | ADC_CHANNEL_3_SMP) /*!< ADC external channel (channel connected to GPIO pin) ADCx_IN3 */
528 #define LL_ADC_CHANNEL_4 (ADC_CHANNEL_4_NUMBER | ADC_CHANNEL_4_SMP) /*!< ADC external channel (channel connected to GPIO pin) ADCx_IN4 */
529 #define LL_ADC_CHANNEL_5 (ADC_CHANNEL_5_NUMBER | ADC_CHANNEL_5_SMP) /*!< ADC external channel (channel connected to GPIO pin) ADCx_IN5 */
530 #define LL_ADC_CHANNEL_6 (ADC_CHANNEL_6_NUMBER | ADC_CHANNEL_6_SMP) /*!< ADC external channel (channel connected to GPIO pin) ADCx_IN6 */
531 #define LL_ADC_CHANNEL_7 (ADC_CHANNEL_7_NUMBER | ADC_CHANNEL_7_SMP) /*!< ADC external channel (channel connected to GPIO pin) ADCx_IN7 */
532 #define LL_ADC_CHANNEL_8 (ADC_CHANNEL_8_NUMBER | ADC_CHANNEL_8_SMP) /*!< ADC external channel (channel connected to GPIO pin) ADCx_IN8 */
533 #define LL_ADC_CHANNEL_9 (ADC_CHANNEL_9_NUMBER | ADC_CHANNEL_9_SMP) /*!< ADC external channel (channel connected to GPIO pin) ADCx_IN9 */
534 #define LL_ADC_CHANNEL_10 (ADC_CHANNEL_10_NUMBER | ADC_CHANNEL_10_SMP) /*!< ADC external channel (channel connected to GPIO pin) ADCx_IN10 */
535 #define LL_ADC_CHANNEL_11 (ADC_CHANNEL_11_NUMBER | ADC_CHANNEL_11_SMP) /*!< ADC external channel (channel connected to GPIO pin) ADCx_IN11 */
536 #define LL_ADC_CHANNEL_12 (ADC_CHANNEL_12_NUMBER | ADC_CHANNEL_12_SMP) /*!< ADC external channel (channel connected to GPIO pin) ADCx_IN12 */
537 #define LL_ADC_CHANNEL_13 (ADC_CHANNEL_13_NUMBER | ADC_CHANNEL_13_SMP) /*!< ADC external channel (channel connected to GPIO pin) ADCx_IN13 */
538 #define LL_ADC_CHANNEL_14 (ADC_CHANNEL_14_NUMBER | ADC_CHANNEL_14_SMP) /*!< ADC external channel (channel connected to GPIO pin) ADCx_IN14 */
539 #define LL_ADC_CHANNEL_15 (ADC_CHANNEL_15_NUMBER | ADC_CHANNEL_15_SMP) /*!< ADC external channel (channel connected to GPIO pin) ADCx_IN15 */
540 #define LL_ADC_CHANNEL_16 (ADC_CHANNEL_16_NUMBER | ADC_CHANNEL_16_SMP) /*!< ADC external channel (channel connected to GPIO pin) ADCx_IN16 */
541 #define LL_ADC_CHANNEL_17 (ADC_CHANNEL_17_NUMBER | ADC_CHANNEL_17_SMP) /*!< ADC external channel (channel connected to GPIO pin) ADCx_IN17 */
542 #define LL_ADC_CHANNEL_VREFINT (LL_ADC_CHANNEL_17 | ADC_CHANNEL_ID_INTERNAL_CH) /*!< ADC internal channel connected to VrefInt: Internal voltage reference. On STM32F1, ADC channel available only on ADC instance: ADC1. */
543 #define LL_ADC_CHANNEL_TEMPSENSOR (LL_ADC_CHANNEL_16 | ADC_CHANNEL_ID_INTERNAL_CH) /*!< ADC internal channel connected to Temperature sensor. */
548 /** @defgroup ADC_LL_EC_REG_TRIGGER_SOURCE ADC group regular - Trigger source
551 /* ADC group regular external triggers for ADC instances: ADC1, ADC2, ADC3 (for ADC instances ADCx available on the selected device) */
552 #define LL_ADC_REG_TRIG_SOFTWARE (ADC_CR2_EXTSEL_2 | ADC_CR2_EXTSEL_1 | ADC_CR2_EXTSEL_0) /*!< ADC group regular conversion trigger internal: SW start. */
553 #define LL_ADC_REG_TRIG_EXT_TIM1_CH3 (ADC_CR2_EXTSEL_1) /*!< ADC group regular conversion trigger from external IP: TIM1 channel 3 event (capture compare: input capture or output capture). Trigger edge set to rising edge (default setting). */
554 /* ADC group regular external triggers for ADC instances: ADC1, ADC2 (for ADC instances ADCx available on the selected device) */
555 #define LL_ADC_REG_TRIG_EXT_TIM1_CH1 0x00000000U /*!< ADC group regular conversion trigger from external IP: TIM1 channel 1 event (capture compare: input capture or output capture). Trigger edge set to rising edge (default setting). */
556 #define LL_ADC_REG_TRIG_EXT_TIM1_CH2 (ADC_CR2_EXTSEL_0) /*!< ADC group regular conversion trigger from external IP: TIM1 channel 2 event (capture compare: input capture or output capture). Trigger edge set to rising edge (default setting). */
557 #define LL_ADC_REG_TRIG_EXT_TIM2_CH2 (ADC_CR2_EXTSEL_1 | ADC_CR2_EXTSEL_0) /*!< ADC group regular conversion trigger from external IP: TIM2 channel 2 event (capture compare: input capture or output capture). Trigger edge set to rising edge (default setting). */
558 #define LL_ADC_REG_TRIG_EXT_TIM3_TRGO (ADC_CR2_EXTSEL_2) /*!< ADC group regular conversion trigger from external IP: TIM3 TRGO. Trigger edge set to rising edge (default setting). */
559 #define LL_ADC_REG_TRIG_EXT_TIM4_CH4 (ADC_CR2_EXTSEL_2 | ADC_CR2_EXTSEL_0) /*!< ADC group regular conversion trigger from external IP: TIM4 channel 4 event (capture compare: input capture or output capture). Trigger edge set to rising edge (default setting). */
560 #define LL_ADC_REG_TRIG_EXT_EXTI_LINE11 (ADC_CR2_EXTSEL_2 | ADC_CR2_EXTSEL_1) /*!< ADC group regular conversion trigger from external IP: external interrupt line 11. Trigger edge set to rising edge (default setting). */
561 #if defined (STM32F101xE) || defined (STM32F103xE) || defined (STM32F103xG) || defined (STM32F105xC) || defined (STM32F107xC)
562 /* Note: TIM8_TRGO is available on ADC1 and ADC2 only in high-density and */
563 /* XL-density devices. */
564 /* Note: To use TIM8_TRGO on ADC1 or ADC2, a remap of trigger must be done */
565 /* A remap of trigger must be done at top level (refer to */
566 /* AFIO peripheral). */
567 #define LL_ADC_REG_TRIG_EXT_TIM8_TRGO (LL_ADC_REG_TRIG_EXT_EXTI_LINE11) /*!< ADC group regular conversion trigger from external IP: TIM8 TRGO. Trigger edge set to rising edge (default setting). Available only on high-density and XL-density devices. A remap of trigger must be done at top level (refer to AFIO peripheral).*/
568 #endif /* STM32F101xE || STM32F103xE || STM32F103xG || STM32F105xC || STM32F107xC */
569 #if defined (STM32F103xE) || defined (STM32F103xG)
570 /* ADC group regular external triggers for ADC instances: ADC3 (for ADC instances ADCx available on the selected device) */
571 #define LL_ADC_REG_TRIG_EXT_TIM3_CH1 (LL_ADC_REG_TRIG_EXT_TIM1_CH1) /*!< ADC group regular conversion trigger from external IP: TIM3 channel 1 event (capture compare: input capture or output capture). Trigger edge set to rising edge (default setting). */
572 #define LL_ADC_REG_TRIG_EXT_TIM2_CH3 (LL_ADC_REG_TRIG_EXT_TIM1_CH2) /*!< ADC group regular conversion trigger from external IP: TIM2 channel 3 event (capture compare: input capture or output capture). Trigger edge set to rising edge (default setting). */
573 #define LL_ADC_REG_TRIG_EXT_TIM8_CH1 (LL_ADC_REG_TRIG_EXT_TIM2_CH2) /*!< ADC group regular conversion trigger from external IP: TIM8 channel 1 event (capture compare: input capture or output capture). Trigger edge set to rising edge (default setting). */
574 #define LL_ADC_REG_TRIG_EXT_TIM8_TRGO_ADC3 (LL_ADC_REG_TRIG_EXT_TIM3_TRGO) /*!< ADC group regular conversion trigger from external IP: TIM8 TRGO. Trigger edge set to rising edge (default setting). */
575 #define LL_ADC_REG_TRIG_EXT_TIM5_CH1 (LL_ADC_REG_TRIG_EXT_TIM4_CH4) /*!< ADC group regular conversion trigger from external IP: TIM5 channel 1 event (capture compare: input capture or output capture). Trigger edge set to rising edge (default setting). */
576 #define LL_ADC_REG_TRIG_EXT_TIM5_CH3 (LL_ADC_REG_TRIG_EXT_EXTI_LINE11) /*!< ADC group regular conversion trigger from external IP: TIM5 channel 3 event (capture compare: input capture or output capture). Trigger edge set to rising edge (default setting). */
582 /** @defgroup ADC_LL_EC_REG_TRIGGER_EDGE ADC group regular - Trigger edge
585 #define LL_ADC_REG_TRIG_EXT_RISING ADC_CR2_EXTTRIG /*!< ADC group regular conversion trigger polarity set to rising edge */
590 /** @defgroup ADC_LL_EC_REG_CONTINUOUS_MODE ADC group regular - Continuous mode
593 #define LL_ADC_REG_CONV_SINGLE 0x00000000U /*!< ADC conversions are performed in single mode: one conversion per trigger */
594 #define LL_ADC_REG_CONV_CONTINUOUS (ADC_CR2_CONT) /*!< ADC conversions are performed in continuous mode: after the first trigger, following conversions launched successively automatically */
599 /** @defgroup ADC_LL_EC_REG_DMA_TRANSFER ADC group regular - DMA transfer of ADC conversion data
602 #define LL_ADC_REG_DMA_TRANSFER_NONE 0x00000000U /*!< ADC conversions are not transferred by DMA */
603 #define LL_ADC_REG_DMA_TRANSFER_UNLIMITED (ADC_CR2_DMA) /*!< ADC conversion data are transferred by DMA, in unlimited mode: DMA transfer requests are unlimited, whatever number of DMA data transferred (number of ADC conversions). This ADC mode is intended to be used with DMA mode circular. */
608 /** @defgroup ADC_LL_EC_REG_SEQ_SCAN_LENGTH ADC group regular - Sequencer scan length
611 #define LL_ADC_REG_SEQ_SCAN_DISABLE 0x00000000U /*!< ADC group regular sequencer disable (equivalent to sequencer of 1 rank: ADC conversion on only 1 channel) */
612 #define LL_ADC_REG_SEQ_SCAN_ENABLE_2RANKS ( ADC_SQR1_L_0) /*!< ADC group regular sequencer enable with 2 ranks in the sequence */
613 #define LL_ADC_REG_SEQ_SCAN_ENABLE_3RANKS ( ADC_SQR1_L_1 ) /*!< ADC group regular sequencer enable with 3 ranks in the sequence */
614 #define LL_ADC_REG_SEQ_SCAN_ENABLE_4RANKS ( ADC_SQR1_L_1 | ADC_SQR1_L_0) /*!< ADC group regular sequencer enable with 4 ranks in the sequence */
615 #define LL_ADC_REG_SEQ_SCAN_ENABLE_5RANKS ( ADC_SQR1_L_2 ) /*!< ADC group regular sequencer enable with 5 ranks in the sequence */
616 #define LL_ADC_REG_SEQ_SCAN_ENABLE_6RANKS ( ADC_SQR1_L_2 | ADC_SQR1_L_0) /*!< ADC group regular sequencer enable with 6 ranks in the sequence */
617 #define LL_ADC_REG_SEQ_SCAN_ENABLE_7RANKS ( ADC_SQR1_L_2 | ADC_SQR1_L_1 ) /*!< ADC group regular sequencer enable with 7 ranks in the sequence */
618 #define LL_ADC_REG_SEQ_SCAN_ENABLE_8RANKS ( ADC_SQR1_L_2 | ADC_SQR1_L_1 | ADC_SQR1_L_0) /*!< ADC group regular sequencer enable with 8 ranks in the sequence */
619 #define LL_ADC_REG_SEQ_SCAN_ENABLE_9RANKS (ADC_SQR1_L_3 ) /*!< ADC group regular sequencer enable with 9 ranks in the sequence */
620 #define LL_ADC_REG_SEQ_SCAN_ENABLE_10RANKS (ADC_SQR1_L_3 | ADC_SQR1_L_0) /*!< ADC group regular sequencer enable with 10 ranks in the sequence */
621 #define LL_ADC_REG_SEQ_SCAN_ENABLE_11RANKS (ADC_SQR1_L_3 | ADC_SQR1_L_1 ) /*!< ADC group regular sequencer enable with 11 ranks in the sequence */
622 #define LL_ADC_REG_SEQ_SCAN_ENABLE_12RANKS (ADC_SQR1_L_3 | ADC_SQR1_L_1 | ADC_SQR1_L_0) /*!< ADC group regular sequencer enable with 12 ranks in the sequence */
623 #define LL_ADC_REG_SEQ_SCAN_ENABLE_13RANKS (ADC_SQR1_L_3 | ADC_SQR1_L_2 ) /*!< ADC group regular sequencer enable with 13 ranks in the sequence */
624 #define LL_ADC_REG_SEQ_SCAN_ENABLE_14RANKS (ADC_SQR1_L_3 | ADC_SQR1_L_2 | ADC_SQR1_L_0) /*!< ADC group regular sequencer enable with 14 ranks in the sequence */
625 #define LL_ADC_REG_SEQ_SCAN_ENABLE_15RANKS (ADC_SQR1_L_3 | ADC_SQR1_L_2 | ADC_SQR1_L_1 ) /*!< ADC group regular sequencer enable with 15 ranks in the sequence */
626 #define LL_ADC_REG_SEQ_SCAN_ENABLE_16RANKS (ADC_SQR1_L_3 | ADC_SQR1_L_2 | ADC_SQR1_L_1 | ADC_SQR1_L_0) /*!< ADC group regular sequencer enable with 16 ranks in the sequence */
631 /** @defgroup ADC_LL_EC_REG_SEQ_DISCONT_MODE ADC group regular - Sequencer discontinuous mode
634 #define LL_ADC_REG_SEQ_DISCONT_DISABLE 0x00000000U /*!< ADC group regular sequencer discontinuous mode disable */
635 #define LL_ADC_REG_SEQ_DISCONT_1RANK ( ADC_CR1_DISCEN) /*!< ADC group regular sequencer discontinuous mode enable with sequence interruption every rank */
636 #define LL_ADC_REG_SEQ_DISCONT_2RANKS ( ADC_CR1_DISCNUM_0 | ADC_CR1_DISCEN) /*!< ADC group regular sequencer discontinuous mode enabled with sequence interruption every 2 ranks */
637 #define LL_ADC_REG_SEQ_DISCONT_3RANKS ( ADC_CR1_DISCNUM_1 | ADC_CR1_DISCEN) /*!< ADC group regular sequencer discontinuous mode enable with sequence interruption every 3 ranks */
638 #define LL_ADC_REG_SEQ_DISCONT_4RANKS ( ADC_CR1_DISCNUM_1 | ADC_CR1_DISCNUM_0 | ADC_CR1_DISCEN) /*!< ADC group regular sequencer discontinuous mode enable with sequence interruption every 4 ranks */
639 #define LL_ADC_REG_SEQ_DISCONT_5RANKS (ADC_CR1_DISCNUM_2 | ADC_CR1_DISCEN) /*!< ADC group regular sequencer discontinuous mode enable with sequence interruption every 5 ranks */
640 #define LL_ADC_REG_SEQ_DISCONT_6RANKS (ADC_CR1_DISCNUM_2 | ADC_CR1_DISCNUM_0 | ADC_CR1_DISCEN) /*!< ADC group regular sequencer discontinuous mode enable with sequence interruption every 6 ranks */
641 #define LL_ADC_REG_SEQ_DISCONT_7RANKS (ADC_CR1_DISCNUM_2 | ADC_CR1_DISCNUM_1 | ADC_CR1_DISCEN) /*!< ADC group regular sequencer discontinuous mode enable with sequence interruption every 7 ranks */
642 #define LL_ADC_REG_SEQ_DISCONT_8RANKS (ADC_CR1_DISCNUM_2 | ADC_CR1_DISCNUM_1 | ADC_CR1_DISCNUM_0 | ADC_CR1_DISCEN) /*!< ADC group regular sequencer discontinuous mode enable with sequence interruption every 8 ranks */
647 /** @defgroup ADC_LL_EC_REG_SEQ_RANKS ADC group regular - Sequencer ranks
650 #define LL_ADC_REG_RANK_1 (ADC_SQR3_REGOFFSET | ADC_REG_RANK_1_SQRX_BITOFFSET_POS) /*!< ADC group regular sequencer rank 1 */
651 #define LL_ADC_REG_RANK_2 (ADC_SQR3_REGOFFSET | ADC_REG_RANK_2_SQRX_BITOFFSET_POS) /*!< ADC group regular sequencer rank 2 */
652 #define LL_ADC_REG_RANK_3 (ADC_SQR3_REGOFFSET | ADC_REG_RANK_3_SQRX_BITOFFSET_POS) /*!< ADC group regular sequencer rank 3 */
653 #define LL_ADC_REG_RANK_4 (ADC_SQR3_REGOFFSET | ADC_REG_RANK_4_SQRX_BITOFFSET_POS) /*!< ADC group regular sequencer rank 4 */
654 #define LL_ADC_REG_RANK_5 (ADC_SQR3_REGOFFSET | ADC_REG_RANK_5_SQRX_BITOFFSET_POS) /*!< ADC group regular sequencer rank 5 */
655 #define LL_ADC_REG_RANK_6 (ADC_SQR3_REGOFFSET | ADC_REG_RANK_6_SQRX_BITOFFSET_POS) /*!< ADC group regular sequencer rank 6 */
656 #define LL_ADC_REG_RANK_7 (ADC_SQR2_REGOFFSET | ADC_REG_RANK_7_SQRX_BITOFFSET_POS) /*!< ADC group regular sequencer rank 7 */
657 #define LL_ADC_REG_RANK_8 (ADC_SQR2_REGOFFSET | ADC_REG_RANK_8_SQRX_BITOFFSET_POS) /*!< ADC group regular sequencer rank 8 */
658 #define LL_ADC_REG_RANK_9 (ADC_SQR2_REGOFFSET | ADC_REG_RANK_9_SQRX_BITOFFSET_POS) /*!< ADC group regular sequencer rank 9 */
659 #define LL_ADC_REG_RANK_10 (ADC_SQR2_REGOFFSET | ADC_REG_RANK_10_SQRX_BITOFFSET_POS) /*!< ADC group regular sequencer rank 10 */
660 #define LL_ADC_REG_RANK_11 (ADC_SQR2_REGOFFSET | ADC_REG_RANK_11_SQRX_BITOFFSET_POS) /*!< ADC group regular sequencer rank 11 */
661 #define LL_ADC_REG_RANK_12 (ADC_SQR2_REGOFFSET | ADC_REG_RANK_12_SQRX_BITOFFSET_POS) /*!< ADC group regular sequencer rank 12 */
662 #define LL_ADC_REG_RANK_13 (ADC_SQR1_REGOFFSET | ADC_REG_RANK_13_SQRX_BITOFFSET_POS) /*!< ADC group regular sequencer rank 13 */
663 #define LL_ADC_REG_RANK_14 (ADC_SQR1_REGOFFSET | ADC_REG_RANK_14_SQRX_BITOFFSET_POS) /*!< ADC group regular sequencer rank 14 */
664 #define LL_ADC_REG_RANK_15 (ADC_SQR1_REGOFFSET | ADC_REG_RANK_15_SQRX_BITOFFSET_POS) /*!< ADC group regular sequencer rank 15 */
665 #define LL_ADC_REG_RANK_16 (ADC_SQR1_REGOFFSET | ADC_REG_RANK_16_SQRX_BITOFFSET_POS) /*!< ADC group regular sequencer rank 16 */
670 /** @defgroup ADC_LL_EC_INJ_TRIGGER_SOURCE ADC group injected - Trigger source
673 /* ADC group injected external triggers for ADC instances: ADC1, ADC2, ADC3 (for ADC instances ADCx available on the selected device) */
674 #define LL_ADC_INJ_TRIG_SOFTWARE (ADC_CR2_JEXTSEL_2 | ADC_CR2_JEXTSEL_1 | ADC_CR2_JEXTSEL_0) /*!< ADC group injected conversion trigger internal: SW start. */
675 #define LL_ADC_INJ_TRIG_EXT_TIM1_TRGO 0x00000000U /*!< ADC group injected conversion trigger from external IP: TIM1 TRGO. Trigger edge set to rising edge (default setting). */
676 #define LL_ADC_INJ_TRIG_EXT_TIM1_CH4 (ADC_CR2_JEXTSEL_0) /*!< ADC group injected conversion trigger from external IP: TIM1 channel 4 event (capture compare: input capture or output capture). Trigger edge set to rising edge (default setting). */
677 /* ADC group injected external triggers for ADC instances: ADC1, ADC2 (for ADC instances ADCx available on the selected device) */
678 #define LL_ADC_INJ_TRIG_EXT_TIM2_TRGO (ADC_CR2_JEXTSEL_1) /*!< ADC group injected conversion trigger from external IP: TIM2 TRGO. Trigger edge set to rising edge (default setting). */
679 #define LL_ADC_INJ_TRIG_EXT_TIM2_CH1 (ADC_CR2_JEXTSEL_1 | ADC_CR2_JEXTSEL_0) /*!< ADC group injected conversion trigger from external IP: TIM2 channel 1 event (capture compare: input capture or output capture). Trigger edge set to rising edge (default setting). */
680 #define LL_ADC_INJ_TRIG_EXT_TIM3_CH4 (ADC_CR2_JEXTSEL_2) /*!< ADC group injected conversion trigger from external IP: TIM3 channel 4 event (capture compare: input capture or output capture). Trigger edge set to rising edge (default setting). */
681 #define LL_ADC_INJ_TRIG_EXT_TIM4_TRGO (ADC_CR2_JEXTSEL_2 | ADC_CR2_JEXTSEL_0) /*!< ADC group injected conversion trigger from external IP: TIM4 TRGO. Trigger edge set to rising edge (default setting). */
682 #define LL_ADC_INJ_TRIG_EXT_EXTI_LINE15 (ADC_CR2_JEXTSEL_2 | ADC_CR2_JEXTSEL_1) /*!< ADC group injected conversion trigger from external IP: external interrupt line 15. Trigger edge set to rising edge (default setting). */
683 #if defined (STM32F101xE) || defined (STM32F103xE) || defined (STM32F103xG) || defined (STM32F105xC) || defined (STM32F107xC)
684 /* Note: TIM8_CH4 is available on ADC1 and ADC2 only in high-density and */
685 /* XL-density devices. */
686 /* Note: To use TIM8_TRGO on ADC1 or ADC2, a remap of trigger must be done */
687 /* A remap of trigger must be done at top level (refer to */
688 /* AFIO peripheral). */
689 #define LL_ADC_INJ_TRIG_EXT_TIM8_CH4 (LL_ADC_INJ_TRIG_EXT_EXTI_LINE15) /*!< ADC group injected conversion trigger from external IP: TIM8 channel 4 event (capture compare: input capture or output capture). Trigger edge set to rising edge (default setting). Available only on high-density and XL-density devices. A remap of trigger must be done at top level (refer to AFIO peripheral). */
690 #endif /* STM32F101xE || STM32F103xE || STM32F103xG || STM32F105xC || STM32F107xC */
691 #if defined (STM32F103xE) || defined (STM32F103xG)
692 /* ADC group injected external triggers for ADC instances: ADC3 (for ADC instances ADCx available on the selected device) */
693 #define LL_ADC_INJ_TRIG_EXT_TIM4_CH3 (LL_ADC_INJ_TRIG_EXT_TIM2_TRGO) /*!< ADC group injected conversion trigger from external IP: TIM4 channel 3 event (capture compare: input capture or output capture). Trigger edge set to rising edge (default setting). */
694 #define LL_ADC_INJ_TRIG_EXT_TIM8_CH2 (LL_ADC_INJ_TRIG_EXT_TIM2_CH1) /*!< ADC group injected conversion trigger from external IP: TIM8 channel 2 event (capture compare: input capture or output capture). Trigger edge set to rising edge (default setting). */
695 #define LL_ADC_INJ_TRIG_EXT_TIM8_CH4_ADC3 (LL_ADC_INJ_TRIG_EXT_TIM3_CH4) /*!< ADC group injected conversion trigger from external IP: TIM8 channel 4 event (capture compare: input capture or output capture). Trigger edge set to rising edge (default setting). */
696 #define LL_ADC_INJ_TRIG_EXT_TIM5_TRGO (LL_ADC_INJ_TRIG_EXT_TIM4_TRGO) /*!< ADC group injected conversion trigger from external IP: TIM5 TRGO. Trigger edge set to rising edge (default setting). */
697 #define LL_ADC_INJ_TRIG_EXT_TIM5_CH4 (LL_ADC_INJ_TRIG_EXT_EXTI_LINE15) /*!< ADC group injected conversion trigger from external IP: TIM5 channel 4 event (capture compare: input capture or output capture). Trigger edge set to rising edge (default setting). */
703 /** @defgroup ADC_LL_EC_INJ_TRIGGER_EDGE ADC group injected - Trigger edge
706 #define LL_ADC_INJ_TRIG_EXT_RISING ADC_CR2_JEXTTRIG /*!< ADC group injected conversion trigger polarity set to rising edge */
711 /** @defgroup ADC_LL_EC_INJ_TRIG_AUTO ADC group injected - Automatic trigger mode
714 #define LL_ADC_INJ_TRIG_INDEPENDENT 0x00000000U /*!< ADC group injected conversion trigger independent. Setting mandatory if ADC group injected injected trigger source is set to an external trigger. */
715 #define LL_ADC_INJ_TRIG_FROM_GRP_REGULAR (ADC_CR1_JAUTO) /*!< ADC group injected conversion trigger from ADC group regular. Setting compliant only with group injected trigger source set to SW start, without any further action on ADC group injected conversion start or stop: in this case, ADC group injected is controlled only from ADC group regular. */
721 /** @defgroup ADC_LL_EC_INJ_SEQ_SCAN_LENGTH ADC group injected - Sequencer scan length
724 #define LL_ADC_INJ_SEQ_SCAN_DISABLE 0x00000000U /*!< ADC group injected sequencer disable (equivalent to sequencer of 1 rank: ADC conversion on only 1 channel) */
725 #define LL_ADC_INJ_SEQ_SCAN_ENABLE_2RANKS ( ADC_JSQR_JL_0) /*!< ADC group injected sequencer enable with 2 ranks in the sequence */
726 #define LL_ADC_INJ_SEQ_SCAN_ENABLE_3RANKS (ADC_JSQR_JL_1 ) /*!< ADC group injected sequencer enable with 3 ranks in the sequence */
727 #define LL_ADC_INJ_SEQ_SCAN_ENABLE_4RANKS (ADC_JSQR_JL_1 | ADC_JSQR_JL_0) /*!< ADC group injected sequencer enable with 4 ranks in the sequence */
732 /** @defgroup ADC_LL_EC_INJ_SEQ_DISCONT_MODE ADC group injected - Sequencer discontinuous mode
735 #define LL_ADC_INJ_SEQ_DISCONT_DISABLE 0x00000000U /*!< ADC group injected sequencer discontinuous mode disable */
736 #define LL_ADC_INJ_SEQ_DISCONT_1RANK (ADC_CR1_JDISCEN) /*!< ADC group injected sequencer discontinuous mode enable with sequence interruption every rank */
741 /** @defgroup ADC_LL_EC_INJ_SEQ_RANKS ADC group injected - Sequencer ranks
744 #define LL_ADC_INJ_RANK_1 (ADC_JDR1_REGOFFSET | ADC_JOFR1_REGOFFSET | 0x00000001U) /*!< ADC group injected sequencer rank 1 */
745 #define LL_ADC_INJ_RANK_2 (ADC_JDR2_REGOFFSET | ADC_JOFR2_REGOFFSET | 0x00000002U) /*!< ADC group injected sequencer rank 2 */
746 #define LL_ADC_INJ_RANK_3 (ADC_JDR3_REGOFFSET | ADC_JOFR3_REGOFFSET | 0x00000003U) /*!< ADC group injected sequencer rank 3 */
747 #define LL_ADC_INJ_RANK_4 (ADC_JDR4_REGOFFSET | ADC_JOFR4_REGOFFSET | 0x00000004U) /*!< ADC group injected sequencer rank 4 */
752 /** @defgroup ADC_LL_EC_CHANNEL_SAMPLINGTIME Channel - Sampling time
755 #define LL_ADC_SAMPLINGTIME_1CYCLE_5 0x00000000U /*!< Sampling time 1.5 ADC clock cycle */
756 #define LL_ADC_SAMPLINGTIME_7CYCLES_5 (ADC_SMPR2_SMP0_0) /*!< Sampling time 7.5 ADC clock cycles */
757 #define LL_ADC_SAMPLINGTIME_13CYCLES_5 (ADC_SMPR2_SMP0_1) /*!< Sampling time 13.5 ADC clock cycles */
758 #define LL_ADC_SAMPLINGTIME_28CYCLES_5 (ADC_SMPR2_SMP0_1 | ADC_SMPR2_SMP0_0) /*!< Sampling time 28.5 ADC clock cycles */
759 #define LL_ADC_SAMPLINGTIME_41CYCLES_5 (ADC_SMPR2_SMP0_2) /*!< Sampling time 41.5 ADC clock cycles */
760 #define LL_ADC_SAMPLINGTIME_55CYCLES_5 (ADC_SMPR2_SMP0_2 | ADC_SMPR2_SMP0_0) /*!< Sampling time 55.5 ADC clock cycles */
761 #define LL_ADC_SAMPLINGTIME_71CYCLES_5 (ADC_SMPR2_SMP0_2 | ADC_SMPR2_SMP0_1) /*!< Sampling time 71.5 ADC clock cycles */
762 #define LL_ADC_SAMPLINGTIME_239CYCLES_5 (ADC_SMPR2_SMP0_2 | ADC_SMPR2_SMP0_1 | ADC_SMPR2_SMP0_0) /*!< Sampling time 239.5 ADC clock cycles */
767 /** @defgroup ADC_LL_EC_AWD_NUMBER Analog watchdog - Analog watchdog number
770 #define LL_ADC_AWD1 (ADC_AWD_CR1_CHANNEL_MASK | ADC_AWD_CR1_REGOFFSET) /*!< ADC analog watchdog number 1 */
775 /** @defgroup ADC_LL_EC_AWD_CHANNELS Analog watchdog - Monitored channels
778 #define LL_ADC_AWD_DISABLE 0x00000000U /*!< ADC analog watchdog monitoring disabled */
779 #define LL_ADC_AWD_ALL_CHANNELS_REG ( ADC_CR1_AWDEN ) /*!< ADC analog watchdog monitoring of all channels, converted by group regular only */
780 #define LL_ADC_AWD_ALL_CHANNELS_INJ ( ADC_CR1_JAWDEN ) /*!< ADC analog watchdog monitoring of all channels, converted by group injected only */
781 #define LL_ADC_AWD_ALL_CHANNELS_REG_INJ ( ADC_CR1_JAWDEN | ADC_CR1_AWDEN ) /*!< ADC analog watchdog monitoring of all channels, converted by either group regular or injected */
782 #define LL_ADC_AWD_CHANNEL_0_REG ((LL_ADC_CHANNEL_0 & ADC_CHANNEL_ID_MASK) | ADC_CR1_AWDEN | ADC_CR1_AWDSGL) /*!< ADC analog watchdog monitoring of ADC external channel (channel connected to GPIO pin) ADCx_IN0, converted by group regular only */
783 #define LL_ADC_AWD_CHANNEL_0_INJ ((LL_ADC_CHANNEL_0 & ADC_CHANNEL_ID_MASK) | ADC_CR1_JAWDEN | ADC_CR1_AWDSGL) /*!< ADC analog watchdog monitoring of ADC external channel (channel connected to GPIO pin) ADCx_IN0, converted by group injected only */
784 #define LL_ADC_AWD_CHANNEL_0_REG_INJ ((LL_ADC_CHANNEL_0 & ADC_CHANNEL_ID_MASK) | ADC_CR1_JAWDEN | ADC_CR1_AWDEN | ADC_CR1_AWDSGL) /*!< ADC analog watchdog monitoring of ADC external channel (channel connected to GPIO pin) ADCx_IN0, converted by either group regular or injected */
785 #define LL_ADC_AWD_CHANNEL_1_REG ((LL_ADC_CHANNEL_1 & ADC_CHANNEL_ID_MASK) | ADC_CR1_AWDEN | ADC_CR1_AWDSGL) /*!< ADC analog watchdog monitoring of ADC external channel (channel connected to GPIO pin) ADCx_IN1, converted by group regular only */
786 #define LL_ADC_AWD_CHANNEL_1_INJ ((LL_ADC_CHANNEL_1 & ADC_CHANNEL_ID_MASK) | ADC_CR1_JAWDEN | ADC_CR1_AWDSGL) /*!< ADC analog watchdog monitoring of ADC external channel (channel connected to GPIO pin) ADCx_IN1, converted by group injected only */
787 #define LL_ADC_AWD_CHANNEL_1_REG_INJ ((LL_ADC_CHANNEL_1 & ADC_CHANNEL_ID_MASK) | ADC_CR1_JAWDEN | ADC_CR1_AWDEN | ADC_CR1_AWDSGL) /*!< ADC analog watchdog monitoring of ADC external channel (channel connected to GPIO pin) ADCx_IN1, converted by either group regular or injected */
788 #define LL_ADC_AWD_CHANNEL_2_REG ((LL_ADC_CHANNEL_2 & ADC_CHANNEL_ID_MASK) | ADC_CR1_AWDEN | ADC_CR1_AWDSGL) /*!< ADC analog watchdog monitoring of ADC external channel (channel connected to GPIO pin) ADCx_IN2, converted by group regular only */
789 #define LL_ADC_AWD_CHANNEL_2_INJ ((LL_ADC_CHANNEL_2 & ADC_CHANNEL_ID_MASK) | ADC_CR1_JAWDEN | ADC_CR1_AWDSGL) /*!< ADC analog watchdog monitoring of ADC external channel (channel connected to GPIO pin) ADCx_IN2, converted by group injected only */
790 #define LL_ADC_AWD_CHANNEL_2_REG_INJ ((LL_ADC_CHANNEL_2 & ADC_CHANNEL_ID_MASK) | ADC_CR1_JAWDEN | ADC_CR1_AWDEN | ADC_CR1_AWDSGL) /*!< ADC analog watchdog monitoring of ADC external channel (channel connected to GPIO pin) ADCx_IN2, converted by either group regular or injected */
791 #define LL_ADC_AWD_CHANNEL_3_REG ((LL_ADC_CHANNEL_3 & ADC_CHANNEL_ID_MASK) | ADC_CR1_AWDEN | ADC_CR1_AWDSGL) /*!< ADC analog watchdog monitoring of ADC external channel (channel connected to GPIO pin) ADCx_IN3, converted by group regular only */
792 #define LL_ADC_AWD_CHANNEL_3_INJ ((LL_ADC_CHANNEL_3 & ADC_CHANNEL_ID_MASK) | ADC_CR1_JAWDEN | ADC_CR1_AWDSGL) /*!< ADC analog watchdog monitoring of ADC external channel (channel connected to GPIO pin) ADCx_IN3, converted by group injected only */
793 #define LL_ADC_AWD_CHANNEL_3_REG_INJ ((LL_ADC_CHANNEL_3 & ADC_CHANNEL_ID_MASK) | ADC_CR1_JAWDEN | ADC_CR1_AWDEN | ADC_CR1_AWDSGL) /*!< ADC analog watchdog monitoring of ADC external channel (channel connected to GPIO pin) ADCx_IN3, converted by either group regular or injected */
794 #define LL_ADC_AWD_CHANNEL_4_REG ((LL_ADC_CHANNEL_4 & ADC_CHANNEL_ID_MASK) | ADC_CR1_AWDEN | ADC_CR1_AWDSGL) /*!< ADC analog watchdog monitoring of ADC external channel (channel connected to GPIO pin) ADCx_IN4, converted by group regular only */
795 #define LL_ADC_AWD_CHANNEL_4_INJ ((LL_ADC_CHANNEL_4 & ADC_CHANNEL_ID_MASK) | ADC_CR1_JAWDEN | ADC_CR1_AWDSGL) /*!< ADC analog watchdog monitoring of ADC external channel (channel connected to GPIO pin) ADCx_IN4, converted by group injected only */
796 #define LL_ADC_AWD_CHANNEL_4_REG_INJ ((LL_ADC_CHANNEL_4 & ADC_CHANNEL_ID_MASK) | ADC_CR1_JAWDEN | ADC_CR1_AWDEN | ADC_CR1_AWDSGL) /*!< ADC analog watchdog monitoring of ADC external channel (channel connected to GPIO pin) ADCx_IN4, converted by either group regular or injected */
797 #define LL_ADC_AWD_CHANNEL_5_REG ((LL_ADC_CHANNEL_5 & ADC_CHANNEL_ID_MASK) | ADC_CR1_AWDEN | ADC_CR1_AWDSGL) /*!< ADC analog watchdog monitoring of ADC external channel (channel connected to GPIO pin) ADCx_IN5, converted by group regular only */
798 #define LL_ADC_AWD_CHANNEL_5_INJ ((LL_ADC_CHANNEL_5 & ADC_CHANNEL_ID_MASK) | ADC_CR1_JAWDEN | ADC_CR1_AWDSGL) /*!< ADC analog watchdog monitoring of ADC external channel (channel connected to GPIO pin) ADCx_IN5, converted by group injected only */
799 #define LL_ADC_AWD_CHANNEL_5_REG_INJ ((LL_ADC_CHANNEL_5 & ADC_CHANNEL_ID_MASK) | ADC_CR1_JAWDEN | ADC_CR1_AWDEN | ADC_CR1_AWDSGL) /*!< ADC analog watchdog monitoring of ADC external channel (channel connected to GPIO pin) ADCx_IN5, converted by either group regular or injected */
800 #define LL_ADC_AWD_CHANNEL_6_REG ((LL_ADC_CHANNEL_6 & ADC_CHANNEL_ID_MASK) | ADC_CR1_AWDEN | ADC_CR1_AWDSGL) /*!< ADC analog watchdog monitoring of ADC external channel (channel connected to GPIO pin) ADCx_IN6, converted by group regular only */
801 #define LL_ADC_AWD_CHANNEL_6_INJ ((LL_ADC_CHANNEL_6 & ADC_CHANNEL_ID_MASK) | ADC_CR1_JAWDEN | ADC_CR1_AWDSGL) /*!< ADC analog watchdog monitoring of ADC external channel (channel connected to GPIO pin) ADCx_IN6, converted by group injected only */
802 #define LL_ADC_AWD_CHANNEL_6_REG_INJ ((LL_ADC_CHANNEL_6 & ADC_CHANNEL_ID_MASK) | ADC_CR1_JAWDEN | ADC_CR1_AWDEN | ADC_CR1_AWDSGL) /*!< ADC analog watchdog monitoring of ADC external channel (channel connected to GPIO pin) ADCx_IN6, converted by either group regular or injected */
803 #define LL_ADC_AWD_CHANNEL_7_REG ((LL_ADC_CHANNEL_7 & ADC_CHANNEL_ID_MASK) | ADC_CR1_AWDEN | ADC_CR1_AWDSGL) /*!< ADC analog watchdog monitoring of ADC external channel (channel connected to GPIO pin) ADCx_IN7, converted by group regular only */
804 #define LL_ADC_AWD_CHANNEL_7_INJ ((LL_ADC_CHANNEL_7 & ADC_CHANNEL_ID_MASK) | ADC_CR1_JAWDEN | ADC_CR1_AWDSGL) /*!< ADC analog watchdog monitoring of ADC external channel (channel connected to GPIO pin) ADCx_IN7, converted by group injected only */
805 #define LL_ADC_AWD_CHANNEL_7_REG_INJ ((LL_ADC_CHANNEL_7 & ADC_CHANNEL_ID_MASK) | ADC_CR1_JAWDEN | ADC_CR1_AWDEN | ADC_CR1_AWDSGL) /*!< ADC analog watchdog monitoring of ADC external channel (channel connected to GPIO pin) ADCx_IN7, converted by either group regular or injected */
806 #define LL_ADC_AWD_CHANNEL_8_REG ((LL_ADC_CHANNEL_8 & ADC_CHANNEL_ID_MASK) | ADC_CR1_AWDEN | ADC_CR1_AWDSGL) /*!< ADC analog watchdog monitoring of ADC external channel (channel connected to GPIO pin) ADCx_IN8, converted by group regular only */
807 #define LL_ADC_AWD_CHANNEL_8_INJ ((LL_ADC_CHANNEL_8 & ADC_CHANNEL_ID_MASK) | ADC_CR1_JAWDEN | ADC_CR1_AWDSGL) /*!< ADC analog watchdog monitoring of ADC external channel (channel connected to GPIO pin) ADCx_IN8, converted by group injected only */
808 #define LL_ADC_AWD_CHANNEL_8_REG_INJ ((LL_ADC_CHANNEL_8 & ADC_CHANNEL_ID_MASK) | ADC_CR1_JAWDEN | ADC_CR1_AWDEN | ADC_CR1_AWDSGL) /*!< ADC analog watchdog monitoring of ADC external channel (channel connected to GPIO pin) ADCx_IN8, converted by either group regular or injected */
809 #define LL_ADC_AWD_CHANNEL_9_REG ((LL_ADC_CHANNEL_9 & ADC_CHANNEL_ID_MASK) | ADC_CR1_AWDEN | ADC_CR1_AWDSGL) /*!< ADC analog watchdog monitoring of ADC external channel (channel connected to GPIO pin) ADCx_IN9, converted by group regular only */
810 #define LL_ADC_AWD_CHANNEL_9_INJ ((LL_ADC_CHANNEL_9 & ADC_CHANNEL_ID_MASK) | ADC_CR1_JAWDEN | ADC_CR1_AWDSGL) /*!< ADC analog watchdog monitoring of ADC external channel (channel connected to GPIO pin) ADCx_IN9, converted by group injected only */
811 #define LL_ADC_AWD_CHANNEL_9_REG_INJ ((LL_ADC_CHANNEL_9 & ADC_CHANNEL_ID_MASK) | ADC_CR1_JAWDEN | ADC_CR1_AWDEN | ADC_CR1_AWDSGL) /*!< ADC analog watchdog monitoring of ADC external channel (channel connected to GPIO pin) ADCx_IN9, converted by either group regular or injected */
812 #define LL_ADC_AWD_CHANNEL_10_REG ((LL_ADC_CHANNEL_10 & ADC_CHANNEL_ID_MASK) | ADC_CR1_AWDEN | ADC_CR1_AWDSGL) /*!< ADC analog watchdog monitoring of ADC external channel (channel connected to GPIO pin) ADCx_IN10, converted by group regular only */
813 #define LL_ADC_AWD_CHANNEL_10_INJ ((LL_ADC_CHANNEL_10 & ADC_CHANNEL_ID_MASK) | ADC_CR1_JAWDEN | ADC_CR1_AWDSGL) /*!< ADC analog watchdog monitoring of ADC external channel (channel connected to GPIO pin) ADCx_IN10, converted by group injected only */
814 #define LL_ADC_AWD_CHANNEL_10_REG_INJ ((LL_ADC_CHANNEL_10 & ADC_CHANNEL_ID_MASK) | ADC_CR1_JAWDEN | ADC_CR1_AWDEN | ADC_CR1_AWDSGL) /*!< ADC analog watchdog monitoring of ADC external channel (channel connected to GPIO pin) ADCx_IN10, converted by either group regular or injected */
815 #define LL_ADC_AWD_CHANNEL_11_REG ((LL_ADC_CHANNEL_11 & ADC_CHANNEL_ID_MASK) | ADC_CR1_AWDEN | ADC_CR1_AWDSGL) /*!< ADC analog watchdog monitoring of ADC external channel (channel connected to GPIO pin) ADCx_IN11, converted by group regular only */
816 #define LL_ADC_AWD_CHANNEL_11_INJ ((LL_ADC_CHANNEL_11 & ADC_CHANNEL_ID_MASK) | ADC_CR1_JAWDEN | ADC_CR1_AWDSGL) /*!< ADC analog watchdog monitoring of ADC external channel (channel connected to GPIO pin) ADCx_IN11, converted by group injected only */
817 #define LL_ADC_AWD_CHANNEL_11_REG_INJ ((LL_ADC_CHANNEL_11 & ADC_CHANNEL_ID_MASK) | ADC_CR1_JAWDEN | ADC_CR1_AWDEN | ADC_CR1_AWDSGL) /*!< ADC analog watchdog monitoring of ADC external channel (channel connected to GPIO pin) ADCx_IN11, converted by either group regular or injected */
818 #define LL_ADC_AWD_CHANNEL_12_REG ((LL_ADC_CHANNEL_12 & ADC_CHANNEL_ID_MASK) | ADC_CR1_AWDEN | ADC_CR1_AWDSGL) /*!< ADC analog watchdog monitoring of ADC external channel (channel connected to GPIO pin) ADCx_IN12, converted by group regular only */
819 #define LL_ADC_AWD_CHANNEL_12_INJ ((LL_ADC_CHANNEL_12 & ADC_CHANNEL_ID_MASK) | ADC_CR1_JAWDEN | ADC_CR1_AWDSGL) /*!< ADC analog watchdog monitoring of ADC external channel (channel connected to GPIO pin) ADCx_IN12, converted by group injected only */
820 #define LL_ADC_AWD_CHANNEL_12_REG_INJ ((LL_ADC_CHANNEL_12 & ADC_CHANNEL_ID_MASK) | ADC_CR1_JAWDEN | ADC_CR1_AWDEN | ADC_CR1_AWDSGL) /*!< ADC analog watchdog monitoring of ADC external channel (channel connected to GPIO pin) ADCx_IN12, converted by either group regular or injected */
821 #define LL_ADC_AWD_CHANNEL_13_REG ((LL_ADC_CHANNEL_13 & ADC_CHANNEL_ID_MASK) | ADC_CR1_AWDEN | ADC_CR1_AWDSGL) /*!< ADC analog watchdog monitoring of ADC external channel (channel connected to GPIO pin) ADCx_IN13, converted by group regular only */
822 #define LL_ADC_AWD_CHANNEL_13_INJ ((LL_ADC_CHANNEL_13 & ADC_CHANNEL_ID_MASK) | ADC_CR1_JAWDEN | ADC_CR1_AWDSGL) /*!< ADC analog watchdog monitoring of ADC external channel (channel connected to GPIO pin) ADCx_IN13, converted by group injected only */
823 #define LL_ADC_AWD_CHANNEL_13_REG_INJ ((LL_ADC_CHANNEL_13 & ADC_CHANNEL_ID_MASK) | ADC_CR1_JAWDEN | ADC_CR1_AWDEN | ADC_CR1_AWDSGL) /*!< ADC analog watchdog monitoring of ADC external channel (channel connected to GPIO pin) ADCx_IN13, converted by either group regular or injected */
824 #define LL_ADC_AWD_CHANNEL_14_REG ((LL_ADC_CHANNEL_14 & ADC_CHANNEL_ID_MASK) | ADC_CR1_AWDEN | ADC_CR1_AWDSGL) /*!< ADC analog watchdog monitoring of ADC external channel (channel connected to GPIO pin) ADCx_IN14, converted by group regular only */
825 #define LL_ADC_AWD_CHANNEL_14_INJ ((LL_ADC_CHANNEL_14 & ADC_CHANNEL_ID_MASK) | ADC_CR1_JAWDEN | ADC_CR1_AWDSGL) /*!< ADC analog watchdog monitoring of ADC external channel (channel connected to GPIO pin) ADCx_IN14, converted by group injected only */
826 #define LL_ADC_AWD_CHANNEL_14_REG_INJ ((LL_ADC_CHANNEL_14 & ADC_CHANNEL_ID_MASK) | ADC_CR1_JAWDEN | ADC_CR1_AWDEN | ADC_CR1_AWDSGL) /*!< ADC analog watchdog monitoring of ADC external channel (channel connected to GPIO pin) ADCx_IN14, converted by either group regular or injected */
827 #define LL_ADC_AWD_CHANNEL_15_REG ((LL_ADC_CHANNEL_15 & ADC_CHANNEL_ID_MASK) | ADC_CR1_AWDEN | ADC_CR1_AWDSGL) /*!< ADC analog watchdog monitoring of ADC external channel (channel connected to GPIO pin) ADCx_IN15, converted by group regular only */
828 #define LL_ADC_AWD_CHANNEL_15_INJ ((LL_ADC_CHANNEL_15 & ADC_CHANNEL_ID_MASK) | ADC_CR1_JAWDEN | ADC_CR1_AWDSGL) /*!< ADC analog watchdog monitoring of ADC external channel (channel connected to GPIO pin) ADCx_IN15, converted by group injected only */
829 #define LL_ADC_AWD_CHANNEL_15_REG_INJ ((LL_ADC_CHANNEL_15 & ADC_CHANNEL_ID_MASK) | ADC_CR1_JAWDEN | ADC_CR1_AWDEN | ADC_CR1_AWDSGL) /*!< ADC analog watchdog monitoring of ADC external channel (channel connected to GPIO pin) ADCx_IN15, converted by either group regular or injected */
830 #define LL_ADC_AWD_CHANNEL_16_REG ((LL_ADC_CHANNEL_16 & ADC_CHANNEL_ID_MASK) | ADC_CR1_AWDEN | ADC_CR1_AWDSGL) /*!< ADC analog watchdog monitoring of ADC external channel (channel connected to GPIO pin) ADCx_IN16, converted by group regular only */
831 #define LL_ADC_AWD_CHANNEL_16_INJ ((LL_ADC_CHANNEL_16 & ADC_CHANNEL_ID_MASK) | ADC_CR1_JAWDEN | ADC_CR1_AWDSGL) /*!< ADC analog watchdog monitoring of ADC external channel (channel connected to GPIO pin) ADCx_IN16, converted by group injected only */
832 #define LL_ADC_AWD_CHANNEL_16_REG_INJ ((LL_ADC_CHANNEL_16 & ADC_CHANNEL_ID_MASK) | ADC_CR1_JAWDEN | ADC_CR1_AWDEN | ADC_CR1_AWDSGL) /*!< ADC analog watchdog monitoring of ADC external channel (channel connected to GPIO pin) ADCx_IN16, converted by either group regular or injected */
833 #define LL_ADC_AWD_CHANNEL_17_REG ((LL_ADC_CHANNEL_17 & ADC_CHANNEL_ID_MASK) | ADC_CR1_AWDEN | ADC_CR1_AWDSGL) /*!< ADC analog watchdog monitoring of ADC external channel (channel connected to GPIO pin) ADCx_IN17, converted by group regular only */
834 #define LL_ADC_AWD_CHANNEL_17_INJ ((LL_ADC_CHANNEL_17 & ADC_CHANNEL_ID_MASK) | ADC_CR1_JAWDEN | ADC_CR1_AWDSGL) /*!< ADC analog watchdog monitoring of ADC external channel (channel connected to GPIO pin) ADCx_IN17, converted by group injected only */
835 #define LL_ADC_AWD_CHANNEL_17_REG_INJ ((LL_ADC_CHANNEL_17 & ADC_CHANNEL_ID_MASK) | ADC_CR1_JAWDEN | ADC_CR1_AWDEN | ADC_CR1_AWDSGL) /*!< ADC analog watchdog monitoring of ADC external channel (channel connected to GPIO pin) ADCx_IN17, converted by either group regular or injected */
836 #define LL_ADC_AWD_CH_VREFINT_REG ((LL_ADC_CHANNEL_VREFINT & ADC_CHANNEL_ID_MASK) | ADC_CR1_AWDEN | ADC_CR1_AWDSGL) /*!< ADC analog watchdog monitoring of ADC internal channel connected to VrefInt: Internal voltage reference, converted by group regular only */
837 #define LL_ADC_AWD_CH_VREFINT_INJ ((LL_ADC_CHANNEL_VREFINT & ADC_CHANNEL_ID_MASK) | ADC_CR1_JAWDEN | ADC_CR1_AWDSGL) /*!< ADC analog watchdog monitoring of ADC internal channel connected to VrefInt: Internal voltage reference, converted by group injected only */
838 #define LL_ADC_AWD_CH_VREFINT_REG_INJ ((LL_ADC_CHANNEL_VREFINT & ADC_CHANNEL_ID_MASK) | ADC_CR1_JAWDEN | ADC_CR1_AWDEN | ADC_CR1_AWDSGL) /*!< ADC analog watchdog monitoring of ADC internal channel connected to VrefInt: Internal voltage reference, converted by either group regular or injected */
839 #define LL_ADC_AWD_CH_TEMPSENSOR_REG ((LL_ADC_CHANNEL_TEMPSENSOR & ADC_CHANNEL_ID_MASK) | ADC_CR1_AWDEN | ADC_CR1_AWDSGL) /*!< ADC analog watchdog monitoring of ADC internal channel connected to Temperature sensor, converted by group regular only */
840 #define LL_ADC_AWD_CH_TEMPSENSOR_INJ ((LL_ADC_CHANNEL_TEMPSENSOR & ADC_CHANNEL_ID_MASK) | ADC_CR1_JAWDEN | ADC_CR1_AWDSGL) /*!< ADC analog watchdog monitoring of ADC internal channel connected to Temperature sensor, converted by group injected only */
841 #define LL_ADC_AWD_CH_TEMPSENSOR_REG_INJ ((LL_ADC_CHANNEL_TEMPSENSOR & ADC_CHANNEL_ID_MASK) | ADC_CR1_JAWDEN | ADC_CR1_AWDEN | ADC_CR1_AWDSGL) /*!< ADC analog watchdog monitoring of ADC internal channel connected to Temperature sensor, converted by either group regular or injected */
846 /** @defgroup ADC_LL_EC_AWD_THRESHOLDS Analog watchdog - Thresholds
849 #define LL_ADC_AWD_THRESHOLD_HIGH (ADC_AWD_TR1_HIGH_REGOFFSET) /*!< ADC analog watchdog threshold high */
850 #define LL_ADC_AWD_THRESHOLD_LOW (ADC_AWD_TR1_LOW_REGOFFSET) /*!< ADC analog watchdog threshold low */
855 #if !defined(ADC_MULTIMODE_SUPPORT)
856 /** @defgroup ADC_LL_EC_MULTI_MODE Multimode - Mode
859 #define LL_ADC_MULTI_INDEPENDENT 0x00000000U /*!< ADC dual mode disabled (ADC independent mode) */
864 #if defined(ADC_MULTIMODE_SUPPORT)
865 /** @defgroup ADC_LL_EC_MULTI_MODE Multimode - Mode
868 #define LL_ADC_MULTI_INDEPENDENT 0x00000000U /*!< ADC dual mode disabled (ADC independent mode) */
869 #define LL_ADC_MULTI_DUAL_REG_SIMULT ( ADC_CR1_DUALMOD_2 | ADC_CR1_DUALMOD_1 ) /*!< ADC dual mode enabled: group regular simultaneous */
870 #define LL_ADC_MULTI_DUAL_REG_INTERL_FAST ( ADC_CR1_DUALMOD_2 | ADC_CR1_DUALMOD_1 | ADC_CR1_DUALMOD_0) /*!< ADC dual mode enabled: Combined group regular interleaved fast (delay between ADC sampling phases: 7 ADC clock cycles) (equivalent to multimode sampling delay set to "LL_ADC_MULTI_TWOSMP_DELAY_7CYCLES" on other STM32 devices)) */
871 #define LL_ADC_MULTI_DUAL_REG_INTERL_SLOW (ADC_CR1_DUALMOD_3 ) /*!< ADC dual mode enabled: Combined group regular interleaved slow (delay between ADC sampling phases: 14 ADC clock cycles) (equivalent to multimode sampling delay set to "LL_ADC_MULTI_TWOSMP_DELAY_14CYCLES" on other STM32 devices)) */
872 #define LL_ADC_MULTI_DUAL_INJ_SIMULT ( ADC_CR1_DUALMOD_2 | ADC_CR1_DUALMOD_0) /*!< ADC dual mode enabled: group injected simultaneous slow (delay between ADC sampling phases: 14 ADC clock cycles) (equivalent to multimode sampling delay set to "LL_ADC_MULTI_TWOSMP_DELAY_14CYCLES" on other STM32 devices)) */
873 #define LL_ADC_MULTI_DUAL_INJ_ALTERN (ADC_CR1_DUALMOD_3 | ADC_CR1_DUALMOD_0) /*!< ADC dual mode enabled: group injected alternate trigger. Works only with external triggers (not internal SW start) */
874 #define LL_ADC_MULTI_DUAL_REG_SIM_INJ_SIM ( ADC_CR1_DUALMOD_0) /*!< ADC dual mode enabled: Combined group regular simultaneous + group injected simultaneous */
875 #define LL_ADC_MULTI_DUAL_REG_SIM_INJ_ALT ( ADC_CR1_DUALMOD_1 ) /*!< ADC dual mode enabled: Combined group regular simultaneous + group injected alternate trigger */
876 #define LL_ADC_MULTI_DUAL_REG_INTFAST_INJ_SIM ( ADC_CR1_DUALMOD_1 | ADC_CR1_DUALMOD_0) /*!< ADC dual mode enabled: Combined group regular interleaved fast (delay between ADC sampling phases: 7 ADC clock cycles) + group injected simultaneous */
877 #define LL_ADC_MULTI_DUAL_REG_INTSLOW_INJ_SIM ( ADC_CR1_DUALMOD_2 ) /*!< ADC dual mode enabled: Combined group regular interleaved slow (delay between ADC sampling phases: 14 ADC clock cycles) + group injected simultaneous */
883 /** @defgroup ADC_LL_EC_MULTI_MASTER_SLAVE Multimode - ADC master or slave
886 #define LL_ADC_MULTI_MASTER ( ADC_DR_DATA) /*!< In multimode, selection among several ADC instances: ADC master */
887 #define LL_ADC_MULTI_SLAVE (ADC_DR_ADC2DATA ) /*!< In multimode, selection among several ADC instances: ADC slave */
888 #define LL_ADC_MULTI_MASTER_SLAVE (ADC_DR_ADC2DATA | ADC_DR_DATA) /*!< In multimode, selection among several ADC instances: both ADC master and ADC slave */
893 #endif /* ADC_MULTIMODE_SUPPORT */
896 /** @defgroup ADC_LL_EC_HW_DELAYS Definitions of ADC hardware constraints delays
897 * @note Only ADC IP HW delays are defined in ADC LL driver driver,
898 * not timeout values.
899 * For details on delays values, refer to descriptions in source code
900 * above each literal definition.
904 /* Note: Only ADC IP HW delays are defined in ADC LL driver driver, */
905 /* not timeout values. */
906 /* Timeout values for ADC operations are dependent to device clock */
907 /* configuration (system clock versus ADC clock), */
908 /* and therefore must be defined in user application. */
909 /* Indications for estimation of ADC timeout delays, for this */
911 /* - ADC enable time: maximum delay is 1us */
912 /* (refer to device datasheet, parameter "tSTAB") */
913 /* - ADC conversion time: duration depending on ADC clock and ADC */
915 /* (refer to device reference manual, section "Timing") */
917 /* Delay for temperature sensor stabilization time. */
918 /* Literal set to maximum value (refer to device datasheet, */
919 /* parameter "tSTART"). */
921 #define LL_ADC_DELAY_TEMPSENSOR_STAB_US (10U) /*!< Delay for internal voltage reference stabilization time */
923 /* Delay required between ADC disable and ADC calibration start. */
924 /* Note: On this STM32 serie, before starting a calibration, */
925 /* ADC must be disabled. */
926 /* A minimum number of ADC clock cycles are required */
927 /* between ADC disable state and calibration start. */
928 /* Refer to literal @ref LL_ADC_DELAY_ENABLE_CALIB_ADC_CYCLES. */
929 /* Wait time can be computed in user application by waiting for the */
930 /* equivalent number of CPU cycles, by taking into account */
931 /* ratio of CPU clock versus ADC clock prescalers. */
932 /* Unit: ADC clock cycles. */
933 #define LL_ADC_DELAY_DISABLE_CALIB_ADC_CYCLES (2U) /*!< Delay required between ADC disable and ADC calibration start */
935 /* Delay required between end of ADC Enable and the start of ADC calibration. */
936 /* Note: On this STM32 serie, a minimum number of ADC clock cycles */
937 /* are required between the end of ADC enable and the start of ADC */
939 /* Wait time can be computed in user application by waiting for the */
940 /* equivalent number of CPU cycles, by taking into account */
941 /* ratio of CPU clock versus ADC clock prescalers. */
942 /* Unit: ADC clock cycles. */
943 #define LL_ADC_DELAY_ENABLE_CALIB_ADC_CYCLES (2U) /*!< Delay required between end of ADC enable and the start of ADC calibration */
954 /* Exported macro ------------------------------------------------------------*/
955 /** @defgroup ADC_LL_Exported_Macros ADC Exported Macros
959 /** @defgroup ADC_LL_EM_WRITE_READ Common write and read registers Macros
964 * @brief Write a value in ADC register
965 * @param __INSTANCE__ ADC Instance
966 * @param __REG__ Register to be written
967 * @param __VALUE__ Value to be written in the register
970 #define LL_ADC_WriteReg(__INSTANCE__, __REG__, __VALUE__) WRITE_REG(__INSTANCE__->__REG__, (__VALUE__))
973 * @brief Read a value in ADC register
974 * @param __INSTANCE__ ADC Instance
975 * @param __REG__ Register to be read
976 * @retval Register value
978 #define LL_ADC_ReadReg(__INSTANCE__, __REG__) READ_REG(__INSTANCE__->__REG__)
983 /** @defgroup ADC_LL_EM_HELPER_MACRO ADC helper macro
988 * @brief Helper macro to get ADC channel number in decimal format
989 * from literals LL_ADC_CHANNEL_x.
991 * __LL_ADC_CHANNEL_TO_DECIMAL_NB(LL_ADC_CHANNEL_4)
992 * will return decimal number "4".
993 * @note The input can be a value from functions where a channel
994 * number is returned, either defined with number
995 * or with bitfield (only one bit must be set).
996 * @param __CHANNEL__ This parameter can be one of the following values:
997 * @arg @ref LL_ADC_CHANNEL_0
998 * @arg @ref LL_ADC_CHANNEL_1
999 * @arg @ref LL_ADC_CHANNEL_2
1000 * @arg @ref LL_ADC_CHANNEL_3
1001 * @arg @ref LL_ADC_CHANNEL_4
1002 * @arg @ref LL_ADC_CHANNEL_5
1003 * @arg @ref LL_ADC_CHANNEL_6
1004 * @arg @ref LL_ADC_CHANNEL_7
1005 * @arg @ref LL_ADC_CHANNEL_8
1006 * @arg @ref LL_ADC_CHANNEL_9
1007 * @arg @ref LL_ADC_CHANNEL_10
1008 * @arg @ref LL_ADC_CHANNEL_11
1009 * @arg @ref LL_ADC_CHANNEL_12
1010 * @arg @ref LL_ADC_CHANNEL_13
1011 * @arg @ref LL_ADC_CHANNEL_14
1012 * @arg @ref LL_ADC_CHANNEL_15
1013 * @arg @ref LL_ADC_CHANNEL_16
1014 * @arg @ref LL_ADC_CHANNEL_17
1015 * @arg @ref LL_ADC_CHANNEL_VREFINT (1)
1016 * @arg @ref LL_ADC_CHANNEL_TEMPSENSOR (1)
1018 * (1) On STM32F1, parameter available only on ADC instance: ADC1.
1019 * @retval Value between Min_Data=0 and Max_Data=18
1021 #define __LL_ADC_CHANNEL_TO_DECIMAL_NB(__CHANNEL__) \
1022 (((__CHANNEL__) & ADC_CHANNEL_ID_NUMBER_MASK) >> ADC_CHANNEL_ID_NUMBER_BITOFFSET_POS)
1025 * @brief Helper macro to get ADC channel in literal format LL_ADC_CHANNEL_x
1026 * from number in decimal format.
1028 * __LL_ADC_DECIMAL_NB_TO_CHANNEL(4)
1029 * will return a data equivalent to "LL_ADC_CHANNEL_4".
1030 * @param __DECIMAL_NB__: Value between Min_Data=0 and Max_Data=18
1031 * @retval Returned value can be one of the following values:
1032 * @arg @ref LL_ADC_CHANNEL_0
1033 * @arg @ref LL_ADC_CHANNEL_1
1034 * @arg @ref LL_ADC_CHANNEL_2
1035 * @arg @ref LL_ADC_CHANNEL_3
1036 * @arg @ref LL_ADC_CHANNEL_4
1037 * @arg @ref LL_ADC_CHANNEL_5
1038 * @arg @ref LL_ADC_CHANNEL_6
1039 * @arg @ref LL_ADC_CHANNEL_7
1040 * @arg @ref LL_ADC_CHANNEL_8
1041 * @arg @ref LL_ADC_CHANNEL_9
1042 * @arg @ref LL_ADC_CHANNEL_10
1043 * @arg @ref LL_ADC_CHANNEL_11
1044 * @arg @ref LL_ADC_CHANNEL_12
1045 * @arg @ref LL_ADC_CHANNEL_13
1046 * @arg @ref LL_ADC_CHANNEL_14
1047 * @arg @ref LL_ADC_CHANNEL_15
1048 * @arg @ref LL_ADC_CHANNEL_16
1049 * @arg @ref LL_ADC_CHANNEL_17
1050 * @arg @ref LL_ADC_CHANNEL_VREFINT (1)
1051 * @arg @ref LL_ADC_CHANNEL_TEMPSENSOR (1)
1053 * (1) On STM32F1, parameter available only on ADC instance: ADC1.\n
1054 * (1) For ADC channel read back from ADC register,
1055 * comparison with internal channel parameter to be done
1056 * using helper macro @ref __LL_ADC_CHANNEL_INTERNAL_TO_EXTERNAL().
1058 #define __LL_ADC_DECIMAL_NB_TO_CHANNEL(__DECIMAL_NB__) \
1059 (((__DECIMAL_NB__) <= 9U) \
1061 ((__DECIMAL_NB__) << ADC_CHANNEL_ID_NUMBER_BITOFFSET_POS) | \
1062 (ADC_SMPR2_REGOFFSET | (((uint32_t) (3U * (__DECIMAL_NB__))) << ADC_CHANNEL_SMPx_BITOFFSET_POS)) \
1066 ((__DECIMAL_NB__) << ADC_CHANNEL_ID_NUMBER_BITOFFSET_POS) | \
1067 (ADC_SMPR1_REGOFFSET | (((uint32_t) (3U * ((__DECIMAL_NB__) - 10U))) << ADC_CHANNEL_SMPx_BITOFFSET_POS)) \
1072 * @brief Helper macro to determine whether the selected channel
1073 * corresponds to literal definitions of driver.
1074 * @note The different literal definitions of ADC channels are:
1075 * - ADC internal channel:
1076 * LL_ADC_CHANNEL_VREFINT, LL_ADC_CHANNEL_TEMPSENSOR, ...
1077 * - ADC external channel (channel connected to a GPIO pin):
1078 * LL_ADC_CHANNEL_1, LL_ADC_CHANNEL_2, ...
1079 * @note The channel parameter must be a value defined from literal
1080 * definition of a ADC internal channel (LL_ADC_CHANNEL_VREFINT,
1081 * LL_ADC_CHANNEL_TEMPSENSOR, ...),
1082 * ADC external channel (LL_ADC_CHANNEL_1, LL_ADC_CHANNEL_2, ...),
1083 * must not be a value from functions where a channel number is
1084 * returned from ADC registers,
1085 * because internal and external channels share the same channel
1086 * number in ADC registers. The differentiation is made only with
1087 * parameters definitions of driver.
1088 * @param __CHANNEL__ This parameter can be one of the following values:
1089 * @arg @ref LL_ADC_CHANNEL_0
1090 * @arg @ref LL_ADC_CHANNEL_1
1091 * @arg @ref LL_ADC_CHANNEL_2
1092 * @arg @ref LL_ADC_CHANNEL_3
1093 * @arg @ref LL_ADC_CHANNEL_4
1094 * @arg @ref LL_ADC_CHANNEL_5
1095 * @arg @ref LL_ADC_CHANNEL_6
1096 * @arg @ref LL_ADC_CHANNEL_7
1097 * @arg @ref LL_ADC_CHANNEL_8
1098 * @arg @ref LL_ADC_CHANNEL_9
1099 * @arg @ref LL_ADC_CHANNEL_10
1100 * @arg @ref LL_ADC_CHANNEL_11
1101 * @arg @ref LL_ADC_CHANNEL_12
1102 * @arg @ref LL_ADC_CHANNEL_13
1103 * @arg @ref LL_ADC_CHANNEL_14
1104 * @arg @ref LL_ADC_CHANNEL_15
1105 * @arg @ref LL_ADC_CHANNEL_16
1106 * @arg @ref LL_ADC_CHANNEL_17
1107 * @arg @ref LL_ADC_CHANNEL_VREFINT (1)
1108 * @arg @ref LL_ADC_CHANNEL_TEMPSENSOR (1)
1110 * (1) On STM32F1, parameter available only on ADC instance: ADC1.
1111 * @retval Value "0" if the channel corresponds to a parameter definition of a ADC external channel (channel connected to a GPIO pin).
1112 * Value "1" if the channel corresponds to a parameter definition of a ADC internal channel.
1114 #define __LL_ADC_IS_CHANNEL_INTERNAL(__CHANNEL__) \
1115 (((__CHANNEL__) & ADC_CHANNEL_ID_INTERNAL_CH_MASK) != 0U)
1118 * @brief Helper macro to convert a channel defined from parameter
1119 * definition of a ADC internal channel (LL_ADC_CHANNEL_VREFINT,
1120 * LL_ADC_CHANNEL_TEMPSENSOR, ...),
1121 * to its equivalent parameter definition of a ADC external channel
1122 * (LL_ADC_CHANNEL_1, LL_ADC_CHANNEL_2, ...).
1123 * @note The channel parameter can be, additionally to a value
1124 * defined from parameter definition of a ADC internal channel
1125 * (LL_ADC_CHANNEL_VREFINT, LL_ADC_CHANNEL_TEMPSENSOR, ...),
1126 * a value defined from parameter definition of
1127 * ADC external channel (LL_ADC_CHANNEL_1, LL_ADC_CHANNEL_2, ...)
1128 * or a value from functions where a channel number is returned
1129 * from ADC registers.
1130 * @param __CHANNEL__ This parameter can be one of the following values:
1131 * @arg @ref LL_ADC_CHANNEL_0
1132 * @arg @ref LL_ADC_CHANNEL_1
1133 * @arg @ref LL_ADC_CHANNEL_2
1134 * @arg @ref LL_ADC_CHANNEL_3
1135 * @arg @ref LL_ADC_CHANNEL_4
1136 * @arg @ref LL_ADC_CHANNEL_5
1137 * @arg @ref LL_ADC_CHANNEL_6
1138 * @arg @ref LL_ADC_CHANNEL_7
1139 * @arg @ref LL_ADC_CHANNEL_8
1140 * @arg @ref LL_ADC_CHANNEL_9
1141 * @arg @ref LL_ADC_CHANNEL_10
1142 * @arg @ref LL_ADC_CHANNEL_11
1143 * @arg @ref LL_ADC_CHANNEL_12
1144 * @arg @ref LL_ADC_CHANNEL_13
1145 * @arg @ref LL_ADC_CHANNEL_14
1146 * @arg @ref LL_ADC_CHANNEL_15
1147 * @arg @ref LL_ADC_CHANNEL_16
1148 * @arg @ref LL_ADC_CHANNEL_17
1149 * @arg @ref LL_ADC_CHANNEL_VREFINT (1)
1150 * @arg @ref LL_ADC_CHANNEL_TEMPSENSOR (1)
1152 * (1) On STM32F1, parameter available only on ADC instance: ADC1.
1153 * @retval Returned value can be one of the following values:
1154 * @arg @ref LL_ADC_CHANNEL_0
1155 * @arg @ref LL_ADC_CHANNEL_1
1156 * @arg @ref LL_ADC_CHANNEL_2
1157 * @arg @ref LL_ADC_CHANNEL_3
1158 * @arg @ref LL_ADC_CHANNEL_4
1159 * @arg @ref LL_ADC_CHANNEL_5
1160 * @arg @ref LL_ADC_CHANNEL_6
1161 * @arg @ref LL_ADC_CHANNEL_7
1162 * @arg @ref LL_ADC_CHANNEL_8
1163 * @arg @ref LL_ADC_CHANNEL_9
1164 * @arg @ref LL_ADC_CHANNEL_10
1165 * @arg @ref LL_ADC_CHANNEL_11
1166 * @arg @ref LL_ADC_CHANNEL_12
1167 * @arg @ref LL_ADC_CHANNEL_13
1168 * @arg @ref LL_ADC_CHANNEL_14
1169 * @arg @ref LL_ADC_CHANNEL_15
1170 * @arg @ref LL_ADC_CHANNEL_16
1171 * @arg @ref LL_ADC_CHANNEL_17
1173 #define __LL_ADC_CHANNEL_INTERNAL_TO_EXTERNAL(__CHANNEL__) \
1174 ((__CHANNEL__) & ~ADC_CHANNEL_ID_INTERNAL_CH_MASK)
1177 * @brief Helper macro to determine whether the internal channel
1178 * selected is available on the ADC instance selected.
1179 * @note The channel parameter must be a value defined from parameter
1180 * definition of a ADC internal channel (LL_ADC_CHANNEL_VREFINT,
1181 * LL_ADC_CHANNEL_TEMPSENSOR, ...),
1182 * must not be a value defined from parameter definition of
1183 * ADC external channel (LL_ADC_CHANNEL_1, LL_ADC_CHANNEL_2, ...)
1184 * or a value from functions where a channel number is
1185 * returned from ADC registers,
1186 * because internal and external channels share the same channel
1187 * number in ADC registers. The differentiation is made only with
1188 * parameters definitions of driver.
1189 * @param __ADC_INSTANCE__ ADC instance
1190 * @param __CHANNEL__ This parameter can be one of the following values:
1191 * @arg @ref LL_ADC_CHANNEL_VREFINT (1)
1192 * @arg @ref LL_ADC_CHANNEL_TEMPSENSOR (1)
1194 * (1) On STM32F1, parameter available only on ADC instance: ADC1.
1195 * @retval Value "0" if the internal channel selected is not available on the ADC instance selected.
1196 * Value "1" if the internal channel selected is available on the ADC instance selected.
1198 #define __LL_ADC_IS_CHANNEL_INTERNAL_AVAILABLE(__ADC_INSTANCE__, __CHANNEL__) \
1199 (((__ADC_INSTANCE__) == ADC1) \
1201 ((__CHANNEL__) == LL_ADC_CHANNEL_VREFINT) || \
1202 ((__CHANNEL__) == LL_ADC_CHANNEL_TEMPSENSOR) \
1209 * @brief Helper macro to define ADC analog watchdog parameter:
1210 * define a single channel to monitor with analog watchdog
1211 * from sequencer channel and groups definition.
1212 * @note To be used with function @ref LL_ADC_SetAnalogWDMonitChannels().
1214 * LL_ADC_SetAnalogWDMonitChannels(
1215 * ADC1, LL_ADC_AWD1,
1216 * __LL_ADC_ANALOGWD_CHANNEL_GROUP(LL_ADC_CHANNEL4, LL_ADC_GROUP_REGULAR))
1217 * @param __CHANNEL__ This parameter can be one of the following values:
1218 * @arg @ref LL_ADC_CHANNEL_0
1219 * @arg @ref LL_ADC_CHANNEL_1
1220 * @arg @ref LL_ADC_CHANNEL_2
1221 * @arg @ref LL_ADC_CHANNEL_3
1222 * @arg @ref LL_ADC_CHANNEL_4
1223 * @arg @ref LL_ADC_CHANNEL_5
1224 * @arg @ref LL_ADC_CHANNEL_6
1225 * @arg @ref LL_ADC_CHANNEL_7
1226 * @arg @ref LL_ADC_CHANNEL_8
1227 * @arg @ref LL_ADC_CHANNEL_9
1228 * @arg @ref LL_ADC_CHANNEL_10
1229 * @arg @ref LL_ADC_CHANNEL_11
1230 * @arg @ref LL_ADC_CHANNEL_12
1231 * @arg @ref LL_ADC_CHANNEL_13
1232 * @arg @ref LL_ADC_CHANNEL_14
1233 * @arg @ref LL_ADC_CHANNEL_15
1234 * @arg @ref LL_ADC_CHANNEL_16
1235 * @arg @ref LL_ADC_CHANNEL_17
1236 * @arg @ref LL_ADC_CHANNEL_VREFINT (1)
1237 * @arg @ref LL_ADC_CHANNEL_TEMPSENSOR (1)
1239 * (1) On STM32F1, parameter available only on ADC instance: ADC1.\n
1240 * (1) For ADC channel read back from ADC register,
1241 * comparison with internal channel parameter to be done
1242 * using helper macro @ref __LL_ADC_CHANNEL_INTERNAL_TO_EXTERNAL().
1243 * @param __GROUP__ This parameter can be one of the following values:
1244 * @arg @ref LL_ADC_GROUP_REGULAR
1245 * @arg @ref LL_ADC_GROUP_INJECTED
1246 * @arg @ref LL_ADC_GROUP_REGULAR_INJECTED
1247 * @retval Returned value can be one of the following values:
1248 * @arg @ref LL_ADC_AWD_DISABLE
1249 * @arg @ref LL_ADC_AWD_ALL_CHANNELS_REG
1250 * @arg @ref LL_ADC_AWD_ALL_CHANNELS_INJ
1251 * @arg @ref LL_ADC_AWD_ALL_CHANNELS_REG_INJ
1252 * @arg @ref LL_ADC_AWD_CHANNEL_0_REG
1253 * @arg @ref LL_ADC_AWD_CHANNEL_0_INJ
1254 * @arg @ref LL_ADC_AWD_CHANNEL_0_REG_INJ
1255 * @arg @ref LL_ADC_AWD_CHANNEL_1_REG
1256 * @arg @ref LL_ADC_AWD_CHANNEL_1_INJ
1257 * @arg @ref LL_ADC_AWD_CHANNEL_1_REG_INJ
1258 * @arg @ref LL_ADC_AWD_CHANNEL_2_REG
1259 * @arg @ref LL_ADC_AWD_CHANNEL_2_INJ
1260 * @arg @ref LL_ADC_AWD_CHANNEL_2_REG_INJ
1261 * @arg @ref LL_ADC_AWD_CHANNEL_3_REG
1262 * @arg @ref LL_ADC_AWD_CHANNEL_3_INJ
1263 * @arg @ref LL_ADC_AWD_CHANNEL_3_REG_INJ
1264 * @arg @ref LL_ADC_AWD_CHANNEL_4_REG
1265 * @arg @ref LL_ADC_AWD_CHANNEL_4_INJ
1266 * @arg @ref LL_ADC_AWD_CHANNEL_4_REG_INJ
1267 * @arg @ref LL_ADC_AWD_CHANNEL_5_REG
1268 * @arg @ref LL_ADC_AWD_CHANNEL_5_INJ
1269 * @arg @ref LL_ADC_AWD_CHANNEL_5_REG_INJ
1270 * @arg @ref LL_ADC_AWD_CHANNEL_6_REG
1271 * @arg @ref LL_ADC_AWD_CHANNEL_6_INJ
1272 * @arg @ref LL_ADC_AWD_CHANNEL_6_REG_INJ
1273 * @arg @ref LL_ADC_AWD_CHANNEL_7_REG
1274 * @arg @ref LL_ADC_AWD_CHANNEL_7_INJ
1275 * @arg @ref LL_ADC_AWD_CHANNEL_7_REG_INJ
1276 * @arg @ref LL_ADC_AWD_CHANNEL_8_REG
1277 * @arg @ref LL_ADC_AWD_CHANNEL_8_INJ
1278 * @arg @ref LL_ADC_AWD_CHANNEL_8_REG_INJ
1279 * @arg @ref LL_ADC_AWD_CHANNEL_9_REG
1280 * @arg @ref LL_ADC_AWD_CHANNEL_9_INJ
1281 * @arg @ref LL_ADC_AWD_CHANNEL_9_REG_INJ
1282 * @arg @ref LL_ADC_AWD_CHANNEL_10_REG
1283 * @arg @ref LL_ADC_AWD_CHANNEL_10_INJ
1284 * @arg @ref LL_ADC_AWD_CHANNEL_10_REG_INJ
1285 * @arg @ref LL_ADC_AWD_CHANNEL_11_REG
1286 * @arg @ref LL_ADC_AWD_CHANNEL_11_INJ
1287 * @arg @ref LL_ADC_AWD_CHANNEL_11_REG_INJ
1288 * @arg @ref LL_ADC_AWD_CHANNEL_12_REG
1289 * @arg @ref LL_ADC_AWD_CHANNEL_12_INJ
1290 * @arg @ref LL_ADC_AWD_CHANNEL_12_REG_INJ
1291 * @arg @ref LL_ADC_AWD_CHANNEL_13_REG
1292 * @arg @ref LL_ADC_AWD_CHANNEL_13_INJ
1293 * @arg @ref LL_ADC_AWD_CHANNEL_13_REG_INJ
1294 * @arg @ref LL_ADC_AWD_CHANNEL_14_REG
1295 * @arg @ref LL_ADC_AWD_CHANNEL_14_INJ
1296 * @arg @ref LL_ADC_AWD_CHANNEL_14_REG_INJ
1297 * @arg @ref LL_ADC_AWD_CHANNEL_15_REG
1298 * @arg @ref LL_ADC_AWD_CHANNEL_15_INJ
1299 * @arg @ref LL_ADC_AWD_CHANNEL_15_REG_INJ
1300 * @arg @ref LL_ADC_AWD_CHANNEL_16_REG
1301 * @arg @ref LL_ADC_AWD_CHANNEL_16_INJ
1302 * @arg @ref LL_ADC_AWD_CHANNEL_16_REG_INJ
1303 * @arg @ref LL_ADC_AWD_CHANNEL_17_REG
1304 * @arg @ref LL_ADC_AWD_CHANNEL_17_INJ
1305 * @arg @ref LL_ADC_AWD_CHANNEL_17_REG_INJ
1306 * @arg @ref LL_ADC_AWD_CH_VREFINT_REG (1)
1307 * @arg @ref LL_ADC_AWD_CH_VREFINT_INJ (1)
1308 * @arg @ref LL_ADC_AWD_CH_VREFINT_REG_INJ (1)
1309 * @arg @ref LL_ADC_AWD_CH_TEMPSENSOR_REG (1)
1310 * @arg @ref LL_ADC_AWD_CH_TEMPSENSOR_INJ (1)
1311 * @arg @ref LL_ADC_AWD_CH_TEMPSENSOR_REG_INJ (1)
1313 * (1) On STM32F1, parameter available only on ADC instance: ADC1.
1315 #define __LL_ADC_ANALOGWD_CHANNEL_GROUP(__CHANNEL__, __GROUP__) \
1316 (((__GROUP__) == LL_ADC_GROUP_REGULAR) \
1317 ? (((__CHANNEL__) & ADC_CHANNEL_ID_MASK) | ADC_CR1_AWDEN | ADC_CR1_AWDSGL) \
1319 ((__GROUP__) == LL_ADC_GROUP_INJECTED) \
1320 ? (((__CHANNEL__) & ADC_CHANNEL_ID_MASK) | ADC_CR1_JAWDEN | ADC_CR1_AWDSGL) \
1322 (((__CHANNEL__) & ADC_CHANNEL_ID_MASK) | ADC_CR1_JAWDEN | ADC_CR1_AWDEN | ADC_CR1_AWDSGL) \
1326 * @brief Helper macro to set the value of ADC analog watchdog threshold high
1327 * or low in function of ADC resolution, when ADC resolution is
1328 * different of 12 bits.
1329 * @note To be used with function @ref LL_ADC_SetAnalogWDThresholds().
1330 * Example, with a ADC resolution of 8 bits, to set the value of
1331 * analog watchdog threshold high (on 8 bits):
1332 * LL_ADC_SetAnalogWDThresholds
1334 * __LL_ADC_ANALOGWD_SET_THRESHOLD_RESOLUTION(LL_ADC_RESOLUTION_8B, <threshold_value_8_bits>)
1336 * @param __ADC_RESOLUTION__ This parameter can be one of the following values:
1337 * @arg @ref LL_ADC_RESOLUTION_12B
1338 * @param __AWD_THRESHOLD__ Value between Min_Data=0x000 and Max_Data=0xFFF
1339 * @retval Value between Min_Data=0x000 and Max_Data=0xFFF
1341 /* Note: On this STM32 serie, ADC is fixed to resolution 12 bits. */
1342 /* This macro has been kept anyway for compatibility with other */
1343 /* STM32 families featuring different ADC resolutions. */
1344 #define __LL_ADC_ANALOGWD_SET_THRESHOLD_RESOLUTION(__ADC_RESOLUTION__, __AWD_THRESHOLD__) \
1345 ((__AWD_THRESHOLD__) << (0U))
1348 * @brief Helper macro to get the value of ADC analog watchdog threshold high
1349 * or low in function of ADC resolution, when ADC resolution is
1350 * different of 12 bits.
1351 * @note To be used with function @ref LL_ADC_GetAnalogWDThresholds().
1352 * Example, with a ADC resolution of 8 bits, to get the value of
1353 * analog watchdog threshold high (on 8 bits):
1354 * < threshold_value_6_bits > = __LL_ADC_ANALOGWD_GET_THRESHOLD_RESOLUTION
1355 * (LL_ADC_RESOLUTION_8B,
1356 * LL_ADC_GetAnalogWDThresholds(<ADCx param>, LL_ADC_AWD_THRESHOLD_HIGH)
1358 * @param __ADC_RESOLUTION__ This parameter can be one of the following values:
1359 * @arg @ref LL_ADC_RESOLUTION_12B
1360 * @param __AWD_THRESHOLD_12_BITS__ Value between Min_Data=0x000 and Max_Data=0xFFF
1361 * @retval Value between Min_Data=0x000 and Max_Data=0xFFF
1363 /* Note: On this STM32 serie, ADC is fixed to resolution 12 bits. */
1364 /* This macro has been kept anyway for compatibility with other */
1365 /* STM32 families featuring different ADC resolutions. */
1366 #define __LL_ADC_ANALOGWD_GET_THRESHOLD_RESOLUTION(__ADC_RESOLUTION__, __AWD_THRESHOLD_12_BITS__) \
1367 (__AWD_THRESHOLD_12_BITS__)
1369 #if defined(ADC_MULTIMODE_SUPPORT)
1371 * @brief Helper macro to get the ADC multimode conversion data of ADC master
1372 * or ADC slave from raw value with both ADC conversion data concatenated.
1373 * @note This macro is intended to be used when multimode transfer by DMA
1375 * In this case the transferred data need to processed with this macro
1376 * to separate the conversion data of ADC master and ADC slave.
1377 * @param __ADC_MULTI_MASTER_SLAVE__ This parameter can be one of the following values:
1378 * @arg @ref LL_ADC_MULTI_MASTER
1379 * @arg @ref LL_ADC_MULTI_SLAVE
1380 * @param __ADC_MULTI_CONV_DATA__ Value between Min_Data=0x000 and Max_Data=0xFFF
1381 * @retval Value between Min_Data=0x000 and Max_Data=0xFFF
1383 #define __LL_ADC_MULTI_CONV_DATA_MASTER_SLAVE(__ADC_MULTI_MASTER_SLAVE__, __ADC_MULTI_CONV_DATA__) \
1384 (((__ADC_MULTI_CONV_DATA__) >> POSITION_VAL((__ADC_MULTI_MASTER_SLAVE__))) & ADC_DR_DATA)
1388 * @brief Helper macro to select the ADC common instance
1389 * to which is belonging the selected ADC instance.
1390 * @note ADC common register instance can be used for:
1391 * - Set parameters common to several ADC instances
1392 * - Multimode (for devices with several ADC instances)
1393 * Refer to functions having argument "ADCxy_COMMON" as parameter.
1394 * @note On STM32F1, there is no common ADC instance.
1395 * However, ADC instance ADC1 has a role of common ADC instance
1396 * for ADC1 and ADC2:
1397 * this instance is used to manage internal channels
1398 * and multimode (these features are managed in ADC common
1399 * instances on some other STM32 devices).
1400 * ADC instance ADC3 (if available on the selected device)
1401 * has no ADC common instance.
1402 * @param __ADCx__ ADC instance
1403 * @retval ADC common register instance
1405 #if defined(ADC1) && defined(ADC2) && defined(ADC3)
1406 #define __LL_ADC_COMMON_INSTANCE(__ADCx__) \
1407 ((((__ADCx__) == ADC1) || ((__ADCx__) == ADC2)) \
1416 #elif defined(ADC1) && defined(ADC2)
1417 #define __LL_ADC_COMMON_INSTANCE(__ADCx__) \
1420 #define __LL_ADC_COMMON_INSTANCE(__ADCx__) \
1425 * @brief Helper macro to check if all ADC instances sharing the same
1426 * ADC common instance are disabled.
1427 * @note This check is required by functions with setting conditioned to
1429 * All ADC instances of the ADC common group must be disabled.
1430 * Refer to functions having argument "ADCxy_COMMON" as parameter.
1431 * @note On devices with only 1 ADC common instance, parameter of this macro
1432 * is useless and can be ignored (parameter kept for compatibility
1433 * with devices featuring several ADC common instances).
1434 * @note On STM32F1, there is no common ADC instance.
1435 * However, ADC instance ADC1 has a role of common ADC instance
1436 * for ADC1 and ADC2:
1437 * this instance is used to manage internal channels
1438 * and multimode (these features are managed in ADC common
1439 * instances on some other STM32 devices).
1440 * ADC instance ADC3 (if available on the selected device)
1441 * has no ADC common instance.
1442 * @param __ADCXY_COMMON__ ADC common instance
1443 * (can be set directly from CMSIS definition or by using helper macro @ref __LL_ADC_COMMON_INSTANCE() )
1444 * @retval Value "0" if all ADC instances sharing the same ADC common instance
1446 * Value "1" if at least one ADC instance sharing the same ADC common instance
1449 #if defined(ADC1) && defined(ADC2) && defined(ADC3)
1450 #define __LL_ADC_IS_ENABLED_ALL_COMMON_INSTANCE(__ADCXY_COMMON__) \
1451 (((__ADCXY_COMMON__) == ADC12_COMMON) \
1453 (LL_ADC_IsEnabled(ADC1) | \
1454 LL_ADC_IsEnabled(ADC2) ) \
1458 LL_ADC_IsEnabled(ADC3) \
1461 #elif defined(ADC1) && defined(ADC2)
1462 #define __LL_ADC_IS_ENABLED_ALL_COMMON_INSTANCE(__ADCXY_COMMON__) \
1463 (LL_ADC_IsEnabled(ADC1) | \
1464 LL_ADC_IsEnabled(ADC2) )
1466 #define __LL_ADC_IS_ENABLED_ALL_COMMON_INSTANCE(__ADCXY_COMMON__) \
1467 LL_ADC_IsEnabled(ADC1)
1471 * @brief Helper macro to define the ADC conversion data full-scale digital
1472 * value corresponding to the selected ADC resolution.
1473 * @note ADC conversion data full-scale corresponds to voltage range
1474 * determined by analog voltage references Vref+ and Vref-
1475 * (refer to reference manual).
1476 * @param __ADC_RESOLUTION__ This parameter can be one of the following values:
1477 * @arg @ref LL_ADC_RESOLUTION_12B
1478 * @retval ADC conversion data equivalent voltage value (unit: mVolt)
1480 #define __LL_ADC_DIGITAL_SCALE(__ADC_RESOLUTION__) \
1485 * @brief Helper macro to calculate the voltage (unit: mVolt)
1486 * corresponding to a ADC conversion data (unit: digital value).
1487 * @note Analog reference voltage (Vref+) must be known from
1488 * user board environment or can be calculated using ADC measurement.
1489 * @param __VREFANALOG_VOLTAGE__ Analog reference voltage (unit: mV)
1490 * @param __ADC_DATA__ ADC conversion data (resolution 12 bits)
1491 * (unit: digital value).
1492 * @param __ADC_RESOLUTION__ This parameter can be one of the following values:
1493 * @arg @ref LL_ADC_RESOLUTION_12B
1494 * @retval ADC conversion data equivalent voltage value (unit: mVolt)
1496 #define __LL_ADC_CALC_DATA_TO_VOLTAGE(__VREFANALOG_VOLTAGE__,\
1498 __ADC_RESOLUTION__) \
1499 ((__ADC_DATA__) * (__VREFANALOG_VOLTAGE__) \
1500 / __LL_ADC_DIGITAL_SCALE(__ADC_RESOLUTION__) \
1505 * @brief Helper macro to calculate the temperature (unit: degree Celsius)
1506 * from ADC conversion data of internal temperature sensor.
1507 * @note Computation is using temperature sensor typical values
1508 * (refer to device datasheet).
1509 * @note Calculation formula:
1510 * Temperature = (TS_TYP_CALx_VOLT(uV) - TS_ADC_DATA * Conversion_uV)
1511 * / Avg_Slope + CALx_TEMP
1512 * with TS_ADC_DATA = temperature sensor raw data measured by ADC
1513 * (unit: digital value)
1514 * Avg_Slope = temperature sensor slope
1515 * (unit: uV/Degree Celsius)
1516 * TS_TYP_CALx_VOLT = temperature sensor digital value at
1517 * temperature CALx_TEMP (unit: mV)
1518 * Caution: Calculation relevancy under reserve the temperature sensor
1519 * of the current device has characteristics in line with
1520 * datasheet typical values.
1521 * If temperature sensor calibration values are available on
1522 * on this device (presence of macro __LL_ADC_CALC_TEMPERATURE()),
1523 * temperature calculation will be more accurate using
1524 * helper macro @ref __LL_ADC_CALC_TEMPERATURE().
1525 * @note As calculation input, the analog reference voltage (Vref+) must be
1526 * defined as it impacts the ADC LSB equivalent voltage.
1527 * @note Analog reference voltage (Vref+) must be known from
1528 * user board environment or can be calculated using ADC measurement.
1529 * @note ADC measurement data must correspond to a resolution of 12bits
1530 * (full scale digital value 4095). If not the case, the data must be
1531 * preliminarily rescaled to an equivalent resolution of 12 bits.
1532 * @param __TEMPSENSOR_TYP_AVGSLOPE__ Device datasheet data: Temperature sensor slope typical value (unit: uV/DegCelsius).
1533 * On STM32F1, refer to device datasheet parameter "Avg_Slope".
1534 * @param __TEMPSENSOR_TYP_CALX_V__ Device datasheet data: Temperature sensor voltage typical value (at temperature and Vref+ defined in parameters below) (unit: mV).
1535 * On STM32F1, refer to device datasheet parameter "V25".
1536 * @param __TEMPSENSOR_CALX_TEMP__ Device datasheet data: Temperature at which temperature sensor voltage (see parameter above) is corresponding (unit: mV)
1537 * @param __VREFANALOG_VOLTAGE__ Analog voltage reference (Vref+) voltage (unit: mV)
1538 * @param __TEMPSENSOR_ADC_DATA__ ADC conversion data of internal temperature sensor (unit: digital value).
1539 * @param __ADC_RESOLUTION__ ADC resolution at which internal temperature sensor voltage has been measured.
1540 * This parameter can be one of the following values:
1541 * @arg @ref LL_ADC_RESOLUTION_12B
1542 * @retval Temperature (unit: degree Celsius)
1544 #define __LL_ADC_CALC_TEMPERATURE_TYP_PARAMS(__TEMPSENSOR_TYP_AVGSLOPE__,\
1545 __TEMPSENSOR_TYP_CALX_V__,\
1546 __TEMPSENSOR_CALX_TEMP__,\
1547 __VREFANALOG_VOLTAGE__,\
1548 __TEMPSENSOR_ADC_DATA__,\
1549 __ADC_RESOLUTION__) \
1551 (int32_t)(((__TEMPSENSOR_TYP_CALX_V__)) \
1554 (int32_t)((((__TEMPSENSOR_ADC_DATA__) * (__VREFANALOG_VOLTAGE__)) \
1555 / __LL_ADC_DIGITAL_SCALE(__ADC_RESOLUTION__)) \
1558 ) / (__TEMPSENSOR_TYP_AVGSLOPE__) \
1559 ) + (__TEMPSENSOR_CALX_TEMP__) \
1571 /* Exported functions --------------------------------------------------------*/
1572 /** @defgroup ADC_LL_Exported_Functions ADC Exported Functions
1576 /** @defgroup ADC_LL_EF_DMA_Management ADC DMA management
1579 /* Note: LL ADC functions to set DMA transfer are located into sections of */
1580 /* configuration of ADC instance, groups and multimode (if available): */
1581 /* @ref LL_ADC_REG_SetDMATransfer(), ... */
1584 * @brief Function to help to configure DMA transfer from ADC: retrieve the
1585 * ADC register address from ADC instance and a list of ADC registers
1586 * intended to be used (most commonly) with DMA transfer.
1587 * @note These ADC registers are data registers:
1588 * when ADC conversion data is available in ADC data registers,
1589 * ADC generates a DMA transfer request.
1590 * @note This macro is intended to be used with LL DMA driver, refer to
1591 * function "LL_DMA_ConfigAddresses()".
1593 * LL_DMA_ConfigAddresses(DMA1,
1595 * LL_ADC_DMA_GetRegAddr(ADC1, LL_ADC_DMA_REG_REGULAR_DATA),
1596 * (uint32_t)&< array or variable >,
1597 * LL_DMA_DIRECTION_PERIPH_TO_MEMORY);
1598 * @note For devices with several ADC: in multimode, some devices
1599 * use a different data register outside of ADC instance scope
1600 * (common data register). This macro manages this register difference,
1601 * only ADC instance has to be set as parameter.
1602 * @note On STM32F1, only ADC instances ADC1 and ADC3 have DMA transfer
1603 * capability, not ADC2 (ADC2 and ADC3 instances not available on
1605 * @note On STM32F1, multimode can be used only with ADC1 and ADC2, not ADC3.
1606 * Therefore, the corresponding parameter of data transfer
1607 * for multimode can be used only with ADC1 and ADC2.
1608 * (ADC2 and ADC3 instances not available on all devices).
1609 * @rmtoll DR DATA LL_ADC_DMA_GetRegAddr
1610 * @param ADCx ADC instance
1611 * @param Register This parameter can be one of the following values:
1612 * @arg @ref LL_ADC_DMA_REG_REGULAR_DATA
1613 * @arg @ref LL_ADC_DMA_REG_REGULAR_DATA_MULTI (1)
1615 * (1) Available on devices with several ADC instances.
1616 * @retval ADC register address
1618 #if defined(ADC_MULTIMODE_SUPPORT)
1619 __STATIC_INLINE
uint32_t LL_ADC_DMA_GetRegAddr(ADC_TypeDef
*ADCx
, uint32_t Register
)
1621 register uint32_t data_reg_addr
= 0U;
1623 if (Register
== LL_ADC_DMA_REG_REGULAR_DATA
)
1625 /* Retrieve address of register DR */
1626 data_reg_addr
= (uint32_t)&(ADCx
->DR
);
1628 else /* (Register == LL_ADC_DMA_REG_REGULAR_DATA_MULTI) */
1630 /* Retrieve address of register of multimode data */
1631 data_reg_addr
= (uint32_t)&(ADC12_COMMON
->DR
);
1634 return data_reg_addr
;
1637 __STATIC_INLINE
uint32_t LL_ADC_DMA_GetRegAddr(ADC_TypeDef
*ADCx
, uint32_t Register
)
1639 /* Retrieve address of register DR */
1640 return (uint32_t)&(ADCx
->DR
);
1648 /** @defgroup ADC_LL_EF_Configuration_ADC_Common Configuration of ADC hierarchical scope: common to several ADC instances
1653 * @brief Set parameter common to several ADC: measurement path to internal
1654 * channels (VrefInt, temperature sensor, ...).
1655 * @note One or several values can be selected.
1656 * Example: (LL_ADC_PATH_INTERNAL_VREFINT |
1657 * LL_ADC_PATH_INTERNAL_TEMPSENSOR)
1658 * @note Stabilization time of measurement path to internal channel:
1659 * After enabling internal paths, before starting ADC conversion,
1660 * a delay is required for internal voltage reference and
1661 * temperature sensor stabilization time.
1662 * Refer to device datasheet.
1663 * Refer to literal @ref LL_ADC_DELAY_TEMPSENSOR_STAB_US.
1664 * @note ADC internal channel sampling time constraint:
1665 * For ADC conversion of internal channels,
1666 * a sampling time minimum value is required.
1667 * Refer to device datasheet.
1668 * @rmtoll CR2 TSVREFE LL_ADC_SetCommonPathInternalCh
1669 * @param ADCxy_COMMON ADC common instance
1670 * (can be set directly from CMSIS definition or by using helper macro @ref __LL_ADC_COMMON_INSTANCE() )
1671 * @param PathInternal This parameter can be a combination of the following values:
1672 * @arg @ref LL_ADC_PATH_INTERNAL_NONE
1673 * @arg @ref LL_ADC_PATH_INTERNAL_VREFINT
1674 * @arg @ref LL_ADC_PATH_INTERNAL_TEMPSENSOR
1677 __STATIC_INLINE
void LL_ADC_SetCommonPathInternalCh(ADC_Common_TypeDef
*ADCxy_COMMON
, uint32_t PathInternal
)
1679 MODIFY_REG(ADCxy_COMMON
->CR2
, (ADC_CR2_TSVREFE
), PathInternal
);
1683 * @brief Get parameter common to several ADC: measurement path to internal
1684 * channels (VrefInt, temperature sensor, ...).
1685 * @note One or several values can be selected.
1686 * Example: (LL_ADC_PATH_INTERNAL_VREFINT |
1687 * LL_ADC_PATH_INTERNAL_TEMPSENSOR)
1688 * @rmtoll CR2 TSVREFE LL_ADC_GetCommonPathInternalCh
1689 * @param ADCxy_COMMON ADC common instance
1690 * (can be set directly from CMSIS definition or by using helper macro @ref __LL_ADC_COMMON_INSTANCE() )
1691 * @retval Returned value can be a combination of the following values:
1692 * @arg @ref LL_ADC_PATH_INTERNAL_NONE
1693 * @arg @ref LL_ADC_PATH_INTERNAL_VREFINT
1694 * @arg @ref LL_ADC_PATH_INTERNAL_TEMPSENSOR
1696 __STATIC_INLINE
uint32_t LL_ADC_GetCommonPathInternalCh(ADC_Common_TypeDef
*ADCxy_COMMON
)
1698 return (uint32_t)(READ_BIT(ADCxy_COMMON
->CR2
, ADC_CR2_TSVREFE
));
1705 /** @defgroup ADC_LL_EF_Configuration_ADC_Instance Configuration of ADC hierarchical scope: ADC instance
1710 * @brief Set ADC conversion data alignment.
1711 * @note Refer to reference manual for alignments formats
1712 * dependencies to ADC resolutions.
1713 * @rmtoll CR2 ALIGN LL_ADC_SetDataAlignment
1714 * @param ADCx ADC instance
1715 * @param DataAlignment This parameter can be one of the following values:
1716 * @arg @ref LL_ADC_DATA_ALIGN_RIGHT
1717 * @arg @ref LL_ADC_DATA_ALIGN_LEFT
1720 __STATIC_INLINE
void LL_ADC_SetDataAlignment(ADC_TypeDef
*ADCx
, uint32_t DataAlignment
)
1722 MODIFY_REG(ADCx
->CR2
, ADC_CR2_ALIGN
, DataAlignment
);
1726 * @brief Get ADC conversion data alignment.
1727 * @note Refer to reference manual for alignments formats
1728 * dependencies to ADC resolutions.
1729 * @rmtoll CR2 ALIGN LL_ADC_SetDataAlignment
1730 * @param ADCx ADC instance
1731 * @retval Returned value can be one of the following values:
1732 * @arg @ref LL_ADC_DATA_ALIGN_RIGHT
1733 * @arg @ref LL_ADC_DATA_ALIGN_LEFT
1735 __STATIC_INLINE
uint32_t LL_ADC_GetDataAlignment(ADC_TypeDef
*ADCx
)
1737 return (uint32_t)(READ_BIT(ADCx
->CR2
, ADC_CR2_ALIGN
));
1741 * @brief Set ADC sequencers scan mode, for all ADC groups
1742 * (group regular, group injected).
1743 * @note According to sequencers scan mode :
1744 * - If disabled: ADC conversion is performed in unitary conversion
1745 * mode (one channel converted, that defined in rank 1).
1746 * Configuration of sequencers of all ADC groups
1747 * (sequencer scan length, ...) is discarded: equivalent to
1748 * scan length of 1 rank.
1749 * - If enabled: ADC conversions are performed in sequence conversions
1750 * mode, according to configuration of sequencers of
1751 * each ADC group (sequencer scan length, ...).
1752 * Refer to function @ref LL_ADC_REG_SetSequencerLength()
1753 * and to function @ref LL_ADC_INJ_SetSequencerLength().
1754 * @rmtoll CR1 SCAN LL_ADC_SetSequencersScanMode
1755 * @param ADCx ADC instance
1756 * @param ScanMode This parameter can be one of the following values:
1757 * @arg @ref LL_ADC_SEQ_SCAN_DISABLE
1758 * @arg @ref LL_ADC_SEQ_SCAN_ENABLE
1761 __STATIC_INLINE
void LL_ADC_SetSequencersScanMode(ADC_TypeDef
*ADCx
, uint32_t ScanMode
)
1763 MODIFY_REG(ADCx
->CR1
, ADC_CR1_SCAN
, ScanMode
);
1767 * @brief Get ADC sequencers scan mode, for all ADC groups
1768 * (group regular, group injected).
1769 * @note According to sequencers scan mode :
1770 * - If disabled: ADC conversion is performed in unitary conversion
1771 * mode (one channel converted, that defined in rank 1).
1772 * Configuration of sequencers of all ADC groups
1773 * (sequencer scan length, ...) is discarded: equivalent to
1774 * scan length of 1 rank.
1775 * - If enabled: ADC conversions are performed in sequence conversions
1776 * mode, according to configuration of sequencers of
1777 * each ADC group (sequencer scan length, ...).
1778 * Refer to function @ref LL_ADC_REG_SetSequencerLength()
1779 * and to function @ref LL_ADC_INJ_SetSequencerLength().
1780 * @rmtoll CR1 SCAN LL_ADC_GetSequencersScanMode
1781 * @param ADCx ADC instance
1782 * @retval Returned value can be one of the following values:
1783 * @arg @ref LL_ADC_SEQ_SCAN_DISABLE
1784 * @arg @ref LL_ADC_SEQ_SCAN_ENABLE
1786 __STATIC_INLINE
uint32_t LL_ADC_GetSequencersScanMode(ADC_TypeDef
*ADCx
)
1788 return (uint32_t)(READ_BIT(ADCx
->CR1
, ADC_CR1_SCAN
));
1795 /** @defgroup ADC_LL_EF_Configuration_ADC_Group_Regular Configuration of ADC hierarchical scope: group regular
1800 * @brief Set ADC group regular conversion trigger source:
1801 * internal (SW start) or from external IP (timer event,
1802 * external interrupt line).
1803 * @note On this STM32 serie, external trigger is set with trigger polarity:
1804 * rising edge (only trigger polarity available on this STM32 serie).
1805 * @note Availability of parameters of trigger sources from timer
1806 * depends on timers availability on the selected device.
1807 * @rmtoll CR2 EXTSEL LL_ADC_REG_SetTriggerSource
1808 * @param ADCx ADC instance
1809 * @param TriggerSource This parameter can be one of the following values:
1810 * @arg @ref LL_ADC_REG_TRIG_SOFTWARE
1811 * @arg @ref LL_ADC_REG_TRIG_EXT_TIM1_CH3 (1)
1812 * @arg @ref LL_ADC_REG_TRIG_EXT_TIM1_CH1 (2)
1813 * @arg @ref LL_ADC_REG_TRIG_EXT_TIM1_CH2 (2)
1814 * @arg @ref LL_ADC_REG_TRIG_EXT_TIM2_CH2 (2)
1815 * @arg @ref LL_ADC_REG_TRIG_EXT_TIM3_TRGO (2)
1816 * @arg @ref LL_ADC_REG_TRIG_EXT_TIM4_CH4 (2)
1817 * @arg @ref LL_ADC_REG_TRIG_EXT_EXTI_LINE11 (2)
1818 * @arg @ref LL_ADC_REG_TRIG_EXT_TIM8_TRGO (2)(4)
1819 * @arg @ref LL_ADC_REG_TRIG_EXT_TIM8_TRGO_ADC3 (3)
1820 * @arg @ref LL_ADC_REG_TRIG_EXT_TIM3_CH1 (3)
1821 * @arg @ref LL_ADC_REG_TRIG_EXT_TIM2_CH3 (3)
1822 * @arg @ref LL_ADC_REG_TRIG_EXT_TIM8_CH1 (3)
1823 * @arg @ref LL_ADC_REG_TRIG_EXT_TIM8_TRGO (3)
1824 * @arg @ref LL_ADC_REG_TRIG_EXT_TIM5_CH1 (3)
1825 * @arg @ref LL_ADC_REG_TRIG_EXT_TIM5_CH3 (3)
1827 * (1) On STM32F1, parameter available on all ADC instances: ADC1, ADC2, ADC3 (for ADC instances ADCx available on the selected device).\n
1828 * (2) On STM32F1, parameter available only on ADC instances: ADC1, ADC2 (for ADC instances ADCx available on the selected device).\n
1829 * (3) On STM32F1, parameter available only on ADC instances: ADC3 (for ADC instances ADCx available on the selected device).\n
1830 * (4) On STM32F1, parameter available only on high-density and XL-density devices. A remap of trigger must be done at top level (refer to AFIO peripheral).
1833 __STATIC_INLINE
void LL_ADC_REG_SetTriggerSource(ADC_TypeDef
*ADCx
, uint32_t TriggerSource
)
1835 /* Note: On this STM32 serie, ADC group regular external trigger edge */
1836 /* is used to perform a ADC conversion start. */
1837 /* This function does not set external trigger edge. */
1838 /* This feature is set using function */
1839 /* @ref LL_ADC_REG_StartConversionExtTrig(). */
1840 MODIFY_REG(ADCx
->CR2
, ADC_CR2_EXTSEL
, (TriggerSource
& ADC_CR2_EXTSEL
));
1844 * @brief Get ADC group regular conversion trigger source:
1845 * internal (SW start) or from external IP (timer event,
1846 * external interrupt line).
1847 * @note To determine whether group regular trigger source is
1848 * internal (SW start) or external, without detail
1849 * of which peripheral is selected as external trigger,
1851 * "if(LL_ADC_REG_GetTriggerSource(ADC1) == LL_ADC_REG_TRIG_SOFTWARE)")
1852 * use function @ref LL_ADC_REG_IsTriggerSourceSWStart.
1853 * @note Availability of parameters of trigger sources from timer
1854 * depends on timers availability on the selected device.
1855 * @rmtoll CR2 EXTSEL LL_ADC_REG_GetTriggerSource
1856 * @param ADCx ADC instance
1857 * @retval Returned value can be one of the following values:
1858 * @arg @ref LL_ADC_REG_TRIG_SOFTWARE
1859 * @arg @ref LL_ADC_REG_TRIG_EXT_TIM1_CH3 (1)
1860 * @arg @ref LL_ADC_REG_TRIG_EXT_TIM1_CH1 (2)
1861 * @arg @ref LL_ADC_REG_TRIG_EXT_TIM1_CH2 (2)
1862 * @arg @ref LL_ADC_REG_TRIG_EXT_TIM2_CH2 (2)
1863 * @arg @ref LL_ADC_REG_TRIG_EXT_TIM3_TRGO (2)
1864 * @arg @ref LL_ADC_REG_TRIG_EXT_TIM4_CH4 (2)
1865 * @arg @ref LL_ADC_REG_TRIG_EXT_EXTI_LINE11 (2)
1866 * @arg @ref LL_ADC_REG_TRIG_EXT_TIM8_TRGO (2)(4)
1867 * @arg @ref LL_ADC_REG_TRIG_EXT_TIM8_TRGO_ADC3 (3)
1868 * @arg @ref LL_ADC_REG_TRIG_EXT_TIM3_CH1 (3)
1869 * @arg @ref LL_ADC_REG_TRIG_EXT_TIM2_CH3 (3)
1870 * @arg @ref LL_ADC_REG_TRIG_EXT_TIM8_CH1 (3)
1871 * @arg @ref LL_ADC_REG_TRIG_EXT_TIM8_TRGO (3)
1872 * @arg @ref LL_ADC_REG_TRIG_EXT_TIM5_CH1 (3)
1873 * @arg @ref LL_ADC_REG_TRIG_EXT_TIM5_CH3 (3)
1875 * (1) On STM32F1, parameter available on all ADC instances: ADC1, ADC2, ADC3 (for ADC instances ADCx available on the selected device).\n
1876 * (2) On STM32F1, parameter available only on ADC instances: ADC1, ADC2 (for ADC instances ADCx available on the selected device).\n
1877 * (3) On STM32F1, parameter available only on ADC instances: ADC3 (for ADC instances ADCx available on the selected device).\n
1878 * (4) On STM32F1, parameter available only on high-density and XL-density devices. A remap of trigger must be done at top level (refer to AFIO peripheral).
1880 __STATIC_INLINE
uint32_t LL_ADC_REG_GetTriggerSource(ADC_TypeDef
*ADCx
)
1882 return (uint32_t)(READ_BIT(ADCx
->CR2
, ADC_CR2_EXTSEL
));
1886 * @brief Get ADC group regular conversion trigger source internal (SW start)
1888 * @note In case of group regular trigger source set to external trigger,
1889 * to determine which peripheral is selected as external trigger,
1890 * use function @ref LL_ADC_REG_GetTriggerSource().
1891 * @rmtoll CR2 EXTSEL LL_ADC_REG_IsTriggerSourceSWStart
1892 * @param ADCx ADC instance
1893 * @retval Value "0" if trigger source external trigger
1894 * Value "1" if trigger source SW start.
1896 __STATIC_INLINE
uint32_t LL_ADC_REG_IsTriggerSourceSWStart(ADC_TypeDef
*ADCx
)
1898 return (READ_BIT(ADCx
->CR2
, ADC_CR2_EXTSEL
) == (LL_ADC_REG_TRIG_SOFTWARE
));
1903 * @brief Set ADC group regular sequencer length and scan direction.
1904 * @note Description of ADC group regular sequencer features:
1905 * - For devices with sequencer fully configurable
1906 * (function "LL_ADC_REG_SetSequencerRanks()" available):
1907 * sequencer length and each rank affectation to a channel
1909 * This function performs configuration of:
1910 * - Sequence length: Number of ranks in the scan sequence.
1911 * - Sequence direction: Unless specified in parameters, sequencer
1912 * scan direction is forward (from rank 1 to rank n).
1913 * Sequencer ranks are selected using
1914 * function "LL_ADC_REG_SetSequencerRanks()".
1915 * - For devices with sequencer not fully configurable
1916 * (function "LL_ADC_REG_SetSequencerChannels()" available):
1917 * sequencer length and each rank affectation to a channel
1918 * are defined by channel number.
1919 * This function performs configuration of:
1920 * - Sequence length: Number of ranks in the scan sequence is
1921 * defined by number of channels set in the sequence,
1922 * rank of each channel is fixed by channel HW number.
1923 * (channel 0 fixed on rank 0, channel 1 fixed on rank1, ...).
1924 * - Sequence direction: Unless specified in parameters, sequencer
1925 * scan direction is forward (from lowest channel number to
1926 * highest channel number).
1927 * Sequencer ranks are selected using
1928 * function "LL_ADC_REG_SetSequencerChannels()".
1929 * @note On this STM32 serie, group regular sequencer configuration
1930 * is conditioned to ADC instance sequencer mode.
1931 * If ADC instance sequencer mode is disabled, sequencers of
1932 * all groups (group regular, group injected) can be configured
1933 * but their execution is disabled (limited to rank 1).
1934 * Refer to function @ref LL_ADC_SetSequencersScanMode().
1935 * @note Sequencer disabled is equivalent to sequencer of 1 rank:
1936 * ADC conversion on only 1 channel.
1937 * @rmtoll SQR1 L LL_ADC_REG_SetSequencerLength
1938 * @param ADCx ADC instance
1939 * @param SequencerNbRanks This parameter can be one of the following values:
1940 * @arg @ref LL_ADC_REG_SEQ_SCAN_DISABLE
1941 * @arg @ref LL_ADC_REG_SEQ_SCAN_ENABLE_2RANKS
1942 * @arg @ref LL_ADC_REG_SEQ_SCAN_ENABLE_3RANKS
1943 * @arg @ref LL_ADC_REG_SEQ_SCAN_ENABLE_4RANKS
1944 * @arg @ref LL_ADC_REG_SEQ_SCAN_ENABLE_5RANKS
1945 * @arg @ref LL_ADC_REG_SEQ_SCAN_ENABLE_6RANKS
1946 * @arg @ref LL_ADC_REG_SEQ_SCAN_ENABLE_7RANKS
1947 * @arg @ref LL_ADC_REG_SEQ_SCAN_ENABLE_8RANKS
1948 * @arg @ref LL_ADC_REG_SEQ_SCAN_ENABLE_9RANKS
1949 * @arg @ref LL_ADC_REG_SEQ_SCAN_ENABLE_10RANKS
1950 * @arg @ref LL_ADC_REG_SEQ_SCAN_ENABLE_11RANKS
1951 * @arg @ref LL_ADC_REG_SEQ_SCAN_ENABLE_12RANKS
1952 * @arg @ref LL_ADC_REG_SEQ_SCAN_ENABLE_13RANKS
1953 * @arg @ref LL_ADC_REG_SEQ_SCAN_ENABLE_14RANKS
1954 * @arg @ref LL_ADC_REG_SEQ_SCAN_ENABLE_15RANKS
1955 * @arg @ref LL_ADC_REG_SEQ_SCAN_ENABLE_16RANKS
1958 __STATIC_INLINE
void LL_ADC_REG_SetSequencerLength(ADC_TypeDef
*ADCx
, uint32_t SequencerNbRanks
)
1960 MODIFY_REG(ADCx
->SQR1
, ADC_SQR1_L
, SequencerNbRanks
);
1964 * @brief Get ADC group regular sequencer length and scan direction.
1965 * @note Description of ADC group regular sequencer features:
1966 * - For devices with sequencer fully configurable
1967 * (function "LL_ADC_REG_SetSequencerRanks()" available):
1968 * sequencer length and each rank affectation to a channel
1970 * This function retrieves:
1971 * - Sequence length: Number of ranks in the scan sequence.
1972 * - Sequence direction: Unless specified in parameters, sequencer
1973 * scan direction is forward (from rank 1 to rank n).
1974 * Sequencer ranks are selected using
1975 * function "LL_ADC_REG_SetSequencerRanks()".
1976 * - For devices with sequencer not fully configurable
1977 * (function "LL_ADC_REG_SetSequencerChannels()" available):
1978 * sequencer length and each rank affectation to a channel
1979 * are defined by channel number.
1980 * This function retrieves:
1981 * - Sequence length: Number of ranks in the scan sequence is
1982 * defined by number of channels set in the sequence,
1983 * rank of each channel is fixed by channel HW number.
1984 * (channel 0 fixed on rank 0, channel 1 fixed on rank1, ...).
1985 * - Sequence direction: Unless specified in parameters, sequencer
1986 * scan direction is forward (from lowest channel number to
1987 * highest channel number).
1988 * Sequencer ranks are selected using
1989 * function "LL_ADC_REG_SetSequencerChannels()".
1990 * @note On this STM32 serie, group regular sequencer configuration
1991 * is conditioned to ADC instance sequencer mode.
1992 * If ADC instance sequencer mode is disabled, sequencers of
1993 * all groups (group regular, group injected) can be configured
1994 * but their execution is disabled (limited to rank 1).
1995 * Refer to function @ref LL_ADC_SetSequencersScanMode().
1996 * @note Sequencer disabled is equivalent to sequencer of 1 rank:
1997 * ADC conversion on only 1 channel.
1998 * @rmtoll SQR1 L LL_ADC_REG_SetSequencerLength
1999 * @param ADCx ADC instance
2000 * @retval Returned value can be one of the following values:
2001 * @arg @ref LL_ADC_REG_SEQ_SCAN_DISABLE
2002 * @arg @ref LL_ADC_REG_SEQ_SCAN_ENABLE_2RANKS
2003 * @arg @ref LL_ADC_REG_SEQ_SCAN_ENABLE_3RANKS
2004 * @arg @ref LL_ADC_REG_SEQ_SCAN_ENABLE_4RANKS
2005 * @arg @ref LL_ADC_REG_SEQ_SCAN_ENABLE_5RANKS
2006 * @arg @ref LL_ADC_REG_SEQ_SCAN_ENABLE_6RANKS
2007 * @arg @ref LL_ADC_REG_SEQ_SCAN_ENABLE_7RANKS
2008 * @arg @ref LL_ADC_REG_SEQ_SCAN_ENABLE_8RANKS
2009 * @arg @ref LL_ADC_REG_SEQ_SCAN_ENABLE_9RANKS
2010 * @arg @ref LL_ADC_REG_SEQ_SCAN_ENABLE_10RANKS
2011 * @arg @ref LL_ADC_REG_SEQ_SCAN_ENABLE_11RANKS
2012 * @arg @ref LL_ADC_REG_SEQ_SCAN_ENABLE_12RANKS
2013 * @arg @ref LL_ADC_REG_SEQ_SCAN_ENABLE_13RANKS
2014 * @arg @ref LL_ADC_REG_SEQ_SCAN_ENABLE_14RANKS
2015 * @arg @ref LL_ADC_REG_SEQ_SCAN_ENABLE_15RANKS
2016 * @arg @ref LL_ADC_REG_SEQ_SCAN_ENABLE_16RANKS
2018 __STATIC_INLINE
uint32_t LL_ADC_REG_GetSequencerLength(ADC_TypeDef
*ADCx
)
2020 return (uint32_t)(READ_BIT(ADCx
->SQR1
, ADC_SQR1_L
));
2024 * @brief Set ADC group regular sequencer discontinuous mode:
2025 * sequence subdivided and scan conversions interrupted every selected
2027 * @note It is not possible to enable both ADC group regular
2028 * continuous mode and sequencer discontinuous mode.
2029 * @note It is not possible to enable both ADC auto-injected mode
2030 * and ADC group regular sequencer discontinuous mode.
2031 * @rmtoll CR1 DISCEN LL_ADC_REG_SetSequencerDiscont\n
2032 * CR1 DISCNUM LL_ADC_REG_SetSequencerDiscont
2033 * @param ADCx ADC instance
2034 * @param SeqDiscont This parameter can be one of the following values:
2035 * @arg @ref LL_ADC_REG_SEQ_DISCONT_DISABLE
2036 * @arg @ref LL_ADC_REG_SEQ_DISCONT_1RANK
2037 * @arg @ref LL_ADC_REG_SEQ_DISCONT_2RANKS
2038 * @arg @ref LL_ADC_REG_SEQ_DISCONT_3RANKS
2039 * @arg @ref LL_ADC_REG_SEQ_DISCONT_4RANKS
2040 * @arg @ref LL_ADC_REG_SEQ_DISCONT_5RANKS
2041 * @arg @ref LL_ADC_REG_SEQ_DISCONT_6RANKS
2042 * @arg @ref LL_ADC_REG_SEQ_DISCONT_7RANKS
2043 * @arg @ref LL_ADC_REG_SEQ_DISCONT_8RANKS
2046 __STATIC_INLINE
void LL_ADC_REG_SetSequencerDiscont(ADC_TypeDef
*ADCx
, uint32_t SeqDiscont
)
2048 MODIFY_REG(ADCx
->CR1
, ADC_CR1_DISCEN
| ADC_CR1_DISCNUM
, SeqDiscont
);
2052 * @brief Get ADC group regular sequencer discontinuous mode:
2053 * sequence subdivided and scan conversions interrupted every selected
2055 * @rmtoll CR1 DISCEN LL_ADC_REG_GetSequencerDiscont\n
2056 * CR1 DISCNUM LL_ADC_REG_GetSequencerDiscont
2057 * @param ADCx ADC instance
2058 * @retval Returned value can be one of the following values:
2059 * @arg @ref LL_ADC_REG_SEQ_DISCONT_DISABLE
2060 * @arg @ref LL_ADC_REG_SEQ_DISCONT_1RANK
2061 * @arg @ref LL_ADC_REG_SEQ_DISCONT_2RANKS
2062 * @arg @ref LL_ADC_REG_SEQ_DISCONT_3RANKS
2063 * @arg @ref LL_ADC_REG_SEQ_DISCONT_4RANKS
2064 * @arg @ref LL_ADC_REG_SEQ_DISCONT_5RANKS
2065 * @arg @ref LL_ADC_REG_SEQ_DISCONT_6RANKS
2066 * @arg @ref LL_ADC_REG_SEQ_DISCONT_7RANKS
2067 * @arg @ref LL_ADC_REG_SEQ_DISCONT_8RANKS
2069 __STATIC_INLINE
uint32_t LL_ADC_REG_GetSequencerDiscont(ADC_TypeDef
*ADCx
)
2071 return (uint32_t)(READ_BIT(ADCx
->CR1
, ADC_CR1_DISCEN
| ADC_CR1_DISCNUM
));
2075 * @brief Set ADC group regular sequence: channel on the selected
2076 * scan sequence rank.
2077 * @note This function performs configuration of:
2078 * - Channels ordering into each rank of scan sequence:
2079 * whatever channel can be placed into whatever rank.
2080 * @note On this STM32 serie, ADC group regular sequencer is
2081 * fully configurable: sequencer length and each rank
2082 * affectation to a channel are configurable.
2083 * Refer to description of function @ref LL_ADC_REG_SetSequencerLength().
2084 * @note Depending on devices and packages, some channels may not be available.
2085 * Refer to device datasheet for channels availability.
2086 * @note On this STM32 serie, to measure internal channels (VrefInt,
2087 * TempSensor, ...), measurement paths to internal channels must be
2088 * enabled separately.
2089 * This can be done using function @ref LL_ADC_SetCommonPathInternalCh().
2090 * @rmtoll SQR3 SQ1 LL_ADC_REG_SetSequencerRanks\n
2091 * SQR3 SQ2 LL_ADC_REG_SetSequencerRanks\n
2092 * SQR3 SQ3 LL_ADC_REG_SetSequencerRanks\n
2093 * SQR3 SQ4 LL_ADC_REG_SetSequencerRanks\n
2094 * SQR3 SQ5 LL_ADC_REG_SetSequencerRanks\n
2095 * SQR3 SQ6 LL_ADC_REG_SetSequencerRanks\n
2096 * SQR2 SQ7 LL_ADC_REG_SetSequencerRanks\n
2097 * SQR2 SQ8 LL_ADC_REG_SetSequencerRanks\n
2098 * SQR2 SQ9 LL_ADC_REG_SetSequencerRanks\n
2099 * SQR2 SQ10 LL_ADC_REG_SetSequencerRanks\n
2100 * SQR2 SQ11 LL_ADC_REG_SetSequencerRanks\n
2101 * SQR2 SQ12 LL_ADC_REG_SetSequencerRanks\n
2102 * SQR1 SQ13 LL_ADC_REG_SetSequencerRanks\n
2103 * SQR1 SQ14 LL_ADC_REG_SetSequencerRanks\n
2104 * SQR1 SQ15 LL_ADC_REG_SetSequencerRanks\n
2105 * SQR1 SQ16 LL_ADC_REG_SetSequencerRanks
2106 * @param ADCx ADC instance
2107 * @param Rank This parameter can be one of the following values:
2108 * @arg @ref LL_ADC_REG_RANK_1
2109 * @arg @ref LL_ADC_REG_RANK_2
2110 * @arg @ref LL_ADC_REG_RANK_3
2111 * @arg @ref LL_ADC_REG_RANK_4
2112 * @arg @ref LL_ADC_REG_RANK_5
2113 * @arg @ref LL_ADC_REG_RANK_6
2114 * @arg @ref LL_ADC_REG_RANK_7
2115 * @arg @ref LL_ADC_REG_RANK_8
2116 * @arg @ref LL_ADC_REG_RANK_9
2117 * @arg @ref LL_ADC_REG_RANK_10
2118 * @arg @ref LL_ADC_REG_RANK_11
2119 * @arg @ref LL_ADC_REG_RANK_12
2120 * @arg @ref LL_ADC_REG_RANK_13
2121 * @arg @ref LL_ADC_REG_RANK_14
2122 * @arg @ref LL_ADC_REG_RANK_15
2123 * @arg @ref LL_ADC_REG_RANK_16
2124 * @param Channel This parameter can be one of the following values:
2125 * @arg @ref LL_ADC_CHANNEL_0
2126 * @arg @ref LL_ADC_CHANNEL_1
2127 * @arg @ref LL_ADC_CHANNEL_2
2128 * @arg @ref LL_ADC_CHANNEL_3
2129 * @arg @ref LL_ADC_CHANNEL_4
2130 * @arg @ref LL_ADC_CHANNEL_5
2131 * @arg @ref LL_ADC_CHANNEL_6
2132 * @arg @ref LL_ADC_CHANNEL_7
2133 * @arg @ref LL_ADC_CHANNEL_8
2134 * @arg @ref LL_ADC_CHANNEL_9
2135 * @arg @ref LL_ADC_CHANNEL_10
2136 * @arg @ref LL_ADC_CHANNEL_11
2137 * @arg @ref LL_ADC_CHANNEL_12
2138 * @arg @ref LL_ADC_CHANNEL_13
2139 * @arg @ref LL_ADC_CHANNEL_14
2140 * @arg @ref LL_ADC_CHANNEL_15
2141 * @arg @ref LL_ADC_CHANNEL_16
2142 * @arg @ref LL_ADC_CHANNEL_17
2143 * @arg @ref LL_ADC_CHANNEL_VREFINT (1)
2144 * @arg @ref LL_ADC_CHANNEL_TEMPSENSOR (1)
2146 * (1) On STM32F1, parameter available only on ADC instance: ADC1.
2149 __STATIC_INLINE
void LL_ADC_REG_SetSequencerRanks(ADC_TypeDef
*ADCx
, uint32_t Rank
, uint32_t Channel
)
2151 /* Set bits with content of parameter "Channel" with bits position */
2152 /* in register and register position depending on parameter "Rank". */
2153 /* Parameters "Rank" and "Channel" are used with masks because containing */
2154 /* other bits reserved for other purpose. */
2155 register uint32_t *preg
= __ADC_PTR_REG_OFFSET(ADCx
->SQR1
, __ADC_MASK_SHIFT(Rank
, ADC_REG_SQRX_REGOFFSET_MASK
));
2158 ADC_CHANNEL_ID_NUMBER_MASK
<< (Rank
& ADC_REG_RANK_ID_SQRX_MASK
),
2159 (Channel
& ADC_CHANNEL_ID_NUMBER_MASK
) << (Rank
& ADC_REG_RANK_ID_SQRX_MASK
));
2163 * @brief Get ADC group regular sequence: channel on the selected
2164 * scan sequence rank.
2165 * @note On this STM32 serie, ADC group regular sequencer is
2166 * fully configurable: sequencer length and each rank
2167 * affectation to a channel are configurable.
2168 * Refer to description of function @ref LL_ADC_REG_SetSequencerLength().
2169 * @note Depending on devices and packages, some channels may not be available.
2170 * Refer to device datasheet for channels availability.
2171 * @note Usage of the returned channel number:
2172 * - To reinject this channel into another function LL_ADC_xxx:
2173 * the returned channel number is only partly formatted on definition
2174 * of literals LL_ADC_CHANNEL_x. Therefore, it has to be compared
2175 * with parts of literals LL_ADC_CHANNEL_x or using
2176 * helper macro @ref __LL_ADC_CHANNEL_TO_DECIMAL_NB().
2177 * Then the selected literal LL_ADC_CHANNEL_x can be used
2178 * as parameter for another function.
2179 * - To get the channel number in decimal format:
2180 * process the returned value with the helper macro
2181 * @ref __LL_ADC_CHANNEL_TO_DECIMAL_NB().
2182 * @rmtoll SQR3 SQ1 LL_ADC_REG_GetSequencerRanks\n
2183 * SQR3 SQ2 LL_ADC_REG_GetSequencerRanks\n
2184 * SQR3 SQ3 LL_ADC_REG_GetSequencerRanks\n
2185 * SQR3 SQ4 LL_ADC_REG_GetSequencerRanks\n
2186 * SQR3 SQ5 LL_ADC_REG_GetSequencerRanks\n
2187 * SQR3 SQ6 LL_ADC_REG_GetSequencerRanks\n
2188 * SQR2 SQ7 LL_ADC_REG_GetSequencerRanks\n
2189 * SQR2 SQ8 LL_ADC_REG_GetSequencerRanks\n
2190 * SQR2 SQ9 LL_ADC_REG_GetSequencerRanks\n
2191 * SQR2 SQ10 LL_ADC_REG_GetSequencerRanks\n
2192 * SQR2 SQ11 LL_ADC_REG_GetSequencerRanks\n
2193 * SQR2 SQ12 LL_ADC_REG_GetSequencerRanks\n
2194 * SQR1 SQ13 LL_ADC_REG_GetSequencerRanks\n
2195 * SQR1 SQ14 LL_ADC_REG_GetSequencerRanks\n
2196 * SQR1 SQ15 LL_ADC_REG_GetSequencerRanks\n
2197 * SQR1 SQ16 LL_ADC_REG_GetSequencerRanks
2198 * @param ADCx ADC instance
2199 * @param Rank This parameter can be one of the following values:
2200 * @arg @ref LL_ADC_REG_RANK_1
2201 * @arg @ref LL_ADC_REG_RANK_2
2202 * @arg @ref LL_ADC_REG_RANK_3
2203 * @arg @ref LL_ADC_REG_RANK_4
2204 * @arg @ref LL_ADC_REG_RANK_5
2205 * @arg @ref LL_ADC_REG_RANK_6
2206 * @arg @ref LL_ADC_REG_RANK_7
2207 * @arg @ref LL_ADC_REG_RANK_8
2208 * @arg @ref LL_ADC_REG_RANK_9
2209 * @arg @ref LL_ADC_REG_RANK_10
2210 * @arg @ref LL_ADC_REG_RANK_11
2211 * @arg @ref LL_ADC_REG_RANK_12
2212 * @arg @ref LL_ADC_REG_RANK_13
2213 * @arg @ref LL_ADC_REG_RANK_14
2214 * @arg @ref LL_ADC_REG_RANK_15
2215 * @arg @ref LL_ADC_REG_RANK_16
2216 * @retval Returned value can be one of the following values:
2217 * @arg @ref LL_ADC_CHANNEL_0
2218 * @arg @ref LL_ADC_CHANNEL_1
2219 * @arg @ref LL_ADC_CHANNEL_2
2220 * @arg @ref LL_ADC_CHANNEL_3
2221 * @arg @ref LL_ADC_CHANNEL_4
2222 * @arg @ref LL_ADC_CHANNEL_5
2223 * @arg @ref LL_ADC_CHANNEL_6
2224 * @arg @ref LL_ADC_CHANNEL_7
2225 * @arg @ref LL_ADC_CHANNEL_8
2226 * @arg @ref LL_ADC_CHANNEL_9
2227 * @arg @ref LL_ADC_CHANNEL_10
2228 * @arg @ref LL_ADC_CHANNEL_11
2229 * @arg @ref LL_ADC_CHANNEL_12
2230 * @arg @ref LL_ADC_CHANNEL_13
2231 * @arg @ref LL_ADC_CHANNEL_14
2232 * @arg @ref LL_ADC_CHANNEL_15
2233 * @arg @ref LL_ADC_CHANNEL_16
2234 * @arg @ref LL_ADC_CHANNEL_17
2235 * @arg @ref LL_ADC_CHANNEL_VREFINT (1)
2236 * @arg @ref LL_ADC_CHANNEL_TEMPSENSOR (1)
2238 * (1) On STM32F1, parameter available only on ADC instance: ADC1.\n
2239 * (1) For ADC channel read back from ADC register,
2240 * comparison with internal channel parameter to be done
2241 * using helper macro @ref __LL_ADC_CHANNEL_INTERNAL_TO_EXTERNAL().
2243 __STATIC_INLINE
uint32_t LL_ADC_REG_GetSequencerRanks(ADC_TypeDef
*ADCx
, uint32_t Rank
)
2245 register uint32_t *preg
= __ADC_PTR_REG_OFFSET(ADCx
->SQR1
, __ADC_MASK_SHIFT(Rank
, ADC_REG_SQRX_REGOFFSET_MASK
));
2247 return (uint32_t) (READ_BIT(*preg
,
2248 ADC_CHANNEL_ID_NUMBER_MASK
<< (Rank
& ADC_REG_RANK_ID_SQRX_MASK
))
2249 >> (Rank
& ADC_REG_RANK_ID_SQRX_MASK
)
2254 * @brief Set ADC continuous conversion mode on ADC group regular.
2255 * @note Description of ADC continuous conversion mode:
2256 * - single mode: one conversion per trigger
2257 * - continuous mode: after the first trigger, following
2258 * conversions launched successively automatically.
2259 * @note It is not possible to enable both ADC group regular
2260 * continuous mode and sequencer discontinuous mode.
2261 * @rmtoll CR2 CONT LL_ADC_REG_SetContinuousMode
2262 * @param ADCx ADC instance
2263 * @param Continuous This parameter can be one of the following values:
2264 * @arg @ref LL_ADC_REG_CONV_SINGLE
2265 * @arg @ref LL_ADC_REG_CONV_CONTINUOUS
2268 __STATIC_INLINE
void LL_ADC_REG_SetContinuousMode(ADC_TypeDef
*ADCx
, uint32_t Continuous
)
2270 MODIFY_REG(ADCx
->CR2
, ADC_CR2_CONT
, Continuous
);
2274 * @brief Get ADC continuous conversion mode on ADC group regular.
2275 * @note Description of ADC continuous conversion mode:
2276 * - single mode: one conversion per trigger
2277 * - continuous mode: after the first trigger, following
2278 * conversions launched successively automatically.
2279 * @rmtoll CR2 CONT LL_ADC_REG_GetContinuousMode
2280 * @param ADCx ADC instance
2281 * @retval Returned value can be one of the following values:
2282 * @arg @ref LL_ADC_REG_CONV_SINGLE
2283 * @arg @ref LL_ADC_REG_CONV_CONTINUOUS
2285 __STATIC_INLINE
uint32_t LL_ADC_REG_GetContinuousMode(ADC_TypeDef
*ADCx
)
2287 return (uint32_t)(READ_BIT(ADCx
->CR2
, ADC_CR2_CONT
));
2291 * @brief Set ADC group regular conversion data transfer: no transfer or
2292 * transfer by DMA, and DMA requests mode.
2293 * @note If transfer by DMA selected, specifies the DMA requests
2295 * - Limited mode (One shot mode): DMA transfer requests are stopped
2296 * when number of DMA data transfers (number of
2297 * ADC conversions) is reached.
2298 * This ADC mode is intended to be used with DMA mode non-circular.
2299 * - Unlimited mode: DMA transfer requests are unlimited,
2300 * whatever number of DMA data transfers (number of
2302 * This ADC mode is intended to be used with DMA mode circular.
2303 * @note If ADC DMA requests mode is set to unlimited and DMA is set to
2304 * mode non-circular:
2305 * when DMA transfers size will be reached, DMA will stop transfers of
2306 * ADC conversions data ADC will raise an overrun error
2307 * (overrun flag and interruption if enabled).
2308 * @note To configure DMA source address (peripheral address),
2309 * use function @ref LL_ADC_DMA_GetRegAddr().
2310 * @rmtoll CR2 DMA LL_ADC_REG_SetDMATransfer
2311 * @param ADCx ADC instance
2312 * @param DMATransfer This parameter can be one of the following values:
2313 * @arg @ref LL_ADC_REG_DMA_TRANSFER_NONE
2314 * @arg @ref LL_ADC_REG_DMA_TRANSFER_UNLIMITED
2317 __STATIC_INLINE
void LL_ADC_REG_SetDMATransfer(ADC_TypeDef
*ADCx
, uint32_t DMATransfer
)
2319 MODIFY_REG(ADCx
->CR2
, ADC_CR2_DMA
, DMATransfer
);
2323 * @brief Get ADC group regular conversion data transfer: no transfer or
2324 * transfer by DMA, and DMA requests mode.
2325 * @note If transfer by DMA selected, specifies the DMA requests
2327 * - Limited mode (One shot mode): DMA transfer requests are stopped
2328 * when number of DMA data transfers (number of
2329 * ADC conversions) is reached.
2330 * This ADC mode is intended to be used with DMA mode non-circular.
2331 * - Unlimited mode: DMA transfer requests are unlimited,
2332 * whatever number of DMA data transfers (number of
2334 * This ADC mode is intended to be used with DMA mode circular.
2335 * @note If ADC DMA requests mode is set to unlimited and DMA is set to
2336 * mode non-circular:
2337 * when DMA transfers size will be reached, DMA will stop transfers of
2338 * ADC conversions data ADC will raise an overrun error
2339 * (overrun flag and interruption if enabled).
2340 * @note To configure DMA source address (peripheral address),
2341 * use function @ref LL_ADC_DMA_GetRegAddr().
2342 * @rmtoll CR2 DMA LL_ADC_REG_GetDMATransfer
2343 * @param ADCx ADC instance
2344 * @retval Returned value can be one of the following values:
2345 * @arg @ref LL_ADC_REG_DMA_TRANSFER_NONE
2346 * @arg @ref LL_ADC_REG_DMA_TRANSFER_UNLIMITED
2348 __STATIC_INLINE
uint32_t LL_ADC_REG_GetDMATransfer(ADC_TypeDef
*ADCx
)
2350 return (uint32_t)(READ_BIT(ADCx
->CR2
, ADC_CR2_DMA
));
2357 /** @defgroup ADC_LL_EF_Configuration_ADC_Group_Injected Configuration of ADC hierarchical scope: group injected
2362 * @brief Set ADC group injected conversion trigger source:
2363 * internal (SW start) or from external IP (timer event,
2364 * external interrupt line).
2365 * @note On this STM32 serie, external trigger is set with trigger polarity:
2366 * rising edge (only trigger polarity available on this STM32 serie).
2367 * @note Availability of parameters of trigger sources from timer
2368 * depends on timers availability on the selected device.
2369 * @rmtoll CR2 JEXTSEL LL_ADC_INJ_SetTriggerSource
2370 * @param ADCx ADC instance
2371 * @param TriggerSource This parameter can be one of the following values:
2372 * @arg @ref LL_ADC_INJ_TRIG_SOFTWARE
2373 * @arg @ref LL_ADC_INJ_TRIG_EXT_TIM1_TRGO (1)
2374 * @arg @ref LL_ADC_INJ_TRIG_EXT_TIM1_CH4 (1)
2375 * @arg @ref LL_ADC_INJ_TRIG_EXT_TIM2_TRGO (2)
2376 * @arg @ref LL_ADC_INJ_TRIG_EXT_TIM2_CH1 (2)
2377 * @arg @ref LL_ADC_INJ_TRIG_EXT_TIM3_CH4 (2)
2378 * @arg @ref LL_ADC_INJ_TRIG_EXT_TIM4_TRGO (2)
2379 * @arg @ref LL_ADC_INJ_TRIG_EXT_EXTI_LINE15 (2)
2380 * @arg @ref LL_ADC_INJ_TRIG_EXT_TIM8_CH4 (2)(4)
2381 * @arg @ref LL_ADC_INJ_TRIG_EXT_TIM8_CH4_ADC3 (3)
2382 * @arg @ref LL_ADC_INJ_TRIG_EXT_TIM4_CH3 (3)
2383 * @arg @ref LL_ADC_INJ_TRIG_EXT_TIM8_CH2 (3)
2384 * @arg @ref LL_ADC_INJ_TRIG_EXT_TIM8_CH4 (3)
2385 * @arg @ref LL_ADC_INJ_TRIG_EXT_TIM5_TRGO (3)
2386 * @arg @ref LL_ADC_INJ_TRIG_EXT_TIM5_CH4 (3)
2388 * (1) On STM32F1, parameter available on all ADC instances: ADC1, ADC2, ADC3 (for ADC instances ADCx available on the selected device).\n
2389 * (2) On STM32F1, parameter available only on ADC instances: ADC1, ADC2 (for ADC instances ADCx available on the selected device).\n
2390 * (3) On STM32F1, parameter available only on ADC instances: ADC3 (for ADC instances ADCx available on the selected device).\n
2391 * (4) On STM32F1, parameter available only on high-density and XL-density devices. A remap of trigger must be done at top level (refer to AFIO peripheral).
2394 __STATIC_INLINE
void LL_ADC_INJ_SetTriggerSource(ADC_TypeDef
*ADCx
, uint32_t TriggerSource
)
2396 /* Note: On this STM32 serie, ADC group injected external trigger edge */
2397 /* is used to perform a ADC conversion start. */
2398 /* This function does not set external trigger edge. */
2399 /* This feature is set using function */
2400 /* @ref LL_ADC_INJ_StartConversionExtTrig(). */
2401 MODIFY_REG(ADCx
->CR2
, ADC_CR2_JEXTSEL
, (TriggerSource
& ADC_CR2_JEXTSEL
));
2405 * @brief Get ADC group injected conversion trigger source:
2406 * internal (SW start) or from external IP (timer event,
2407 * external interrupt line).
2408 * @note To determine whether group injected trigger source is
2409 * internal (SW start) or external, without detail
2410 * of which peripheral is selected as external trigger,
2412 * "if(LL_ADC_INJ_GetTriggerSource(ADC1) == LL_ADC_INJ_TRIG_SOFTWARE)")
2413 * use function @ref LL_ADC_INJ_IsTriggerSourceSWStart.
2414 * @note Availability of parameters of trigger sources from timer
2415 * depends on timers availability on the selected device.
2416 * @rmtoll CR2 JEXTSEL LL_ADC_INJ_GetTriggerSource
2417 * @param ADCx ADC instance
2418 * @retval Returned value can be one of the following values:
2419 * @arg @ref LL_ADC_INJ_TRIG_SOFTWARE
2420 * @arg @ref LL_ADC_INJ_TRIG_EXT_TIM1_TRGO (1)
2421 * @arg @ref LL_ADC_INJ_TRIG_EXT_TIM1_CH4 (1)
2422 * @arg @ref LL_ADC_INJ_TRIG_EXT_TIM2_TRGO (2)
2423 * @arg @ref LL_ADC_INJ_TRIG_EXT_TIM2_CH1 (2)
2424 * @arg @ref LL_ADC_INJ_TRIG_EXT_TIM3_CH4 (2)
2425 * @arg @ref LL_ADC_INJ_TRIG_EXT_TIM4_TRGO (2)
2426 * @arg @ref LL_ADC_INJ_TRIG_EXT_EXTI_LINE15 (2)
2427 * @arg @ref LL_ADC_INJ_TRIG_EXT_TIM8_CH4 (2)(4)
2428 * @arg @ref LL_ADC_INJ_TRIG_EXT_TIM8_CH4_ADC3 (3)
2429 * @arg @ref LL_ADC_INJ_TRIG_EXT_TIM4_CH3 (3)
2430 * @arg @ref LL_ADC_INJ_TRIG_EXT_TIM8_CH2 (3)
2431 * @arg @ref LL_ADC_INJ_TRIG_EXT_TIM8_CH4 (3)
2432 * @arg @ref LL_ADC_INJ_TRIG_EXT_TIM5_TRGO (3)
2433 * @arg @ref LL_ADC_INJ_TRIG_EXT_TIM5_CH4 (3)
2435 * (1) On STM32F1, parameter available on all ADC instances: ADC1, ADC2, ADC3 (for ADC instances ADCx available on the selected device).\n
2436 * (2) On STM32F1, parameter available only on ADC instances: ADC1, ADC2 (for ADC instances ADCx available on the selected device).\n
2437 * (3) On STM32F1, parameter available only on ADC instances: ADC3 (for ADC instances ADCx available on the selected device).\n
2438 * (4) On STM32F1, parameter available only on high-density and XL-density devices. A remap of trigger must be done at top level (refer to AFIO peripheral).
2440 __STATIC_INLINE
uint32_t LL_ADC_INJ_GetTriggerSource(ADC_TypeDef
*ADCx
)
2442 return (uint32_t)(READ_BIT(ADCx
->CR2
, ADC_CR2_JEXTSEL
));
2446 * @brief Get ADC group injected conversion trigger source internal (SW start)
2448 * @note In case of group injected trigger source set to external trigger,
2449 * to determine which peripheral is selected as external trigger,
2450 * use function @ref LL_ADC_INJ_GetTriggerSource.
2451 * @rmtoll CR2 JEXTSEL LL_ADC_INJ_IsTriggerSourceSWStart
2452 * @param ADCx ADC instance
2453 * @retval Value "0" if trigger source external trigger
2454 * Value "1" if trigger source SW start.
2456 __STATIC_INLINE
uint32_t LL_ADC_INJ_IsTriggerSourceSWStart(ADC_TypeDef
*ADCx
)
2458 return (READ_BIT(ADCx
->CR2
, ADC_CR2_JEXTSEL
) == LL_ADC_INJ_TRIG_SOFTWARE
);
2462 * @brief Set ADC group injected sequencer length and scan direction.
2463 * @note This function performs configuration of:
2464 * - Sequence length: Number of ranks in the scan sequence.
2465 * - Sequence direction: Unless specified in parameters, sequencer
2466 * scan direction is forward (from rank 1 to rank n).
2467 * @note On this STM32 serie, group injected sequencer configuration
2468 * is conditioned to ADC instance sequencer mode.
2469 * If ADC instance sequencer mode is disabled, sequencers of
2470 * all groups (group regular, group injected) can be configured
2471 * but their execution is disabled (limited to rank 1).
2472 * Refer to function @ref LL_ADC_SetSequencersScanMode().
2473 * @note Sequencer disabled is equivalent to sequencer of 1 rank:
2474 * ADC conversion on only 1 channel.
2475 * @rmtoll JSQR JL LL_ADC_INJ_SetSequencerLength
2476 * @param ADCx ADC instance
2477 * @param SequencerNbRanks This parameter can be one of the following values:
2478 * @arg @ref LL_ADC_INJ_SEQ_SCAN_DISABLE
2479 * @arg @ref LL_ADC_INJ_SEQ_SCAN_ENABLE_2RANKS
2480 * @arg @ref LL_ADC_INJ_SEQ_SCAN_ENABLE_3RANKS
2481 * @arg @ref LL_ADC_INJ_SEQ_SCAN_ENABLE_4RANKS
2484 __STATIC_INLINE
void LL_ADC_INJ_SetSequencerLength(ADC_TypeDef
*ADCx
, uint32_t SequencerNbRanks
)
2486 MODIFY_REG(ADCx
->JSQR
, ADC_JSQR_JL
, SequencerNbRanks
);
2490 * @brief Get ADC group injected sequencer length and scan direction.
2491 * @note This function retrieves:
2492 * - Sequence length: Number of ranks in the scan sequence.
2493 * - Sequence direction: Unless specified in parameters, sequencer
2494 * scan direction is forward (from rank 1 to rank n).
2495 * @note On this STM32 serie, group injected sequencer configuration
2496 * is conditioned to ADC instance sequencer mode.
2497 * If ADC instance sequencer mode is disabled, sequencers of
2498 * all groups (group regular, group injected) can be configured
2499 * but their execution is disabled (limited to rank 1).
2500 * Refer to function @ref LL_ADC_SetSequencersScanMode().
2501 * @note Sequencer disabled is equivalent to sequencer of 1 rank:
2502 * ADC conversion on only 1 channel.
2503 * @rmtoll JSQR JL LL_ADC_INJ_GetSequencerLength
2504 * @param ADCx ADC instance
2505 * @retval Returned value can be one of the following values:
2506 * @arg @ref LL_ADC_INJ_SEQ_SCAN_DISABLE
2507 * @arg @ref LL_ADC_INJ_SEQ_SCAN_ENABLE_2RANKS
2508 * @arg @ref LL_ADC_INJ_SEQ_SCAN_ENABLE_3RANKS
2509 * @arg @ref LL_ADC_INJ_SEQ_SCAN_ENABLE_4RANKS
2511 __STATIC_INLINE
uint32_t LL_ADC_INJ_GetSequencerLength(ADC_TypeDef
*ADCx
)
2513 return (uint32_t)(READ_BIT(ADCx
->JSQR
, ADC_JSQR_JL
));
2517 * @brief Set ADC group injected sequencer discontinuous mode:
2518 * sequence subdivided and scan conversions interrupted every selected
2520 * @note It is not possible to enable both ADC group injected
2521 * auto-injected mode and sequencer discontinuous mode.
2522 * @rmtoll CR1 DISCEN LL_ADC_INJ_SetSequencerDiscont
2523 * @param ADCx ADC instance
2524 * @param SeqDiscont This parameter can be one of the following values:
2525 * @arg @ref LL_ADC_INJ_SEQ_DISCONT_DISABLE
2526 * @arg @ref LL_ADC_INJ_SEQ_DISCONT_1RANK
2529 __STATIC_INLINE
void LL_ADC_INJ_SetSequencerDiscont(ADC_TypeDef
*ADCx
, uint32_t SeqDiscont
)
2531 MODIFY_REG(ADCx
->CR1
, ADC_CR1_JDISCEN
, SeqDiscont
);
2535 * @brief Get ADC group injected sequencer discontinuous mode:
2536 * sequence subdivided and scan conversions interrupted every selected
2538 * @rmtoll CR1 DISCEN LL_ADC_REG_GetSequencerDiscont
2539 * @param ADCx ADC instance
2540 * @retval Returned value can be one of the following values:
2541 * @arg @ref LL_ADC_INJ_SEQ_DISCONT_DISABLE
2542 * @arg @ref LL_ADC_INJ_SEQ_DISCONT_1RANK
2544 __STATIC_INLINE
uint32_t LL_ADC_INJ_GetSequencerDiscont(ADC_TypeDef
*ADCx
)
2546 return (uint32_t)(READ_BIT(ADCx
->CR1
, ADC_CR1_JDISCEN
));
2550 * @brief Set ADC group injected sequence: channel on the selected
2552 * @note Depending on devices and packages, some channels may not be available.
2553 * Refer to device datasheet for channels availability.
2554 * @note On this STM32 serie, to measure internal channels (VrefInt,
2555 * TempSensor, ...), measurement paths to internal channels must be
2556 * enabled separately.
2557 * This can be done using function @ref LL_ADC_SetCommonPathInternalCh().
2558 * @rmtoll JSQR JSQ1 LL_ADC_INJ_SetSequencerRanks\n
2559 * JSQR JSQ2 LL_ADC_INJ_SetSequencerRanks\n
2560 * JSQR JSQ3 LL_ADC_INJ_SetSequencerRanks\n
2561 * JSQR JSQ4 LL_ADC_INJ_SetSequencerRanks
2562 * @param ADCx ADC instance
2563 * @param Rank This parameter can be one of the following values:
2564 * @arg @ref LL_ADC_INJ_RANK_1
2565 * @arg @ref LL_ADC_INJ_RANK_2
2566 * @arg @ref LL_ADC_INJ_RANK_3
2567 * @arg @ref LL_ADC_INJ_RANK_4
2568 * @param Channel This parameter can be one of the following values:
2569 * @arg @ref LL_ADC_CHANNEL_0
2570 * @arg @ref LL_ADC_CHANNEL_1
2571 * @arg @ref LL_ADC_CHANNEL_2
2572 * @arg @ref LL_ADC_CHANNEL_3
2573 * @arg @ref LL_ADC_CHANNEL_4
2574 * @arg @ref LL_ADC_CHANNEL_5
2575 * @arg @ref LL_ADC_CHANNEL_6
2576 * @arg @ref LL_ADC_CHANNEL_7
2577 * @arg @ref LL_ADC_CHANNEL_8
2578 * @arg @ref LL_ADC_CHANNEL_9
2579 * @arg @ref LL_ADC_CHANNEL_10
2580 * @arg @ref LL_ADC_CHANNEL_11
2581 * @arg @ref LL_ADC_CHANNEL_12
2582 * @arg @ref LL_ADC_CHANNEL_13
2583 * @arg @ref LL_ADC_CHANNEL_14
2584 * @arg @ref LL_ADC_CHANNEL_15
2585 * @arg @ref LL_ADC_CHANNEL_16
2586 * @arg @ref LL_ADC_CHANNEL_17
2587 * @arg @ref LL_ADC_CHANNEL_VREFINT (1)
2588 * @arg @ref LL_ADC_CHANNEL_TEMPSENSOR (1)
2590 * (1) On STM32F1, parameter available only on ADC instance: ADC1.
2593 __STATIC_INLINE
void LL_ADC_INJ_SetSequencerRanks(ADC_TypeDef
*ADCx
, uint32_t Rank
, uint32_t Channel
)
2595 /* Set bits with content of parameter "Channel" with bits position */
2596 /* in register depending on parameter "Rank". */
2597 /* Parameters "Rank" and "Channel" are used with masks because containing */
2598 /* other bits reserved for other purpose. */
2599 register uint32_t tmpreg1
= (READ_BIT(ADCx
->JSQR
, ADC_JSQR_JL
) >> ADC_JSQR_JL_Pos
) + 1U;
2601 MODIFY_REG(ADCx
->JSQR
,
2602 ADC_CHANNEL_ID_NUMBER_MASK
<< (5U * (uint8_t)(((Rank
) + 3U) - (tmpreg1
))),
2603 (Channel
& ADC_CHANNEL_ID_NUMBER_MASK
) << (5U * (uint8_t)(((Rank
) + 3U) - (tmpreg1
))));
2607 * @brief Get ADC group injected sequence: channel on the selected
2609 * @note Depending on devices and packages, some channels may not be available.
2610 * Refer to device datasheet for channels availability.
2611 * @note Usage of the returned channel number:
2612 * - To reinject this channel into another function LL_ADC_xxx:
2613 * the returned channel number is only partly formatted on definition
2614 * of literals LL_ADC_CHANNEL_x. Therefore, it has to be compared
2615 * with parts of literals LL_ADC_CHANNEL_x or using
2616 * helper macro @ref __LL_ADC_CHANNEL_TO_DECIMAL_NB().
2617 * Then the selected literal LL_ADC_CHANNEL_x can be used
2618 * as parameter for another function.
2619 * - To get the channel number in decimal format:
2620 * process the returned value with the helper macro
2621 * @ref __LL_ADC_CHANNEL_TO_DECIMAL_NB().
2622 * @rmtoll JSQR JSQ1 LL_ADC_INJ_SetSequencerRanks\n
2623 * JSQR JSQ2 LL_ADC_INJ_SetSequencerRanks\n
2624 * JSQR JSQ3 LL_ADC_INJ_SetSequencerRanks\n
2625 * JSQR JSQ4 LL_ADC_INJ_SetSequencerRanks
2626 * @param ADCx ADC instance
2627 * @param Rank This parameter can be one of the following values:
2628 * @arg @ref LL_ADC_INJ_RANK_1
2629 * @arg @ref LL_ADC_INJ_RANK_2
2630 * @arg @ref LL_ADC_INJ_RANK_3
2631 * @arg @ref LL_ADC_INJ_RANK_4
2632 * @retval Returned value can be one of the following values:
2633 * @arg @ref LL_ADC_CHANNEL_0
2634 * @arg @ref LL_ADC_CHANNEL_1
2635 * @arg @ref LL_ADC_CHANNEL_2
2636 * @arg @ref LL_ADC_CHANNEL_3
2637 * @arg @ref LL_ADC_CHANNEL_4
2638 * @arg @ref LL_ADC_CHANNEL_5
2639 * @arg @ref LL_ADC_CHANNEL_6
2640 * @arg @ref LL_ADC_CHANNEL_7
2641 * @arg @ref LL_ADC_CHANNEL_8
2642 * @arg @ref LL_ADC_CHANNEL_9
2643 * @arg @ref LL_ADC_CHANNEL_10
2644 * @arg @ref LL_ADC_CHANNEL_11
2645 * @arg @ref LL_ADC_CHANNEL_12
2646 * @arg @ref LL_ADC_CHANNEL_13
2647 * @arg @ref LL_ADC_CHANNEL_14
2648 * @arg @ref LL_ADC_CHANNEL_15
2649 * @arg @ref LL_ADC_CHANNEL_16
2650 * @arg @ref LL_ADC_CHANNEL_17
2651 * @arg @ref LL_ADC_CHANNEL_VREFINT (1)
2652 * @arg @ref LL_ADC_CHANNEL_TEMPSENSOR (1)
2654 * (1) On STM32F1, parameter available only on ADC instance: ADC1.\n
2655 * (1) For ADC channel read back from ADC register,
2656 * comparison with internal channel parameter to be done
2657 * using helper macro @ref __LL_ADC_CHANNEL_INTERNAL_TO_EXTERNAL().
2659 __STATIC_INLINE
uint32_t LL_ADC_INJ_GetSequencerRanks(ADC_TypeDef
*ADCx
, uint32_t Rank
)
2661 register uint32_t tmpreg1
= (READ_BIT(ADCx
->JSQR
, ADC_JSQR_JL
) >> ADC_JSQR_JL_Pos
) + 1U;
2663 return (uint32_t)(READ_BIT(ADCx
->JSQR
,
2664 ADC_CHANNEL_ID_NUMBER_MASK
<< (5U * (uint8_t)(((Rank
) + 3U) - (tmpreg1
))))
2665 >> (5U * (uint8_t)(((Rank
) + 3U) - (tmpreg1
)))
2670 * @brief Set ADC group injected conversion trigger:
2671 * independent or from ADC group regular.
2672 * @note This mode can be used to extend number of data registers
2673 * updated after one ADC conversion trigger and with data
2674 * permanently kept (not erased by successive conversions of scan of
2675 * ADC sequencer ranks), up to 5 data registers:
2676 * 1 data register on ADC group regular, 4 data registers
2677 * on ADC group injected.
2678 * @note If ADC group injected injected trigger source is set to an
2679 * external trigger, this feature must be must be set to
2680 * independent trigger.
2681 * ADC group injected automatic trigger is compliant only with
2682 * group injected trigger source set to SW start, without any
2683 * further action on ADC group injected conversion start or stop:
2684 * in this case, ADC group injected is controlled only
2685 * from ADC group regular.
2686 * @note It is not possible to enable both ADC group injected
2687 * auto-injected mode and sequencer discontinuous mode.
2688 * @rmtoll CR1 JAUTO LL_ADC_INJ_SetTrigAuto
2689 * @param ADCx ADC instance
2690 * @param TrigAuto This parameter can be one of the following values:
2691 * @arg @ref LL_ADC_INJ_TRIG_INDEPENDENT
2692 * @arg @ref LL_ADC_INJ_TRIG_FROM_GRP_REGULAR
2695 __STATIC_INLINE
void LL_ADC_INJ_SetTrigAuto(ADC_TypeDef
*ADCx
, uint32_t TrigAuto
)
2697 MODIFY_REG(ADCx
->CR1
, ADC_CR1_JAUTO
, TrigAuto
);
2701 * @brief Get ADC group injected conversion trigger:
2702 * independent or from ADC group regular.
2703 * @rmtoll CR1 JAUTO LL_ADC_INJ_GetTrigAuto
2704 * @param ADCx ADC instance
2705 * @retval Returned value can be one of the following values:
2706 * @arg @ref LL_ADC_INJ_TRIG_INDEPENDENT
2707 * @arg @ref LL_ADC_INJ_TRIG_FROM_GRP_REGULAR
2709 __STATIC_INLINE
uint32_t LL_ADC_INJ_GetTrigAuto(ADC_TypeDef
*ADCx
)
2711 return (uint32_t)(READ_BIT(ADCx
->CR1
, ADC_CR1_JAUTO
));
2715 * @brief Set ADC group injected offset.
2717 * - ADC group injected rank to which the offset programmed
2719 * - Offset level (offset to be subtracted from the raw
2721 * Caution: Offset format is dependent to ADC resolution:
2722 * offset has to be left-aligned on bit 11, the LSB (right bits)
2724 * @note Offset cannot be enabled or disabled.
2725 * To emulate offset disabled, set an offset value equal to 0.
2726 * @rmtoll JOFR1 JOFFSET1 LL_ADC_INJ_SetOffset\n
2727 * JOFR2 JOFFSET2 LL_ADC_INJ_SetOffset\n
2728 * JOFR3 JOFFSET3 LL_ADC_INJ_SetOffset\n
2729 * JOFR4 JOFFSET4 LL_ADC_INJ_SetOffset
2730 * @param ADCx ADC instance
2731 * @param Rank This parameter can be one of the following values:
2732 * @arg @ref LL_ADC_INJ_RANK_1
2733 * @arg @ref LL_ADC_INJ_RANK_2
2734 * @arg @ref LL_ADC_INJ_RANK_3
2735 * @arg @ref LL_ADC_INJ_RANK_4
2736 * @param OffsetLevel Value between Min_Data=0x000 and Max_Data=0xFFF
2739 __STATIC_INLINE
void LL_ADC_INJ_SetOffset(ADC_TypeDef
*ADCx
, uint32_t Rank
, uint32_t OffsetLevel
)
2741 register uint32_t *preg
= __ADC_PTR_REG_OFFSET(ADCx
->JOFR1
, __ADC_MASK_SHIFT(Rank
, ADC_INJ_JOFRX_REGOFFSET_MASK
));
2749 * @brief Get ADC group injected offset.
2750 * @note It gives offset level (offset to be subtracted from the raw converted data).
2751 * Caution: Offset format is dependent to ADC resolution:
2752 * offset has to be left-aligned on bit 11, the LSB (right bits)
2754 * @rmtoll JOFR1 JOFFSET1 LL_ADC_INJ_GetOffset\n
2755 * JOFR2 JOFFSET2 LL_ADC_INJ_GetOffset\n
2756 * JOFR3 JOFFSET3 LL_ADC_INJ_GetOffset\n
2757 * JOFR4 JOFFSET4 LL_ADC_INJ_GetOffset
2758 * @param ADCx ADC instance
2759 * @param Rank This parameter can be one of the following values:
2760 * @arg @ref LL_ADC_INJ_RANK_1
2761 * @arg @ref LL_ADC_INJ_RANK_2
2762 * @arg @ref LL_ADC_INJ_RANK_3
2763 * @arg @ref LL_ADC_INJ_RANK_4
2764 * @retval Value between Min_Data=0x000 and Max_Data=0xFFF
2766 __STATIC_INLINE
uint32_t LL_ADC_INJ_GetOffset(ADC_TypeDef
*ADCx
, uint32_t Rank
)
2768 register uint32_t *preg
= __ADC_PTR_REG_OFFSET(ADCx
->JOFR1
, __ADC_MASK_SHIFT(Rank
, ADC_INJ_JOFRX_REGOFFSET_MASK
));
2770 return (uint32_t)(READ_BIT(*preg
,
2779 /** @defgroup ADC_LL_EF_Configuration_Channels Configuration of ADC hierarchical scope: channels
2784 * @brief Set sampling time of the selected ADC channel
2785 * Unit: ADC clock cycles.
2786 * @note On this device, sampling time is on channel scope: independently
2787 * of channel mapped on ADC group regular or injected.
2788 * @note In case of internal channel (VrefInt, TempSensor, ...) to be
2790 * sampling time constraints must be respected (sampling time can be
2791 * adjusted in function of ADC clock frequency and sampling time
2793 * Refer to device datasheet for timings values (parameters TS_vrefint,
2795 * @note Conversion time is the addition of sampling time and processing time.
2796 * Refer to reference manual for ADC processing time of
2798 * @note In case of ADC conversion of internal channel (VrefInt,
2799 * temperature sensor, ...), a sampling time minimum value
2801 * Refer to device datasheet.
2802 * @rmtoll SMPR1 SMP17 LL_ADC_SetChannelSamplingTime\n
2803 * SMPR1 SMP16 LL_ADC_SetChannelSamplingTime\n
2804 * SMPR1 SMP15 LL_ADC_SetChannelSamplingTime\n
2805 * SMPR1 SMP14 LL_ADC_SetChannelSamplingTime\n
2806 * SMPR1 SMP13 LL_ADC_SetChannelSamplingTime\n
2807 * SMPR1 SMP12 LL_ADC_SetChannelSamplingTime\n
2808 * SMPR1 SMP11 LL_ADC_SetChannelSamplingTime\n
2809 * SMPR1 SMP10 LL_ADC_SetChannelSamplingTime\n
2810 * SMPR2 SMP9 LL_ADC_SetChannelSamplingTime\n
2811 * SMPR2 SMP8 LL_ADC_SetChannelSamplingTime\n
2812 * SMPR2 SMP7 LL_ADC_SetChannelSamplingTime\n
2813 * SMPR2 SMP6 LL_ADC_SetChannelSamplingTime\n
2814 * SMPR2 SMP5 LL_ADC_SetChannelSamplingTime\n
2815 * SMPR2 SMP4 LL_ADC_SetChannelSamplingTime\n
2816 * SMPR2 SMP3 LL_ADC_SetChannelSamplingTime\n
2817 * SMPR2 SMP2 LL_ADC_SetChannelSamplingTime\n
2818 * SMPR2 SMP1 LL_ADC_SetChannelSamplingTime\n
2819 * SMPR2 SMP0 LL_ADC_SetChannelSamplingTime
2820 * @param ADCx ADC instance
2821 * @param Channel This parameter can be one of the following values:
2822 * @arg @ref LL_ADC_CHANNEL_0
2823 * @arg @ref LL_ADC_CHANNEL_1
2824 * @arg @ref LL_ADC_CHANNEL_2
2825 * @arg @ref LL_ADC_CHANNEL_3
2826 * @arg @ref LL_ADC_CHANNEL_4
2827 * @arg @ref LL_ADC_CHANNEL_5
2828 * @arg @ref LL_ADC_CHANNEL_6
2829 * @arg @ref LL_ADC_CHANNEL_7
2830 * @arg @ref LL_ADC_CHANNEL_8
2831 * @arg @ref LL_ADC_CHANNEL_9
2832 * @arg @ref LL_ADC_CHANNEL_10
2833 * @arg @ref LL_ADC_CHANNEL_11
2834 * @arg @ref LL_ADC_CHANNEL_12
2835 * @arg @ref LL_ADC_CHANNEL_13
2836 * @arg @ref LL_ADC_CHANNEL_14
2837 * @arg @ref LL_ADC_CHANNEL_15
2838 * @arg @ref LL_ADC_CHANNEL_16
2839 * @arg @ref LL_ADC_CHANNEL_17
2840 * @arg @ref LL_ADC_CHANNEL_VREFINT (1)
2841 * @arg @ref LL_ADC_CHANNEL_TEMPSENSOR (1)
2843 * (1) On STM32F1, parameter available only on ADC instance: ADC1.
2844 * @param SamplingTime This parameter can be one of the following values:
2845 * @arg @ref LL_ADC_SAMPLINGTIME_1CYCLE_5
2846 * @arg @ref LL_ADC_SAMPLINGTIME_7CYCLES_5
2847 * @arg @ref LL_ADC_SAMPLINGTIME_13CYCLES_5
2848 * @arg @ref LL_ADC_SAMPLINGTIME_28CYCLES_5
2849 * @arg @ref LL_ADC_SAMPLINGTIME_41CYCLES_5
2850 * @arg @ref LL_ADC_SAMPLINGTIME_55CYCLES_5
2851 * @arg @ref LL_ADC_SAMPLINGTIME_71CYCLES_5
2852 * @arg @ref LL_ADC_SAMPLINGTIME_239CYCLES_5
2855 __STATIC_INLINE
void LL_ADC_SetChannelSamplingTime(ADC_TypeDef
*ADCx
, uint32_t Channel
, uint32_t SamplingTime
)
2857 /* Set bits with content of parameter "SamplingTime" with bits position */
2858 /* in register and register position depending on parameter "Channel". */
2859 /* Parameter "Channel" is used with masks because containing */
2860 /* other bits reserved for other purpose. */
2861 register uint32_t *preg
= __ADC_PTR_REG_OFFSET(ADCx
->SMPR1
, __ADC_MASK_SHIFT(Channel
, ADC_CHANNEL_SMPRX_REGOFFSET_MASK
));
2864 ADC_SMPR2_SMP0
<< __ADC_MASK_SHIFT(Channel
, ADC_CHANNEL_SMPx_BITOFFSET_MASK
),
2865 SamplingTime
<< __ADC_MASK_SHIFT(Channel
, ADC_CHANNEL_SMPx_BITOFFSET_MASK
));
2869 * @brief Get sampling time of the selected ADC channel
2870 * Unit: ADC clock cycles.
2871 * @note On this device, sampling time is on channel scope: independently
2872 * of channel mapped on ADC group regular or injected.
2873 * @note Conversion time is the addition of sampling time and processing time.
2874 * Refer to reference manual for ADC processing time of
2876 * @rmtoll SMPR1 SMP17 LL_ADC_GetChannelSamplingTime\n
2877 * SMPR1 SMP16 LL_ADC_GetChannelSamplingTime\n
2878 * SMPR1 SMP15 LL_ADC_GetChannelSamplingTime\n
2879 * SMPR1 SMP14 LL_ADC_GetChannelSamplingTime\n
2880 * SMPR1 SMP13 LL_ADC_GetChannelSamplingTime\n
2881 * SMPR1 SMP12 LL_ADC_GetChannelSamplingTime\n
2882 * SMPR1 SMP11 LL_ADC_GetChannelSamplingTime\n
2883 * SMPR1 SMP10 LL_ADC_GetChannelSamplingTime\n
2884 * SMPR2 SMP9 LL_ADC_GetChannelSamplingTime\n
2885 * SMPR2 SMP8 LL_ADC_GetChannelSamplingTime\n
2886 * SMPR2 SMP7 LL_ADC_GetChannelSamplingTime\n
2887 * SMPR2 SMP6 LL_ADC_GetChannelSamplingTime\n
2888 * SMPR2 SMP5 LL_ADC_GetChannelSamplingTime\n
2889 * SMPR2 SMP4 LL_ADC_GetChannelSamplingTime\n
2890 * SMPR2 SMP3 LL_ADC_GetChannelSamplingTime\n
2891 * SMPR2 SMP2 LL_ADC_GetChannelSamplingTime\n
2892 * SMPR2 SMP1 LL_ADC_GetChannelSamplingTime\n
2893 * SMPR2 SMP0 LL_ADC_GetChannelSamplingTime
2894 * @param ADCx ADC instance
2895 * @param Channel This parameter can be one of the following values:
2896 * @arg @ref LL_ADC_CHANNEL_0
2897 * @arg @ref LL_ADC_CHANNEL_1
2898 * @arg @ref LL_ADC_CHANNEL_2
2899 * @arg @ref LL_ADC_CHANNEL_3
2900 * @arg @ref LL_ADC_CHANNEL_4
2901 * @arg @ref LL_ADC_CHANNEL_5
2902 * @arg @ref LL_ADC_CHANNEL_6
2903 * @arg @ref LL_ADC_CHANNEL_7
2904 * @arg @ref LL_ADC_CHANNEL_8
2905 * @arg @ref LL_ADC_CHANNEL_9
2906 * @arg @ref LL_ADC_CHANNEL_10
2907 * @arg @ref LL_ADC_CHANNEL_11
2908 * @arg @ref LL_ADC_CHANNEL_12
2909 * @arg @ref LL_ADC_CHANNEL_13
2910 * @arg @ref LL_ADC_CHANNEL_14
2911 * @arg @ref LL_ADC_CHANNEL_15
2912 * @arg @ref LL_ADC_CHANNEL_16
2913 * @arg @ref LL_ADC_CHANNEL_17
2914 * @arg @ref LL_ADC_CHANNEL_VREFINT (1)
2915 * @arg @ref LL_ADC_CHANNEL_TEMPSENSOR (1)
2917 * (1) On STM32F1, parameter available only on ADC instance: ADC1.
2918 * @retval Returned value can be one of the following values:
2919 * @arg @ref LL_ADC_SAMPLINGTIME_1CYCLE_5
2920 * @arg @ref LL_ADC_SAMPLINGTIME_7CYCLES_5
2921 * @arg @ref LL_ADC_SAMPLINGTIME_13CYCLES_5
2922 * @arg @ref LL_ADC_SAMPLINGTIME_28CYCLES_5
2923 * @arg @ref LL_ADC_SAMPLINGTIME_41CYCLES_5
2924 * @arg @ref LL_ADC_SAMPLINGTIME_55CYCLES_5
2925 * @arg @ref LL_ADC_SAMPLINGTIME_71CYCLES_5
2926 * @arg @ref LL_ADC_SAMPLINGTIME_239CYCLES_5
2928 __STATIC_INLINE
uint32_t LL_ADC_GetChannelSamplingTime(ADC_TypeDef
*ADCx
, uint32_t Channel
)
2930 register uint32_t *preg
= __ADC_PTR_REG_OFFSET(ADCx
->SMPR1
, __ADC_MASK_SHIFT(Channel
, ADC_CHANNEL_SMPRX_REGOFFSET_MASK
));
2932 return (uint32_t)(READ_BIT(*preg
,
2933 ADC_SMPR2_SMP0
<< __ADC_MASK_SHIFT(Channel
, ADC_CHANNEL_SMPx_BITOFFSET_MASK
))
2934 >> __ADC_MASK_SHIFT(Channel
, ADC_CHANNEL_SMPx_BITOFFSET_MASK
)
2942 /** @defgroup ADC_LL_EF_Configuration_ADC_AnalogWatchdog Configuration of ADC transversal scope: analog watchdog
2947 * @brief Set ADC analog watchdog monitored channels:
2948 * a single channel or all channels,
2949 * on ADC groups regular and-or injected.
2950 * @note Once monitored channels are selected, analog watchdog
2952 * @note In case of need to define a single channel to monitor
2953 * with analog watchdog from sequencer channel definition,
2954 * use helper macro @ref __LL_ADC_ANALOGWD_CHANNEL_GROUP().
2955 * @note On this STM32 serie, there is only 1 kind of analog watchdog
2957 * - AWD standard (instance AWD1):
2958 * - channels monitored: can monitor 1 channel or all channels.
2959 * - groups monitored: ADC groups regular and-or injected.
2960 * - resolution: resolution is not limited (corresponds to
2961 * ADC resolution configured).
2962 * @rmtoll CR1 AWD1CH LL_ADC_SetAnalogWDMonitChannels\n
2963 * CR1 AWD1SGL LL_ADC_SetAnalogWDMonitChannels\n
2964 * CR1 AWD1EN LL_ADC_SetAnalogWDMonitChannels
2965 * @param ADCx ADC instance
2966 * @param AWDChannelGroup This parameter can be one of the following values:
2967 * @arg @ref LL_ADC_AWD_DISABLE
2968 * @arg @ref LL_ADC_AWD_ALL_CHANNELS_REG
2969 * @arg @ref LL_ADC_AWD_ALL_CHANNELS_INJ
2970 * @arg @ref LL_ADC_AWD_ALL_CHANNELS_REG_INJ
2971 * @arg @ref LL_ADC_AWD_CHANNEL_0_REG
2972 * @arg @ref LL_ADC_AWD_CHANNEL_0_INJ
2973 * @arg @ref LL_ADC_AWD_CHANNEL_0_REG_INJ
2974 * @arg @ref LL_ADC_AWD_CHANNEL_1_REG
2975 * @arg @ref LL_ADC_AWD_CHANNEL_1_INJ
2976 * @arg @ref LL_ADC_AWD_CHANNEL_1_REG_INJ
2977 * @arg @ref LL_ADC_AWD_CHANNEL_2_REG
2978 * @arg @ref LL_ADC_AWD_CHANNEL_2_INJ
2979 * @arg @ref LL_ADC_AWD_CHANNEL_2_REG_INJ
2980 * @arg @ref LL_ADC_AWD_CHANNEL_3_REG
2981 * @arg @ref LL_ADC_AWD_CHANNEL_3_INJ
2982 * @arg @ref LL_ADC_AWD_CHANNEL_3_REG_INJ
2983 * @arg @ref LL_ADC_AWD_CHANNEL_4_REG
2984 * @arg @ref LL_ADC_AWD_CHANNEL_4_INJ
2985 * @arg @ref LL_ADC_AWD_CHANNEL_4_REG_INJ
2986 * @arg @ref LL_ADC_AWD_CHANNEL_5_REG
2987 * @arg @ref LL_ADC_AWD_CHANNEL_5_INJ
2988 * @arg @ref LL_ADC_AWD_CHANNEL_5_REG_INJ
2989 * @arg @ref LL_ADC_AWD_CHANNEL_6_REG
2990 * @arg @ref LL_ADC_AWD_CHANNEL_6_INJ
2991 * @arg @ref LL_ADC_AWD_CHANNEL_6_REG_INJ
2992 * @arg @ref LL_ADC_AWD_CHANNEL_7_REG
2993 * @arg @ref LL_ADC_AWD_CHANNEL_7_INJ
2994 * @arg @ref LL_ADC_AWD_CHANNEL_7_REG_INJ
2995 * @arg @ref LL_ADC_AWD_CHANNEL_8_REG
2996 * @arg @ref LL_ADC_AWD_CHANNEL_8_INJ
2997 * @arg @ref LL_ADC_AWD_CHANNEL_8_REG_INJ
2998 * @arg @ref LL_ADC_AWD_CHANNEL_9_REG
2999 * @arg @ref LL_ADC_AWD_CHANNEL_9_INJ
3000 * @arg @ref LL_ADC_AWD_CHANNEL_9_REG_INJ
3001 * @arg @ref LL_ADC_AWD_CHANNEL_10_REG
3002 * @arg @ref LL_ADC_AWD_CHANNEL_10_INJ
3003 * @arg @ref LL_ADC_AWD_CHANNEL_10_REG_INJ
3004 * @arg @ref LL_ADC_AWD_CHANNEL_11_REG
3005 * @arg @ref LL_ADC_AWD_CHANNEL_11_INJ
3006 * @arg @ref LL_ADC_AWD_CHANNEL_11_REG_INJ
3007 * @arg @ref LL_ADC_AWD_CHANNEL_12_REG
3008 * @arg @ref LL_ADC_AWD_CHANNEL_12_INJ
3009 * @arg @ref LL_ADC_AWD_CHANNEL_12_REG_INJ
3010 * @arg @ref LL_ADC_AWD_CHANNEL_13_REG
3011 * @arg @ref LL_ADC_AWD_CHANNEL_13_INJ
3012 * @arg @ref LL_ADC_AWD_CHANNEL_13_REG_INJ
3013 * @arg @ref LL_ADC_AWD_CHANNEL_14_REG
3014 * @arg @ref LL_ADC_AWD_CHANNEL_14_INJ
3015 * @arg @ref LL_ADC_AWD_CHANNEL_14_REG_INJ
3016 * @arg @ref LL_ADC_AWD_CHANNEL_15_REG
3017 * @arg @ref LL_ADC_AWD_CHANNEL_15_INJ
3018 * @arg @ref LL_ADC_AWD_CHANNEL_15_REG_INJ
3019 * @arg @ref LL_ADC_AWD_CHANNEL_16_REG
3020 * @arg @ref LL_ADC_AWD_CHANNEL_16_INJ
3021 * @arg @ref LL_ADC_AWD_CHANNEL_16_REG_INJ
3022 * @arg @ref LL_ADC_AWD_CHANNEL_17_REG
3023 * @arg @ref LL_ADC_AWD_CHANNEL_17_INJ
3024 * @arg @ref LL_ADC_AWD_CHANNEL_17_REG_INJ
3025 * @arg @ref LL_ADC_AWD_CH_VREFINT_REG (1)
3026 * @arg @ref LL_ADC_AWD_CH_VREFINT_INJ (1)
3027 * @arg @ref LL_ADC_AWD_CH_VREFINT_REG_INJ (1)
3028 * @arg @ref LL_ADC_AWD_CH_TEMPSENSOR_REG (1)
3029 * @arg @ref LL_ADC_AWD_CH_TEMPSENSOR_INJ (1)
3030 * @arg @ref LL_ADC_AWD_CH_TEMPSENSOR_REG_INJ (1)
3032 * (1) On STM32F1, parameter available only on ADC instance: ADC1.
3035 __STATIC_INLINE
void LL_ADC_SetAnalogWDMonitChannels(ADC_TypeDef
*ADCx
, uint32_t AWDChannelGroup
)
3037 MODIFY_REG(ADCx
->CR1
,
3038 (ADC_CR1_AWDEN
| ADC_CR1_JAWDEN
| ADC_CR1_AWDSGL
| ADC_CR1_AWDCH
),
3043 * @brief Get ADC analog watchdog monitored channel.
3044 * @note Usage of the returned channel number:
3045 * - To reinject this channel into another function LL_ADC_xxx:
3046 * the returned channel number is only partly formatted on definition
3047 * of literals LL_ADC_CHANNEL_x. Therefore, it has to be compared
3048 * with parts of literals LL_ADC_CHANNEL_x or using
3049 * helper macro @ref __LL_ADC_CHANNEL_TO_DECIMAL_NB().
3050 * Then the selected literal LL_ADC_CHANNEL_x can be used
3051 * as parameter for another function.
3052 * - To get the channel number in decimal format:
3053 * process the returned value with the helper macro
3054 * @ref __LL_ADC_CHANNEL_TO_DECIMAL_NB().
3055 * Applicable only when the analog watchdog is set to monitor
3057 * @note On this STM32 serie, there is only 1 kind of analog watchdog
3059 * - AWD standard (instance AWD1):
3060 * - channels monitored: can monitor 1 channel or all channels.
3061 * - groups monitored: ADC groups regular and-or injected.
3062 * - resolution: resolution is not limited (corresponds to
3063 * ADC resolution configured).
3064 * @rmtoll CR1 AWD1CH LL_ADC_GetAnalogWDMonitChannels\n
3065 * CR1 AWD1SGL LL_ADC_GetAnalogWDMonitChannels\n
3066 * CR1 AWD1EN LL_ADC_GetAnalogWDMonitChannels
3067 * @param ADCx ADC instance
3068 * @retval Returned value can be one of the following values:
3069 * @arg @ref LL_ADC_AWD_DISABLE
3070 * @arg @ref LL_ADC_AWD_ALL_CHANNELS_REG
3071 * @arg @ref LL_ADC_AWD_ALL_CHANNELS_INJ
3072 * @arg @ref LL_ADC_AWD_ALL_CHANNELS_REG_INJ
3073 * @arg @ref LL_ADC_AWD_CHANNEL_0_REG
3074 * @arg @ref LL_ADC_AWD_CHANNEL_0_INJ
3075 * @arg @ref LL_ADC_AWD_CHANNEL_0_REG_INJ
3076 * @arg @ref LL_ADC_AWD_CHANNEL_1_REG
3077 * @arg @ref LL_ADC_AWD_CHANNEL_1_INJ
3078 * @arg @ref LL_ADC_AWD_CHANNEL_1_REG_INJ
3079 * @arg @ref LL_ADC_AWD_CHANNEL_2_REG
3080 * @arg @ref LL_ADC_AWD_CHANNEL_2_INJ
3081 * @arg @ref LL_ADC_AWD_CHANNEL_2_REG_INJ
3082 * @arg @ref LL_ADC_AWD_CHANNEL_3_REG
3083 * @arg @ref LL_ADC_AWD_CHANNEL_3_INJ
3084 * @arg @ref LL_ADC_AWD_CHANNEL_3_REG_INJ
3085 * @arg @ref LL_ADC_AWD_CHANNEL_4_REG
3086 * @arg @ref LL_ADC_AWD_CHANNEL_4_INJ
3087 * @arg @ref LL_ADC_AWD_CHANNEL_4_REG_INJ
3088 * @arg @ref LL_ADC_AWD_CHANNEL_5_REG
3089 * @arg @ref LL_ADC_AWD_CHANNEL_5_INJ
3090 * @arg @ref LL_ADC_AWD_CHANNEL_5_REG_INJ
3091 * @arg @ref LL_ADC_AWD_CHANNEL_6_REG
3092 * @arg @ref LL_ADC_AWD_CHANNEL_6_INJ
3093 * @arg @ref LL_ADC_AWD_CHANNEL_6_REG_INJ
3094 * @arg @ref LL_ADC_AWD_CHANNEL_7_REG
3095 * @arg @ref LL_ADC_AWD_CHANNEL_7_INJ
3096 * @arg @ref LL_ADC_AWD_CHANNEL_7_REG_INJ
3097 * @arg @ref LL_ADC_AWD_CHANNEL_8_REG
3098 * @arg @ref LL_ADC_AWD_CHANNEL_8_INJ
3099 * @arg @ref LL_ADC_AWD_CHANNEL_8_REG_INJ
3100 * @arg @ref LL_ADC_AWD_CHANNEL_9_REG
3101 * @arg @ref LL_ADC_AWD_CHANNEL_9_INJ
3102 * @arg @ref LL_ADC_AWD_CHANNEL_9_REG_INJ
3103 * @arg @ref LL_ADC_AWD_CHANNEL_10_REG
3104 * @arg @ref LL_ADC_AWD_CHANNEL_10_INJ
3105 * @arg @ref LL_ADC_AWD_CHANNEL_10_REG_INJ
3106 * @arg @ref LL_ADC_AWD_CHANNEL_11_REG
3107 * @arg @ref LL_ADC_AWD_CHANNEL_11_INJ
3108 * @arg @ref LL_ADC_AWD_CHANNEL_11_REG_INJ
3109 * @arg @ref LL_ADC_AWD_CHANNEL_12_REG
3110 * @arg @ref LL_ADC_AWD_CHANNEL_12_INJ
3111 * @arg @ref LL_ADC_AWD_CHANNEL_12_REG_INJ
3112 * @arg @ref LL_ADC_AWD_CHANNEL_13_REG
3113 * @arg @ref LL_ADC_AWD_CHANNEL_13_INJ
3114 * @arg @ref LL_ADC_AWD_CHANNEL_13_REG_INJ
3115 * @arg @ref LL_ADC_AWD_CHANNEL_14_REG
3116 * @arg @ref LL_ADC_AWD_CHANNEL_14_INJ
3117 * @arg @ref LL_ADC_AWD_CHANNEL_14_REG_INJ
3118 * @arg @ref LL_ADC_AWD_CHANNEL_15_REG
3119 * @arg @ref LL_ADC_AWD_CHANNEL_15_INJ
3120 * @arg @ref LL_ADC_AWD_CHANNEL_15_REG_INJ
3121 * @arg @ref LL_ADC_AWD_CHANNEL_16_REG
3122 * @arg @ref LL_ADC_AWD_CHANNEL_16_INJ
3123 * @arg @ref LL_ADC_AWD_CHANNEL_16_REG_INJ
3124 * @arg @ref LL_ADC_AWD_CHANNEL_17_REG
3125 * @arg @ref LL_ADC_AWD_CHANNEL_17_INJ
3126 * @arg @ref LL_ADC_AWD_CHANNEL_17_REG_INJ
3128 __STATIC_INLINE
uint32_t LL_ADC_GetAnalogWDMonitChannels(ADC_TypeDef
*ADCx
)
3130 return (uint32_t)(READ_BIT(ADCx
->CR1
, (ADC_CR1_AWDEN
| ADC_CR1_JAWDEN
| ADC_CR1_AWDSGL
| ADC_CR1_AWDCH
)));
3134 * @brief Set ADC analog watchdog threshold value of threshold
3136 * @note On this STM32 serie, there is only 1 kind of analog watchdog
3138 * - AWD standard (instance AWD1):
3139 * - channels monitored: can monitor 1 channel or all channels.
3140 * - groups monitored: ADC groups regular and-or injected.
3141 * - resolution: resolution is not limited (corresponds to
3142 * ADC resolution configured).
3143 * @rmtoll HTR HT LL_ADC_SetAnalogWDThresholds\n
3144 * LTR LT LL_ADC_SetAnalogWDThresholds
3145 * @param ADCx ADC instance
3146 * @param AWDThresholdsHighLow This parameter can be one of the following values:
3147 * @arg @ref LL_ADC_AWD_THRESHOLD_HIGH
3148 * @arg @ref LL_ADC_AWD_THRESHOLD_LOW
3149 * @param AWDThresholdValue: Value between Min_Data=0x000 and Max_Data=0xFFF
3152 __STATIC_INLINE
void LL_ADC_SetAnalogWDThresholds(ADC_TypeDef
*ADCx
, uint32_t AWDThresholdsHighLow
, uint32_t AWDThresholdValue
)
3154 register uint32_t *preg
= __ADC_PTR_REG_OFFSET(ADCx
->HTR
, AWDThresholdsHighLow
);
3162 * @brief Get ADC analog watchdog threshold value of threshold high or
3164 * @note In case of ADC resolution different of 12 bits,
3165 * analog watchdog thresholds data require a specific shift.
3166 * Use helper macro @ref __LL_ADC_ANALOGWD_GET_THRESHOLD_RESOLUTION().
3167 * @rmtoll HTR HT LL_ADC_GetAnalogWDThresholds\n
3168 * LTR LT LL_ADC_GetAnalogWDThresholds
3169 * @param ADCx ADC instance
3170 * @param AWDThresholdsHighLow This parameter can be one of the following values:
3171 * @arg @ref LL_ADC_AWD_THRESHOLD_HIGH
3172 * @arg @ref LL_ADC_AWD_THRESHOLD_LOW
3173 * @retval Value between Min_Data=0x000 and Max_Data=0xFFF
3175 __STATIC_INLINE
uint32_t LL_ADC_GetAnalogWDThresholds(ADC_TypeDef
*ADCx
, uint32_t AWDThresholdsHighLow
)
3177 register uint32_t *preg
= __ADC_PTR_REG_OFFSET(ADCx
->HTR
, AWDThresholdsHighLow
);
3179 return (uint32_t)(READ_BIT(*preg
, ADC_HTR_HT
));
3186 /** @defgroup ADC_LL_EF_Configuration_ADC_Multimode Configuration of ADC hierarchical scope: multimode
3190 #if defined(ADC_MULTIMODE_SUPPORT)
3192 * @brief Set ADC multimode configuration to operate in independent mode
3193 * or multimode (for devices with several ADC instances).
3194 * @note If multimode configuration: the selected ADC instance is
3195 * either master or slave depending on hardware.
3196 * Refer to reference manual.
3197 * @rmtoll CR1 DUALMOD LL_ADC_SetMultimode
3198 * @param ADCxy_COMMON ADC common instance
3199 * (can be set directly from CMSIS definition or by using helper macro @ref __LL_ADC_COMMON_INSTANCE() )
3200 * @param Multimode This parameter can be one of the following values:
3201 * @arg @ref LL_ADC_MULTI_INDEPENDENT
3202 * @arg @ref LL_ADC_MULTI_DUAL_REG_SIMULT
3203 * @arg @ref LL_ADC_MULTI_DUAL_REG_INTERL_FAST
3204 * @arg @ref LL_ADC_MULTI_DUAL_REG_INTERL_SLOW
3205 * @arg @ref LL_ADC_MULTI_DUAL_INJ_SIMULT
3206 * @arg @ref LL_ADC_MULTI_DUAL_INJ_ALTERN
3207 * @arg @ref LL_ADC_MULTI_DUAL_REG_SIM_INJ_SIM
3208 * @arg @ref LL_ADC_MULTI_DUAL_REG_SIM_INJ_ALT
3209 * @arg @ref LL_ADC_MULTI_DUAL_REG_INTFAST_INJ_SIM
3210 * @arg @ref LL_ADC_MULTI_DUAL_REG_INTSLOW_INJ_SIM
3213 __STATIC_INLINE
void LL_ADC_SetMultimode(ADC_Common_TypeDef
*ADCxy_COMMON
, uint32_t Multimode
)
3215 MODIFY_REG(ADCxy_COMMON
->CR1
, ADC_CR1_DUALMOD
, Multimode
);
3219 * @brief Get ADC multimode configuration to operate in independent mode
3220 * or multimode (for devices with several ADC instances).
3221 * @note If multimode configuration: the selected ADC instance is
3222 * either master or slave depending on hardware.
3223 * Refer to reference manual.
3224 * @rmtoll CR1 DUALMOD LL_ADC_GetMultimode
3225 * @param ADCxy_COMMON ADC common instance
3226 * (can be set directly from CMSIS definition or by using helper macro @ref __LL_ADC_COMMON_INSTANCE() )
3227 * @retval Returned value can be one of the following values:
3228 * @arg @ref LL_ADC_MULTI_INDEPENDENT
3229 * @arg @ref LL_ADC_MULTI_DUAL_REG_SIMULT
3230 * @arg @ref LL_ADC_MULTI_DUAL_REG_INTERL_FAST
3231 * @arg @ref LL_ADC_MULTI_DUAL_REG_INTERL_SLOW
3232 * @arg @ref LL_ADC_MULTI_DUAL_INJ_SIMULT
3233 * @arg @ref LL_ADC_MULTI_DUAL_INJ_ALTERN
3234 * @arg @ref LL_ADC_MULTI_DUAL_REG_SIM_INJ_SIM
3235 * @arg @ref LL_ADC_MULTI_DUAL_REG_SIM_INJ_ALT
3236 * @arg @ref LL_ADC_MULTI_DUAL_REG_INTFAST_INJ_SIM
3237 * @arg @ref LL_ADC_MULTI_DUAL_REG_INTSLOW_INJ_SIM
3239 __STATIC_INLINE
uint32_t LL_ADC_GetMultimode(ADC_Common_TypeDef
*ADCxy_COMMON
)
3241 return (uint32_t)(READ_BIT(ADCxy_COMMON
->CR1
, ADC_CR1_DUALMOD
));
3244 #endif /* ADC_MULTIMODE_SUPPORT */
3249 /** @defgroup ADC_LL_EF_Operation_ADC_Instance Operation on ADC hierarchical scope: ADC instance
3254 * @brief Enable the selected ADC instance.
3255 * @note On this STM32 serie, after ADC enable, a delay for
3256 * ADC internal analog stabilization is required before performing a
3257 * ADC conversion start.
3258 * Refer to device datasheet, parameter tSTAB.
3259 * @rmtoll CR2 ADON LL_ADC_Enable
3260 * @param ADCx ADC instance
3263 __STATIC_INLINE
void LL_ADC_Enable(ADC_TypeDef
*ADCx
)
3265 SET_BIT(ADCx
->CR2
, ADC_CR2_ADON
);
3269 * @brief Disable the selected ADC instance.
3270 * @rmtoll CR2 ADON LL_ADC_Disable
3271 * @param ADCx ADC instance
3274 __STATIC_INLINE
void LL_ADC_Disable(ADC_TypeDef
*ADCx
)
3276 CLEAR_BIT(ADCx
->CR2
, ADC_CR2_ADON
);
3280 * @brief Get the selected ADC instance enable state.
3281 * @rmtoll CR2 ADON LL_ADC_IsEnabled
3282 * @param ADCx ADC instance
3283 * @retval 0: ADC is disabled, 1: ADC is enabled.
3285 __STATIC_INLINE
uint32_t LL_ADC_IsEnabled(ADC_TypeDef
*ADCx
)
3287 return (READ_BIT(ADCx
->CR2
, ADC_CR2_ADON
) == (ADC_CR2_ADON
));
3291 * @brief Start ADC calibration in the mode single-ended
3292 * or differential (for devices with differential mode available).
3293 * @note On this STM32 serie, before starting a calibration,
3294 * ADC must be disabled.
3295 * A minimum number of ADC clock cycles are required
3296 * between ADC disable state and calibration start.
3297 * Refer to literal @ref LL_ADC_DELAY_DISABLE_CALIB_ADC_CYCLES.
3298 * @note On this STM32 serie, hardware prerequisite before starting a calibration:
3299 the ADC must have been in power-on state for at least
3300 two ADC clock cycles.
3301 * @rmtoll CR2 CAL LL_ADC_StartCalibration
3302 * @param ADCx ADC instance
3305 __STATIC_INLINE
void LL_ADC_StartCalibration(ADC_TypeDef
*ADCx
)
3307 SET_BIT(ADCx
->CR2
, ADC_CR2_CAL
);
3311 * @brief Get ADC calibration state.
3312 * @rmtoll CR2 CAL LL_ADC_IsCalibrationOnGoing
3313 * @param ADCx ADC instance
3314 * @retval 0: calibration complete, 1: calibration in progress.
3316 __STATIC_INLINE
uint32_t LL_ADC_IsCalibrationOnGoing(ADC_TypeDef
*ADCx
)
3318 return (READ_BIT(ADCx
->CR2
, ADC_CR2_CAL
) == (ADC_CR2_CAL
));
3325 /** @defgroup ADC_LL_EF_Operation_ADC_Group_Regular Operation on ADC hierarchical scope: group regular
3330 * @brief Start ADC group regular conversion.
3331 * @note On this STM32 serie, this function is relevant only for
3332 * internal trigger (SW start), not for external trigger:
3333 * - If ADC trigger has been set to software start, ADC conversion
3334 * starts immediately.
3335 * - If ADC trigger has been set to external trigger, ADC conversion
3336 * start must be performed using function
3337 * @ref LL_ADC_REG_StartConversionExtTrig().
3338 * (if external trigger edge would have been set during ADC other
3339 * settings, ADC conversion would start at trigger event
3340 * as soon as ADC is enabled).
3341 * @rmtoll CR2 SWSTART LL_ADC_REG_StartConversionSWStart
3342 * @param ADCx ADC instance
3345 __STATIC_INLINE
void LL_ADC_REG_StartConversionSWStart(ADC_TypeDef
*ADCx
)
3347 SET_BIT(ADCx
->CR2
, (ADC_CR2_SWSTART
| ADC_CR2_EXTTRIG
));
3351 * @brief Start ADC group regular conversion from external trigger.
3352 * @note ADC conversion will start at next trigger event (on the selected
3353 * trigger edge) following the ADC start conversion command.
3354 * @note On this STM32 serie, this function is relevant for
3355 * ADC conversion start from external trigger.
3356 * If internal trigger (SW start) is needed, perform ADC conversion
3357 * start using function @ref LL_ADC_REG_StartConversionSWStart().
3358 * @rmtoll CR2 EXTEN LL_ADC_REG_StartConversionExtTrig
3359 * @param ExternalTriggerEdge This parameter can be one of the following values:
3360 * @arg @ref LL_ADC_REG_TRIG_EXT_RISING
3361 * @param ADCx ADC instance
3364 __STATIC_INLINE
void LL_ADC_REG_StartConversionExtTrig(ADC_TypeDef
*ADCx
, uint32_t ExternalTriggerEdge
)
3366 SET_BIT(ADCx
->CR2
, ExternalTriggerEdge
);
3370 * @brief Stop ADC group regular conversion from external trigger.
3371 * @note No more ADC conversion will start at next trigger event
3372 * following the ADC stop conversion command.
3373 * If a conversion is on-going, it will be completed.
3374 * @note On this STM32 serie, there is no specific command
3375 * to stop a conversion on-going or to stop ADC converting
3376 * in continuous mode. These actions can be performed
3377 * using function @ref LL_ADC_Disable().
3378 * @rmtoll CR2 EXTSEL LL_ADC_REG_StopConversionExtTrig
3379 * @param ADCx ADC instance
3382 __STATIC_INLINE
void LL_ADC_REG_StopConversionExtTrig(ADC_TypeDef
*ADCx
)
3384 CLEAR_BIT(ADCx
->CR2
, ADC_CR2_EXTSEL
);
3388 * @brief Get ADC group regular conversion data, range fit for
3389 * all ADC configurations: all ADC resolutions and
3390 * all oversampling increased data width (for devices
3391 * with feature oversampling).
3392 * @rmtoll DR RDATA LL_ADC_REG_ReadConversionData32
3393 * @param ADCx ADC instance
3394 * @retval Value between Min_Data=0x00000000 and Max_Data=0xFFFFFFFF
3396 __STATIC_INLINE
uint32_t LL_ADC_REG_ReadConversionData32(ADC_TypeDef
*ADCx
)
3398 return (uint16_t)(READ_BIT(ADCx
->DR
, ADC_DR_DATA
));
3402 * @brief Get ADC group regular conversion data, range fit for
3403 * ADC resolution 12 bits.
3404 * @note For devices with feature oversampling: Oversampling
3405 * can increase data width, function for extended range
3406 * may be needed: @ref LL_ADC_REG_ReadConversionData32.
3407 * @rmtoll DR RDATA LL_ADC_REG_ReadConversionData12
3408 * @param ADCx ADC instance
3409 * @retval Value between Min_Data=0x000 and Max_Data=0xFFF
3411 __STATIC_INLINE
uint16_t LL_ADC_REG_ReadConversionData12(ADC_TypeDef
*ADCx
)
3413 return (uint16_t)(READ_BIT(ADCx
->DR
, ADC_DR_DATA
));
3416 #if defined(ADC_MULTIMODE_SUPPORT)
3418 * @brief Get ADC multimode conversion data of ADC master, ADC slave
3419 * or raw data with ADC master and slave concatenated.
3420 * @note If raw data with ADC master and slave concatenated is retrieved,
3421 * a macro is available to get the conversion data of
3422 * ADC master or ADC slave: see helper macro
3423 * @ref __LL_ADC_MULTI_CONV_DATA_MASTER_SLAVE().
3424 * (however this macro is mainly intended for multimode
3425 * transfer by DMA, because this function can do the same
3426 * by getting multimode conversion data of ADC master or ADC slave
3428 * @rmtoll DR DATA LL_ADC_REG_ReadMultiConversionData32\n
3429 * DR ADC2DATA LL_ADC_REG_ReadMultiConversionData32
3430 * @param ADCx ADC instance
3431 * (can be set directly from CMSIS definition or by using helper macro @ref __LL_ADC_COMMON_INSTANCE() )
3432 * @param ConversionData This parameter can be one of the following values:
3433 * @arg @ref LL_ADC_MULTI_MASTER
3434 * @arg @ref LL_ADC_MULTI_SLAVE
3435 * @arg @ref LL_ADC_MULTI_MASTER_SLAVE
3436 * @retval Value between Min_Data=0x00000000 and Max_Data=0xFFFFFFFF
3438 __STATIC_INLINE
uint32_t LL_ADC_REG_ReadMultiConversionData32(ADC_TypeDef
*ADCx
, uint32_t ConversionData
)
3440 return (uint32_t)(READ_BIT(ADCx
->DR
,
3442 >> POSITION_VAL(ConversionData
)
3445 #endif /* ADC_MULTIMODE_SUPPORT */
3451 /** @defgroup ADC_LL_EF_Operation_ADC_Group_Injected Operation on ADC hierarchical scope: group injected
3456 * @brief Start ADC group injected conversion.
3457 * @note On this STM32 serie, this function is relevant only for
3458 * internal trigger (SW start), not for external trigger:
3459 * - If ADC trigger has been set to software start, ADC conversion
3460 * starts immediately.
3461 * - If ADC trigger has been set to external trigger, ADC conversion
3462 * start must be performed using function
3463 * @ref LL_ADC_INJ_StartConversionExtTrig().
3464 * (if external trigger edge would have been set during ADC other
3465 * settings, ADC conversion would start at trigger event
3466 * as soon as ADC is enabled).
3467 * @rmtoll CR2 JSWSTART LL_ADC_INJ_StartConversionSWStart
3468 * @param ADCx ADC instance
3471 __STATIC_INLINE
void LL_ADC_INJ_StartConversionSWStart(ADC_TypeDef
*ADCx
)
3473 SET_BIT(ADCx
->CR2
, (ADC_CR2_JSWSTART
| ADC_CR2_JEXTTRIG
));
3477 * @brief Start ADC group injected conversion from external trigger.
3478 * @note ADC conversion will start at next trigger event (on the selected
3479 * trigger edge) following the ADC start conversion command.
3480 * @note On this STM32 serie, this function is relevant for
3481 * ADC conversion start from external trigger.
3482 * If internal trigger (SW start) is needed, perform ADC conversion
3483 * start using function @ref LL_ADC_INJ_StartConversionSWStart().
3484 * @rmtoll CR2 JEXTEN LL_ADC_INJ_StartConversionExtTrig
3485 * @param ExternalTriggerEdge This parameter can be one of the following values:
3486 * @arg @ref LL_ADC_INJ_TRIG_EXT_RISING
3487 * @param ADCx ADC instance
3490 __STATIC_INLINE
void LL_ADC_INJ_StartConversionExtTrig(ADC_TypeDef
*ADCx
, uint32_t ExternalTriggerEdge
)
3492 SET_BIT(ADCx
->CR2
, ExternalTriggerEdge
);
3496 * @brief Stop ADC group injected conversion from external trigger.
3497 * @note No more ADC conversion will start at next trigger event
3498 * following the ADC stop conversion command.
3499 * If a conversion is on-going, it will be completed.
3500 * @note On this STM32 serie, there is no specific command
3501 * to stop a conversion on-going or to stop ADC converting
3502 * in continuous mode. These actions can be performed
3503 * using function @ref LL_ADC_Disable().
3504 * @rmtoll CR2 JEXTSEL LL_ADC_INJ_StopConversionExtTrig
3505 * @param ADCx ADC instance
3508 __STATIC_INLINE
void LL_ADC_INJ_StopConversionExtTrig(ADC_TypeDef
*ADCx
)
3510 CLEAR_BIT(ADCx
->CR2
, ADC_CR2_JEXTSEL
);
3514 * @brief Get ADC group regular conversion data, range fit for
3515 * all ADC configurations: all ADC resolutions and
3516 * all oversampling increased data width (for devices
3517 * with feature oversampling).
3518 * @rmtoll JDR1 JDATA LL_ADC_INJ_ReadConversionData32\n
3519 * JDR2 JDATA LL_ADC_INJ_ReadConversionData32\n
3520 * JDR3 JDATA LL_ADC_INJ_ReadConversionData32\n
3521 * JDR4 JDATA LL_ADC_INJ_ReadConversionData32
3522 * @param ADCx ADC instance
3523 * @param Rank This parameter can be one of the following values:
3524 * @arg @ref LL_ADC_INJ_RANK_1
3525 * @arg @ref LL_ADC_INJ_RANK_2
3526 * @arg @ref LL_ADC_INJ_RANK_3
3527 * @arg @ref LL_ADC_INJ_RANK_4
3528 * @retval Value between Min_Data=0x00000000 and Max_Data=0xFFFFFFFF
3530 __STATIC_INLINE
uint32_t LL_ADC_INJ_ReadConversionData32(ADC_TypeDef
*ADCx
, uint32_t Rank
)
3532 register uint32_t *preg
= __ADC_PTR_REG_OFFSET(ADCx
->JDR1
, __ADC_MASK_SHIFT(Rank
, ADC_INJ_JDRX_REGOFFSET_MASK
));
3534 return (uint32_t)(READ_BIT(*preg
,
3540 * @brief Get ADC group injected conversion data, range fit for
3541 * ADC resolution 12 bits.
3542 * @note For devices with feature oversampling: Oversampling
3543 * can increase data width, function for extended range
3544 * may be needed: @ref LL_ADC_INJ_ReadConversionData32.
3545 * @rmtoll JDR1 JDATA LL_ADC_INJ_ReadConversionData12\n
3546 * JDR2 JDATA LL_ADC_INJ_ReadConversionData12\n
3547 * JDR3 JDATA LL_ADC_INJ_ReadConversionData12\n
3548 * JDR4 JDATA LL_ADC_INJ_ReadConversionData12
3549 * @param ADCx ADC instance
3550 * @param Rank This parameter can be one of the following values:
3551 * @arg @ref LL_ADC_INJ_RANK_1
3552 * @arg @ref LL_ADC_INJ_RANK_2
3553 * @arg @ref LL_ADC_INJ_RANK_3
3554 * @arg @ref LL_ADC_INJ_RANK_4
3555 * @retval Value between Min_Data=0x000 and Max_Data=0xFFF
3557 __STATIC_INLINE
uint16_t LL_ADC_INJ_ReadConversionData12(ADC_TypeDef
*ADCx
, uint32_t Rank
)
3559 register uint32_t *preg
= __ADC_PTR_REG_OFFSET(ADCx
->JDR1
, __ADC_MASK_SHIFT(Rank
, ADC_INJ_JDRX_REGOFFSET_MASK
));
3561 return (uint16_t)(READ_BIT(*preg
,
3570 /** @defgroup ADC_LL_EF_FLAG_Management ADC flag management
3575 * @brief Get flag ADC group regular end of sequence conversions.
3576 * @rmtoll SR EOC LL_ADC_IsActiveFlag_EOS
3577 * @param ADCx ADC instance
3578 * @retval State of bit (1 or 0).
3580 __STATIC_INLINE
uint32_t LL_ADC_IsActiveFlag_EOS(ADC_TypeDef
*ADCx
)
3582 /* Note: on this STM32 serie, there is no flag ADC group regular */
3583 /* end of unitary conversion. */
3584 /* Flag noted as "EOC" is corresponding to flag "EOS" */
3585 /* in other STM32 families). */
3586 return (READ_BIT(ADCx
->SR
, LL_ADC_FLAG_EOS
) == (LL_ADC_FLAG_EOS
));
3591 * @brief Get flag ADC group injected end of sequence conversions.
3592 * @rmtoll SR JEOC LL_ADC_IsActiveFlag_JEOS
3593 * @param ADCx ADC instance
3594 * @retval State of bit (1 or 0).
3596 __STATIC_INLINE
uint32_t LL_ADC_IsActiveFlag_JEOS(ADC_TypeDef
*ADCx
)
3598 /* Note: on this STM32 serie, there is no flag ADC group injected */
3599 /* end of unitary conversion. */
3600 /* Flag noted as "JEOC" is corresponding to flag "JEOS" */
3601 /* in other STM32 families). */
3602 return (READ_BIT(ADCx
->SR
, LL_ADC_FLAG_JEOS
) == (LL_ADC_FLAG_JEOS
));
3606 * @brief Get flag ADC analog watchdog 1 flag
3607 * @rmtoll SR AWD LL_ADC_IsActiveFlag_AWD1
3608 * @param ADCx ADC instance
3609 * @retval State of bit (1 or 0).
3611 __STATIC_INLINE
uint32_t LL_ADC_IsActiveFlag_AWD1(ADC_TypeDef
*ADCx
)
3613 return (READ_BIT(ADCx
->SR
, LL_ADC_FLAG_AWD1
) == (LL_ADC_FLAG_AWD1
));
3617 * @brief Clear flag ADC group regular end of sequence conversions.
3618 * @rmtoll SR EOC LL_ADC_ClearFlag_EOS
3619 * @param ADCx ADC instance
3622 __STATIC_INLINE
void LL_ADC_ClearFlag_EOS(ADC_TypeDef
*ADCx
)
3624 /* Note: on this STM32 serie, there is no flag ADC group regular */
3625 /* end of unitary conversion. */
3626 /* Flag noted as "EOC" is corresponding to flag "EOS" */
3627 /* in other STM32 families). */
3628 WRITE_REG(ADCx
->SR
, ~LL_ADC_FLAG_EOS
);
3633 * @brief Clear flag ADC group injected end of sequence conversions.
3634 * @rmtoll SR JEOC LL_ADC_ClearFlag_JEOS
3635 * @param ADCx ADC instance
3638 __STATIC_INLINE
void LL_ADC_ClearFlag_JEOS(ADC_TypeDef
*ADCx
)
3640 /* Note: on this STM32 serie, there is no flag ADC group injected */
3641 /* end of unitary conversion. */
3642 /* Flag noted as "JEOC" is corresponding to flag "JEOS" */
3643 /* in other STM32 families). */
3644 WRITE_REG(ADCx
->SR
, ~LL_ADC_FLAG_JEOS
);
3648 * @brief Clear flag ADC analog watchdog 1.
3649 * @rmtoll SR AWD LL_ADC_ClearFlag_AWD1
3650 * @param ADCx ADC instance
3653 __STATIC_INLINE
void LL_ADC_ClearFlag_AWD1(ADC_TypeDef
*ADCx
)
3655 WRITE_REG(ADCx
->SR
, ~LL_ADC_FLAG_AWD1
);
3658 #if defined(ADC_MULTIMODE_SUPPORT)
3660 * @brief Get flag multimode ADC group regular end of sequence conversions of the ADC master.
3661 * @rmtoll SR EOC LL_ADC_IsActiveFlag_MST_EOS
3662 * @param ADCxy_COMMON ADC common instance
3663 * (can be set directly from CMSIS definition or by using helper macro @ref __LL_ADC_COMMON_INSTANCE() )
3664 * @retval State of bit (1 or 0).
3666 __STATIC_INLINE
uint32_t LL_ADC_IsActiveFlag_MST_EOS(ADC_Common_TypeDef
*ADCxy_COMMON
)
3668 /* Note: on this STM32 serie, there is no flag ADC group regular */
3669 /* end of unitary conversion. */
3670 /* Flag noted as "EOC" is corresponding to flag "EOS" */
3671 /* in other STM32 families). */
3672 return (READ_BIT(ADCxy_COMMON
->SR
, ADC_SR_EOC
) == (ADC_SR_EOC
));
3676 * @brief Get flag multimode ADC group regular end of sequence conversions of the ADC slave.
3677 * @rmtoll SR EOC LL_ADC_IsActiveFlag_SLV_EOS
3678 * @param ADCxy_COMMON ADC common instance
3679 * (can be set directly from CMSIS definition or by using helper macro @ref __LL_ADC_COMMON_INSTANCE() )
3680 * @retval State of bit (1 or 0).
3682 __STATIC_INLINE
uint32_t LL_ADC_IsActiveFlag_SLV_EOS(ADC_Common_TypeDef
*ADCxy_COMMON
)
3684 /* Note: on this STM32 serie, there is no flag ADC group regular */
3685 /* end of unitary conversion. */
3686 /* Flag noted as "EOC" is corresponding to flag "EOS" */
3687 /* in other STM32 families). */
3689 register uint32_t *preg
= __ADC_PTR_REG_OFFSET(ADCxy_COMMON
->SR
, 1U);
3691 return (READ_BIT(*preg
, LL_ADC_FLAG_EOS_SLV
) == (LL_ADC_FLAG_EOS_SLV
));
3696 * @brief Get flag multimode ADC group injected end of sequence conversions of the ADC master.
3697 * @rmtoll SR JEOC LL_ADC_IsActiveFlag_MST_JEOS
3698 * @param ADCxy_COMMON ADC common instance
3699 * (can be set directly from CMSIS definition or by using helper macro @ref __LL_ADC_COMMON_INSTANCE() )
3700 * @retval State of bit (1 or 0).
3702 __STATIC_INLINE
uint32_t LL_ADC_IsActiveFlag_MST_JEOS(ADC_Common_TypeDef
*ADCxy_COMMON
)
3704 /* Note: on this STM32 serie, there is no flag ADC group injected */
3705 /* end of unitary conversion. */
3706 /* Flag noted as "JEOC" is corresponding to flag "JEOS" */
3707 /* in other STM32 families). */
3708 return (READ_BIT(ADC1
->SR
, ADC_SR_JEOC
) == (ADC_SR_JEOC
));
3712 * @brief Get flag multimode ADC group injected end of sequence conversions of the ADC slave.
3713 * @rmtoll SR JEOC LL_ADC_IsActiveFlag_SLV_JEOS
3714 * @param ADCxy_COMMON ADC common instance
3715 * (can be set directly from CMSIS definition or by using helper macro @ref __LL_ADC_COMMON_INSTANCE() )
3716 * @retval State of bit (1 or 0).
3718 __STATIC_INLINE
uint32_t LL_ADC_IsActiveFlag_SLV_JEOS(ADC_Common_TypeDef
*ADCxy_COMMON
)
3720 /* Note: on this STM32 serie, there is no flag ADC group injected */
3721 /* end of unitary conversion. */
3722 /* Flag noted as "JEOC" is corresponding to flag "JEOS" */
3723 /* in other STM32 families). */
3725 register uint32_t *preg
= __ADC_PTR_REG_OFFSET(ADCxy_COMMON
->SR
, 1U);
3727 return (READ_BIT(*preg
, LL_ADC_FLAG_JEOS_SLV
) == (LL_ADC_FLAG_JEOS_SLV
));
3731 * @brief Get flag multimode ADC analog watchdog 1 of the ADC master.
3732 * @rmtoll SR AWD LL_ADC_IsActiveFlag_MST_AWD1
3733 * @param ADCxy_COMMON ADC common instance
3734 * (can be set directly from CMSIS definition or by using helper macro @ref __LL_ADC_COMMON_INSTANCE() )
3735 * @retval State of bit (1 or 0).
3737 __STATIC_INLINE
uint32_t LL_ADC_IsActiveFlag_MST_AWD1(ADC_Common_TypeDef
*ADCxy_COMMON
)
3739 return (READ_BIT(ADC1
->SR
, LL_ADC_FLAG_AWD1
) == (LL_ADC_FLAG_AWD1
));
3743 * @brief Get flag multimode analog watchdog 1 of the ADC slave.
3744 * @rmtoll SR AWD LL_ADC_IsActiveFlag_SLV_AWD1
3745 * @param ADCxy_COMMON ADC common instance
3746 * (can be set directly from CMSIS definition or by using helper macro @ref __LL_ADC_COMMON_INSTANCE() )
3747 * @retval State of bit (1 or 0).
3749 __STATIC_INLINE
uint32_t LL_ADC_IsActiveFlag_SLV_AWD1(ADC_Common_TypeDef
*ADCxy_COMMON
)
3751 register uint32_t *preg
= __ADC_PTR_REG_OFFSET(ADCxy_COMMON
->SR
, 1U);
3753 return (READ_BIT(*preg
, LL_ADC_FLAG_AWD1
) == (LL_ADC_FLAG_AWD1
));
3756 #endif /* ADC_MULTIMODE_SUPPORT */
3762 /** @defgroup ADC_LL_EF_IT_Management ADC IT management
3767 * @brief Enable interruption ADC group regular end of sequence conversions.
3768 * @rmtoll CR1 EOCIE LL_ADC_EnableIT_EOS
3769 * @param ADCx ADC instance
3772 __STATIC_INLINE
void LL_ADC_EnableIT_EOS(ADC_TypeDef
*ADCx
)
3774 /* Note: on this STM32 serie, there is no flag ADC group regular */
3775 /* end of unitary conversion. */
3776 /* Flag noted as "EOC" is corresponding to flag "EOS" */
3777 /* in other STM32 families). */
3778 SET_BIT(ADCx
->CR1
, ADC_CR1_EOCIE
);
3783 * @brief Enable interruption ADC group injected end of sequence conversions.
3784 * @rmtoll CR1 JEOCIE LL_ADC_EnableIT_JEOS
3785 * @param ADCx ADC instance
3788 __STATIC_INLINE
void LL_ADC_EnableIT_JEOS(ADC_TypeDef
*ADCx
)
3790 /* Note: on this STM32 serie, there is no flag ADC group injected */
3791 /* end of unitary conversion. */
3792 /* Flag noted as "JEOC" is corresponding to flag "JEOS" */
3793 /* in other STM32 families). */
3794 SET_BIT(ADCx
->CR1
, LL_ADC_IT_JEOS
);
3798 * @brief Enable interruption ADC analog watchdog 1.
3799 * @rmtoll CR1 AWDIE LL_ADC_EnableIT_AWD1
3800 * @param ADCx ADC instance
3803 __STATIC_INLINE
void LL_ADC_EnableIT_AWD1(ADC_TypeDef
*ADCx
)
3805 SET_BIT(ADCx
->CR1
, LL_ADC_IT_AWD1
);
3809 * @brief Disable interruption ADC group regular end of sequence conversions.
3810 * @rmtoll CR1 EOCIE LL_ADC_DisableIT_EOS
3811 * @param ADCx ADC instance
3814 __STATIC_INLINE
void LL_ADC_DisableIT_EOS(ADC_TypeDef
*ADCx
)
3816 /* Note: on this STM32 serie, there is no flag ADC group regular */
3817 /* end of unitary conversion. */
3818 /* Flag noted as "EOC" is corresponding to flag "EOS" */
3819 /* in other STM32 families). */
3820 CLEAR_BIT(ADCx
->CR1
, ADC_CR1_EOCIE
);
3825 * @brief Disable interruption ADC group injected end of sequence conversions.
3826 * @rmtoll CR1 JEOCIE LL_ADC_EnableIT_JEOS
3827 * @param ADCx ADC instance
3830 __STATIC_INLINE
void LL_ADC_DisableIT_JEOS(ADC_TypeDef
*ADCx
)
3832 /* Note: on this STM32 serie, there is no flag ADC group injected */
3833 /* end of unitary conversion. */
3834 /* Flag noted as "JEOC" is corresponding to flag "JEOS" */
3835 /* in other STM32 families). */
3836 CLEAR_BIT(ADCx
->CR1
, LL_ADC_IT_JEOS
);
3840 * @brief Disable interruption ADC analog watchdog 1.
3841 * @rmtoll CR1 AWDIE LL_ADC_EnableIT_AWD1
3842 * @param ADCx ADC instance
3845 __STATIC_INLINE
void LL_ADC_DisableIT_AWD1(ADC_TypeDef
*ADCx
)
3847 CLEAR_BIT(ADCx
->CR1
, LL_ADC_IT_AWD1
);
3851 * @brief Get state of interruption ADC group regular end of sequence conversions
3852 * (0: interrupt disabled, 1: interrupt enabled).
3853 * @rmtoll CR1 EOCIE LL_ADC_IsEnabledIT_EOS
3854 * @param ADCx ADC instance
3855 * @retval State of bit (1 or 0).
3857 __STATIC_INLINE
uint32_t LL_ADC_IsEnabledIT_EOS(ADC_TypeDef
*ADCx
)
3859 /* Note: on this STM32 serie, there is no flag ADC group regular */
3860 /* end of unitary conversion. */
3861 /* Flag noted as "EOC" is corresponding to flag "EOS" */
3862 /* in other STM32 families). */
3863 return (READ_BIT(ADCx
->CR1
, LL_ADC_IT_EOS
) == (LL_ADC_IT_EOS
));
3868 * @brief Get state of interruption ADC group injected end of sequence conversions
3869 * (0: interrupt disabled, 1: interrupt enabled).
3870 * @rmtoll CR1 JEOCIE LL_ADC_EnableIT_JEOS
3871 * @param ADCx ADC instance
3872 * @retval State of bit (1 or 0).
3874 __STATIC_INLINE
uint32_t LL_ADC_IsEnabledIT_JEOS(ADC_TypeDef
*ADCx
)
3876 /* Note: on this STM32 serie, there is no flag ADC group injected */
3877 /* end of unitary conversion. */
3878 /* Flag noted as "JEOC" is corresponding to flag "JEOS" */
3879 /* in other STM32 families). */
3880 return (READ_BIT(ADCx
->CR1
, LL_ADC_IT_JEOS
) == (LL_ADC_IT_JEOS
));
3884 * @brief Get state of interruption ADC analog watchdog 1
3885 * (0: interrupt disabled, 1: interrupt enabled).
3886 * @rmtoll CR1 AWDIE LL_ADC_EnableIT_AWD1
3887 * @param ADCx ADC instance
3888 * @retval State of bit (1 or 0).
3890 __STATIC_INLINE
uint32_t LL_ADC_IsEnabledIT_AWD1(ADC_TypeDef
*ADCx
)
3892 return (READ_BIT(ADCx
->CR1
, LL_ADC_IT_AWD1
) == (LL_ADC_IT_AWD1
));
3899 #if defined(USE_FULL_LL_DRIVER)
3900 /** @defgroup ADC_LL_EF_Init Initialization and de-initialization functions
3904 /* Initialization of some features of ADC common parameters and multimode */
3905 ErrorStatus
LL_ADC_CommonDeInit(ADC_Common_TypeDef
*ADCxy_COMMON
);
3906 ErrorStatus
LL_ADC_CommonInit(ADC_Common_TypeDef
*ADCxy_COMMON
, LL_ADC_CommonInitTypeDef
*ADC_CommonInitStruct
);
3907 void LL_ADC_CommonStructInit(LL_ADC_CommonInitTypeDef
*ADC_CommonInitStruct
);
3909 /* De-initialization of ADC instance, ADC group regular and ADC group injected */
3910 /* (availability of ADC group injected depends on STM32 families) */
3911 ErrorStatus
LL_ADC_DeInit(ADC_TypeDef
*ADCx
);
3913 /* Initialization of some features of ADC instance */
3914 ErrorStatus
LL_ADC_Init(ADC_TypeDef
*ADCx
, LL_ADC_InitTypeDef
*ADC_InitStruct
);
3915 void LL_ADC_StructInit(LL_ADC_InitTypeDef
*ADC_InitStruct
);
3917 /* Initialization of some features of ADC instance and ADC group regular */
3918 ErrorStatus
LL_ADC_REG_Init(ADC_TypeDef
*ADCx
, LL_ADC_REG_InitTypeDef
*ADC_REG_InitStruct
);
3919 void LL_ADC_REG_StructInit(LL_ADC_REG_InitTypeDef
*ADC_REG_InitStruct
);
3921 /* Initialization of some features of ADC instance and ADC group injected */
3922 ErrorStatus
LL_ADC_INJ_Init(ADC_TypeDef
*ADCx
, LL_ADC_INJ_InitTypeDef
*ADC_INJ_InitStruct
);
3923 void LL_ADC_INJ_StructInit(LL_ADC_INJ_InitTypeDef
*ADC_INJ_InitStruct
);
3928 #endif /* USE_FULL_LL_DRIVER */
3938 #endif /* ADC1 || ADC2 || ADC3 */
3948 #endif /* __STM32F1xx_LL_ADC_H */
3950 /************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/