Merge pull request #11189 from klutvott123/move-telemetry-displayport-init
[betaflight.git] / lib / main / STM32G4 / Drivers / STM32G4xx_HAL_Driver / Inc / stm32g4xx_hal_rcc.h
blob07b307e36c36bb093fafcaf3ece61ddfd9e1cde1
1 /**
2 ******************************************************************************
3 * @file stm32g4xx_hal_rcc.h
4 * @author MCD Application Team
5 * @brief Header file of RCC HAL module.
6 ******************************************************************************
7 * @attention
9 * <h2><center>&copy; Copyright (c) 2018 STMicroelectronics.
10 * All rights reserved.</center></h2>
12 * This software component is licensed by ST under BSD 3-Clause license,
13 * the "License"; You may not use this file except in compliance with the
14 * License. You may obtain a copy of the License at:
15 * opensource.org/licenses/BSD-3-Clause
17 ******************************************************************************
20 /* Define to prevent recursive inclusion -------------------------------------*/
21 #ifndef STM32G4xx_HAL_RCC_H
22 #define STM32G4xx_HAL_RCC_H
24 #ifdef __cplusplus
25 extern "C" {
26 #endif
28 /* Includes ------------------------------------------------------------------*/
29 #include "stm32g4xx_hal_def.h"
31 /** @addtogroup STM32G4xx_HAL_Driver
32 * @{
35 /** @addtogroup RCC
36 * @{
39 /* Exported types ------------------------------------------------------------*/
40 /** @defgroup RCC_Exported_Types RCC Exported Types
41 * @{
44 /**
45 * @brief RCC PLL configuration structure definition
47 typedef struct
49 uint32_t PLLState; /*!< The new state of the PLL.
50 This parameter can be a value of @ref RCC_PLL_Config */
52 uint32_t PLLSource; /*!< RCC_PLLSource: PLL entry clock source.
53 This parameter must be a value of @ref RCC_PLL_Clock_Source */
55 uint32_t PLLM; /*!< PLLM: Division factor for PLL VCO input clock.
56 This parameter must be a value of @ref RCC_PLLM_Clock_Divider */
58 uint32_t PLLN; /*!< PLLN: Multiplication factor for PLL VCO output clock.
59 This parameter must be a number between Min_Data = 8 and Max_Data = 127 */
61 uint32_t PLLP; /*!< PLLP: Division factor for ADC clock.
62 This parameter must be a value of @ref RCC_PLLP_Clock_Divider */
64 uint32_t PLLQ; /*!< PLLQ: Division factor for SAI, I2S, USB, FDCAN and QUADSPI clocks.
65 This parameter must be a value of @ref RCC_PLLQ_Clock_Divider */
67 uint32_t PLLR; /*!< PLLR: Division for the main system clock.
68 User have to set the PLLR parameter correctly to not exceed max frequency 170MHZ.
69 This parameter must be a value of @ref RCC_PLLR_Clock_Divider */
71 }RCC_PLLInitTypeDef;
73 /**
74 * @brief RCC Internal/External Oscillator (HSE, HSI, LSE and LSI) configuration structure definition
76 typedef struct
78 uint32_t OscillatorType; /*!< The oscillators to be configured.
79 This parameter can be a value of @ref RCC_Oscillator_Type */
81 uint32_t HSEState; /*!< The new state of the HSE.
82 This parameter can be a value of @ref RCC_HSE_Config */
84 uint32_t LSEState; /*!< The new state of the LSE.
85 This parameter can be a value of @ref RCC_LSE_Config */
87 uint32_t HSIState; /*!< The new state of the HSI.
88 This parameter can be a value of @ref RCC_HSI_Config */
90 uint32_t HSICalibrationValue; /*!< The calibration trimming value (default is RCC_HSICALIBRATION_DEFAULT).
91 This parameter must be a number between Min_Data = 0x00 and Max_Data = 0xFF */
93 uint32_t LSIState; /*!< The new state of the LSI.
94 This parameter can be a value of @ref RCC_LSI_Config */
96 uint32_t HSI48State; /*!< The new state of the HSI48.
97 This parameter can be a value of @ref RCC_HSI48_Config */
99 RCC_PLLInitTypeDef PLL; /*!< Main PLL structure parameters */
101 }RCC_OscInitTypeDef;
104 * @brief RCC System, AHB and APB busses clock configuration structure definition
106 typedef struct
108 uint32_t ClockType; /*!< The clock to be configured.
109 This parameter can be a value of @ref RCC_System_Clock_Type */
111 uint32_t SYSCLKSource; /*!< The clock source used as system clock (SYSCLK).
112 This parameter can be a value of @ref RCC_System_Clock_Source */
114 uint32_t AHBCLKDivider; /*!< The AHB clock (HCLK) divider. This clock is derived from the system clock (SYSCLK).
115 This parameter can be a value of @ref RCC_AHB_Clock_Source */
117 uint32_t APB1CLKDivider; /*!< The APB1 clock (PCLK1) divider. This clock is derived from the AHB clock (HCLK).
118 This parameter can be a value of @ref RCC_APB1_APB2_Clock_Source */
120 uint32_t APB2CLKDivider; /*!< The APB2 clock (PCLK2) divider. This clock is derived from the AHB clock (HCLK).
121 This parameter can be a value of @ref RCC_APB1_APB2_Clock_Source */
123 }RCC_ClkInitTypeDef;
126 * @}
129 /* Exported constants --------------------------------------------------------*/
130 /** @defgroup RCC_Exported_Constants RCC Exported Constants
131 * @{
134 /** @defgroup RCC_Timeout_Value Timeout Values
135 * @{
137 #define RCC_DBP_TIMEOUT_VALUE 2U /* 2 ms (minimum Tick + 1) */
138 #define RCC_LSE_TIMEOUT_VALUE LSE_STARTUP_TIMEOUT
140 * @}
143 /** @defgroup RCC_Oscillator_Type Oscillator Type
144 * @{
146 #define RCC_OSCILLATORTYPE_NONE 0x00000000U /*!< Oscillator configuration unchanged */
147 #define RCC_OSCILLATORTYPE_HSE 0x00000001U /*!< HSE to configure */
148 #define RCC_OSCILLATORTYPE_HSI 0x00000002U /*!< HSI to configure */
149 #define RCC_OSCILLATORTYPE_LSE 0x00000004U /*!< LSE to configure */
150 #define RCC_OSCILLATORTYPE_LSI 0x00000008U /*!< LSI to configure */
151 #define RCC_OSCILLATORTYPE_HSI48 0x00000020U /*!< HSI48 to configure */
153 * @}
156 /** @defgroup RCC_HSE_Config HSE Config
157 * @{
159 #define RCC_HSE_OFF 0x00000000U /*!< HSE clock deactivation */
160 #define RCC_HSE_ON RCC_CR_HSEON /*!< HSE clock activation */
161 #define RCC_HSE_BYPASS (RCC_CR_HSEBYP | RCC_CR_HSEON) /*!< External clock source for HSE clock */
163 * @}
166 /** @defgroup RCC_LSE_Config LSE Config
167 * @{
169 #define RCC_LSE_OFF 0x00000000U /*!< LSE clock deactivation */
170 #define RCC_LSE_ON RCC_BDCR_LSEON /*!< LSE clock activation */
171 #define RCC_LSE_BYPASS (RCC_BDCR_LSEBYP | RCC_BDCR_LSEON) /*!< External clock source for LSE clock */
173 * @}
176 /** @defgroup RCC_HSI_Config HSI Config
177 * @{
179 #define RCC_HSI_OFF 0x00000000U /*!< HSI clock deactivation */
180 #define RCC_HSI_ON RCC_CR_HSION /*!< HSI clock activation */
181 #define RCC_HSICALIBRATION_DEFAULT 0x40U /* Default HSI calibration trimming value */
183 * @}
186 /** @defgroup RCC_LSI_Config LSI Config
187 * @{
189 #define RCC_LSI_OFF 0x00000000U /*!< LSI clock deactivation */
190 #define RCC_LSI_ON RCC_CSR_LSION /*!< LSI clock activation */
192 * @}
195 /** @defgroup RCC_HSI48_Config HSI48 Config
196 * @{
198 #define RCC_HSI48_OFF 0x00000000U /*!< HSI48 clock deactivation */
199 #define RCC_HSI48_ON RCC_CRRCR_HSI48ON /*!< HSI48 clock activation */
201 * @}
204 /** @defgroup RCC_PLL_Config PLL Config
205 * @{
207 #define RCC_PLL_NONE 0x00000000U /*!< PLL configuration unchanged */
208 #define RCC_PLL_OFF 0x00000001U /*!< PLL deactivation */
209 #define RCC_PLL_ON 0x00000002U /*!< PLL activation */
211 * @}
214 /** @defgroup RCC_PLLM_Clock_Divider PLLM Clock Divider
215 * @{
217 #define RCC_PLLM_DIV1 0x00000001U /*!< PLLM division factor = 1 */
218 #define RCC_PLLM_DIV2 0x00000002U /*!< PLLM division factor = 2 */
219 #define RCC_PLLM_DIV3 0x00000003U /*!< PLLM division factor = 3 */
220 #define RCC_PLLM_DIV4 0x00000004U /*!< PLLM division factor = 4 */
221 #define RCC_PLLM_DIV5 0x00000005U /*!< PLLM division factor = 5 */
222 #define RCC_PLLM_DIV6 0x00000006U /*!< PLLM division factor = 6 */
223 #define RCC_PLLM_DIV7 0x00000007U /*!< PLLM division factor = 7 */
224 #define RCC_PLLM_DIV8 0x00000008U /*!< PLLM division factor = 8 */
225 #define RCC_PLLM_DIV9 0x00000009U /*!< PLLM division factor = 9 */
226 #define RCC_PLLM_DIV10 0x0000000AU /*!< PLLM division factor = 10 */
227 #define RCC_PLLM_DIV11 0x0000000BU /*!< PLLM division factor = 11 */
228 #define RCC_PLLM_DIV12 0x0000000CU /*!< PLLM division factor = 12 */
229 #define RCC_PLLM_DIV13 0x0000000DU /*!< PLLM division factor = 13 */
230 #define RCC_PLLM_DIV14 0x0000000EU /*!< PLLM division factor = 14 */
231 #define RCC_PLLM_DIV15 0x0000000FU /*!< PLLM division factor = 15 */
232 #define RCC_PLLM_DIV16 0x00000010U /*!< PLLM division factor = 16 */
234 * @}
237 /** @defgroup RCC_PLLP_Clock_Divider PLLP Clock Divider
238 * @{
240 #define RCC_PLLP_DIV2 0x00000002U /*!< PLLP division factor = 2 */
241 #define RCC_PLLP_DIV3 0x00000003U /*!< PLLP division factor = 3 */
242 #define RCC_PLLP_DIV4 0x00000004U /*!< PLLP division factor = 4 */
243 #define RCC_PLLP_DIV5 0x00000005U /*!< PLLP division factor = 5 */
244 #define RCC_PLLP_DIV6 0x00000006U /*!< PLLP division factor = 6 */
245 #define RCC_PLLP_DIV7 0x00000007U /*!< PLLP division factor = 7 */
246 #define RCC_PLLP_DIV8 0x00000008U /*!< PLLP division factor = 8 */
247 #define RCC_PLLP_DIV9 0x00000009U /*!< PLLP division factor = 9 */
248 #define RCC_PLLP_DIV10 0x0000000AU /*!< PLLP division factor = 10 */
249 #define RCC_PLLP_DIV11 0x0000000BU /*!< PLLP division factor = 11 */
250 #define RCC_PLLP_DIV12 0x0000000CU /*!< PLLP division factor = 12 */
251 #define RCC_PLLP_DIV13 0x0000000DU /*!< PLLP division factor = 13 */
252 #define RCC_PLLP_DIV14 0x0000000EU /*!< PLLP division factor = 14 */
253 #define RCC_PLLP_DIV15 0x0000000FU /*!< PLLP division factor = 15 */
254 #define RCC_PLLP_DIV16 0x00000010U /*!< PLLP division factor = 16 */
255 #define RCC_PLLP_DIV17 0x00000011U /*!< PLLP division factor = 17 */
256 #define RCC_PLLP_DIV18 0x00000012U /*!< PLLP division factor = 18 */
257 #define RCC_PLLP_DIV19 0x00000013U /*!< PLLP division factor = 19 */
258 #define RCC_PLLP_DIV20 0x00000014U /*!< PLLP division factor = 20 */
259 #define RCC_PLLP_DIV21 0x00000015U /*!< PLLP division factor = 21 */
260 #define RCC_PLLP_DIV22 0x00000016U /*!< PLLP division factor = 22 */
261 #define RCC_PLLP_DIV23 0x00000017U /*!< PLLP division factor = 23 */
262 #define RCC_PLLP_DIV24 0x00000018U /*!< PLLP division factor = 24 */
263 #define RCC_PLLP_DIV25 0x00000019U /*!< PLLP division factor = 25 */
264 #define RCC_PLLP_DIV26 0x0000001AU /*!< PLLP division factor = 26 */
265 #define RCC_PLLP_DIV27 0x0000001BU /*!< PLLP division factor = 27 */
266 #define RCC_PLLP_DIV28 0x0000001CU /*!< PLLP division factor = 28 */
267 #define RCC_PLLP_DIV29 0x0000001DU /*!< PLLP division factor = 29 */
268 #define RCC_PLLP_DIV30 0x0000001EU /*!< PLLP division factor = 30 */
269 #define RCC_PLLP_DIV31 0x0000001FU /*!< PLLP division factor = 31 */
271 * @}
274 /** @defgroup RCC_PLLQ_Clock_Divider PLLQ Clock Divider
275 * @{
277 #define RCC_PLLQ_DIV2 0x00000002U /*!< PLLQ division factor = 2 */
278 #define RCC_PLLQ_DIV4 0x00000004U /*!< PLLQ division factor = 4 */
279 #define RCC_PLLQ_DIV6 0x00000006U /*!< PLLQ division factor = 6 */
280 #define RCC_PLLQ_DIV8 0x00000008U /*!< PLLQ division factor = 8 */
282 * @}
285 /** @defgroup RCC_PLLR_Clock_Divider PLLR Clock Divider
286 * @{
288 #define RCC_PLLR_DIV2 0x00000002U /*!< PLLR division factor = 2 */
289 #define RCC_PLLR_DIV4 0x00000004U /*!< PLLR division factor = 4 */
290 #define RCC_PLLR_DIV6 0x00000006U /*!< PLLR division factor = 6 */
291 #define RCC_PLLR_DIV8 0x00000008U /*!< PLLR division factor = 8 */
293 * @}
296 /** @defgroup RCC_PLL_Clock_Source PLL Clock Source
297 * @{
299 #define RCC_PLLSOURCE_NONE 0x00000000U /*!< No clock selected as PLL entry clock source */
300 #define RCC_PLLSOURCE_HSI RCC_PLLCFGR_PLLSRC_HSI /*!< HSI clock selected as PLL entry clock source */
301 #define RCC_PLLSOURCE_HSE RCC_PLLCFGR_PLLSRC_HSE /*!< HSE clock selected as PLL entry clock source */
303 * @}
306 /** @defgroup RCC_PLL_Clock_Output PLL Clock Output
307 * @{
309 #define RCC_PLL_ADCCLK RCC_PLLCFGR_PLLPEN /*!< PLLADCCLK selection from main PLL */
310 #define RCC_PLL_48M1CLK RCC_PLLCFGR_PLLQEN /*!< PLL48M1CLK selection from main PLL */
311 #define RCC_PLL_SYSCLK RCC_PLLCFGR_PLLREN /*!< PLLCLK selection from main PLL */
313 * @}
316 /** @defgroup RCC_System_Clock_Type System Clock Type
317 * @{
319 #define RCC_CLOCKTYPE_SYSCLK 0x00000001U /*!< SYSCLK to configure */
320 #define RCC_CLOCKTYPE_HCLK 0x00000002U /*!< HCLK to configure */
321 #define RCC_CLOCKTYPE_PCLK1 0x00000004U /*!< PCLK1 to configure */
322 #define RCC_CLOCKTYPE_PCLK2 0x00000008U /*!< PCLK2 to configure */
324 * @}
327 /** @defgroup RCC_System_Clock_Source System Clock Source
328 * @{
330 #define RCC_SYSCLKSOURCE_HSI RCC_CFGR_SW_HSI /*!< HSI selection as system clock */
331 #define RCC_SYSCLKSOURCE_HSE RCC_CFGR_SW_HSE /*!< HSE selection as system clock */
332 #define RCC_SYSCLKSOURCE_PLLCLK RCC_CFGR_SW_PLL /*!< PLL selection as system clock */
334 * @}
337 /** @defgroup RCC_System_Clock_Source_Status System Clock Source Status
338 * @{
340 #define RCC_SYSCLKSOURCE_STATUS_HSI RCC_CFGR_SWS_HSI /*!< HSI used as system clock */
341 #define RCC_SYSCLKSOURCE_STATUS_HSE RCC_CFGR_SWS_HSE /*!< HSE used as system clock */
342 #define RCC_SYSCLKSOURCE_STATUS_PLLCLK RCC_CFGR_SWS_PLL /*!< PLL used as system clock */
344 * @}
347 /** @defgroup RCC_AHB_Clock_Source AHB Clock Source
348 * @{
350 #define RCC_SYSCLK_DIV1 RCC_CFGR_HPRE_DIV1 /*!< SYSCLK not divided */
351 #define RCC_SYSCLK_DIV2 RCC_CFGR_HPRE_DIV2 /*!< SYSCLK divided by 2 */
352 #define RCC_SYSCLK_DIV4 RCC_CFGR_HPRE_DIV4 /*!< SYSCLK divided by 4 */
353 #define RCC_SYSCLK_DIV8 RCC_CFGR_HPRE_DIV8 /*!< SYSCLK divided by 8 */
354 #define RCC_SYSCLK_DIV16 RCC_CFGR_HPRE_DIV16 /*!< SYSCLK divided by 16 */
355 #define RCC_SYSCLK_DIV64 RCC_CFGR_HPRE_DIV64 /*!< SYSCLK divided by 64 */
356 #define RCC_SYSCLK_DIV128 RCC_CFGR_HPRE_DIV128 /*!< SYSCLK divided by 128 */
357 #define RCC_SYSCLK_DIV256 RCC_CFGR_HPRE_DIV256 /*!< SYSCLK divided by 256 */
358 #define RCC_SYSCLK_DIV512 RCC_CFGR_HPRE_DIV512 /*!< SYSCLK divided by 512 */
360 * @}
363 /** @defgroup RCC_APB1_APB2_Clock_Source APB1 APB2 Clock Source
364 * @{
366 #define RCC_HCLK_DIV1 RCC_CFGR_PPRE1_DIV1 /*!< HCLK not divided */
367 #define RCC_HCLK_DIV2 RCC_CFGR_PPRE1_DIV2 /*!< HCLK divided by 2 */
368 #define RCC_HCLK_DIV4 RCC_CFGR_PPRE1_DIV4 /*!< HCLK divided by 4 */
369 #define RCC_HCLK_DIV8 RCC_CFGR_PPRE1_DIV8 /*!< HCLK divided by 8 */
370 #define RCC_HCLK_DIV16 RCC_CFGR_PPRE1_DIV16 /*!< HCLK divided by 16 */
372 * @}
375 /** @defgroup RCC_RTC_Clock_Source RTC Clock Source
376 * @{
378 #define RCC_RTCCLKSOURCE_NONE 0x00000000U /*!< No clock used as RTC clock */
379 #define RCC_RTCCLKSOURCE_LSE RCC_BDCR_RTCSEL_0 /*!< LSE oscillator clock used as RTC clock */
380 #define RCC_RTCCLKSOURCE_LSI RCC_BDCR_RTCSEL_1 /*!< LSI oscillator clock used as RTC clock */
381 #define RCC_RTCCLKSOURCE_HSE_DIV32 RCC_BDCR_RTCSEL /*!< HSE oscillator clock divided by 32 used as RTC clock */
383 * @}
386 /** @defgroup RCC_MCO_Index MCO Index
387 * @{
389 #define RCC_MCO1 0x00000000U
390 #define RCC_MCO RCC_MCO1 /*!< MCO1 to be compliant with other families with 2 MCOs*/
392 * @}
395 /** @defgroup RCC_MCO1_Clock_Source MCO1 Clock Source
396 * @{
398 #define RCC_MCO1SOURCE_NOCLOCK 0x00000000U /*!< MCO1 output disabled, no clock on MCO1 */
399 #define RCC_MCO1SOURCE_SYSCLK RCC_CFGR_MCOSEL_0 /*!< SYSCLK selection as MCO1 source */
400 #define RCC_MCO1SOURCE_HSI (RCC_CFGR_MCOSEL_0| RCC_CFGR_MCOSEL_1) /*!< HSI selection as MCO1 source */
401 #define RCC_MCO1SOURCE_HSE RCC_CFGR_MCOSEL_2 /*!< HSE selection as MCO1 source */
402 #define RCC_MCO1SOURCE_PLLCLK (RCC_CFGR_MCOSEL_0|RCC_CFGR_MCOSEL_2) /*!< PLLCLK selection as MCO1 source */
403 #define RCC_MCO1SOURCE_LSI (RCC_CFGR_MCOSEL_1|RCC_CFGR_MCOSEL_2) /*!< LSI selection as MCO1 source */
404 #define RCC_MCO1SOURCE_LSE (RCC_CFGR_MCOSEL_0|RCC_CFGR_MCOSEL_1|RCC_CFGR_MCOSEL_2) /*!< LSE selection as MCO1 source */
405 #define RCC_MCO1SOURCE_HSI48 RCC_CFGR_MCOSEL_3 /*!< HSI48 selection as MCO1 source */
407 * @}
410 /** @defgroup RCC_MCOx_Clock_Prescaler MCO1 Clock Prescaler
411 * @{
413 #define RCC_MCODIV_1 RCC_CFGR_MCOPRE_DIV1 /*!< MCO not divided */
414 #define RCC_MCODIV_2 RCC_CFGR_MCOPRE_DIV2 /*!< MCO divided by 2 */
415 #define RCC_MCODIV_4 RCC_CFGR_MCOPRE_DIV4 /*!< MCO divided by 4 */
416 #define RCC_MCODIV_8 RCC_CFGR_MCOPRE_DIV8 /*!< MCO divided by 8 */
417 #define RCC_MCODIV_16 RCC_CFGR_MCOPRE_DIV16 /*!< MCO divided by 16 */
419 * @}
422 /** @defgroup RCC_Interrupt Interrupts
423 * @{
425 #define RCC_IT_LSIRDY RCC_CIFR_LSIRDYF /*!< LSI Ready Interrupt flag */
426 #define RCC_IT_LSERDY RCC_CIFR_LSERDYF /*!< LSE Ready Interrupt flag */
427 #define RCC_IT_HSIRDY RCC_CIFR_HSIRDYF /*!< HSI16 Ready Interrupt flag */
428 #define RCC_IT_HSERDY RCC_CIFR_HSERDYF /*!< HSE Ready Interrupt flag */
429 #define RCC_IT_PLLRDY RCC_CIFR_PLLRDYF /*!< PLL Ready Interrupt flag */
430 #define RCC_IT_CSS RCC_CIFR_CSSF /*!< Clock Security System Interrupt flag */
431 #define RCC_IT_LSECSS RCC_CIFR_LSECSSF /*!< LSE Clock Security System Interrupt flag */
432 #define RCC_IT_HSI48RDY RCC_CIFR_HSI48RDYF /*!< HSI48 Ready Interrupt flag */
434 * @}
437 /** @defgroup RCC_Flag Flags
438 * Elements values convention: XXXYYYYYb
439 * - YYYYY : Flag position in the register
440 * - XXX : Register index
441 * - 001: CR register
442 * - 010: BDCR register
443 * - 011: CSR register
444 * - 100: CRRCR register
445 * @{
447 /* Flags in the CR register */
448 #define RCC_FLAG_HSIRDY ((CR_REG_INDEX << 5U) | RCC_CR_HSIRDY_Pos) /*!< HSI Ready flag */
449 #define RCC_FLAG_HSERDY ((CR_REG_INDEX << 5U) | RCC_CR_HSERDY_Pos) /*!< HSE Ready flag */
450 #define RCC_FLAG_PLLRDY ((CR_REG_INDEX << 5U) | RCC_CR_PLLRDY_Pos) /*!< PLL Ready flag */
452 /* Flags in the BDCR register */
453 #define RCC_FLAG_LSERDY ((BDCR_REG_INDEX << 5U) | RCC_BDCR_LSERDY_Pos) /*!< LSE Ready flag */
454 #define RCC_FLAG_LSECSSD ((BDCR_REG_INDEX << 5U) | RCC_BDCR_LSECSSD_Pos) /*!< LSE Clock Security System Interrupt flag */
456 /* Flags in the CSR register */
457 #define RCC_FLAG_LSIRDY ((CSR_REG_INDEX << 5U) | RCC_CSR_LSIRDY_Pos) /*!< LSI Ready flag */
458 #define RCC_FLAG_OBLRST ((CSR_REG_INDEX << 5U) | RCC_CSR_OBLRSTF_Pos) /*!< Option Byte Loader reset flag */
459 #define RCC_FLAG_PINRST ((CSR_REG_INDEX << 5U) | RCC_CSR_PINRSTF_Pos) /*!< PIN reset flag */
460 #define RCC_FLAG_BORRST ((CSR_REG_INDEX << 5U) | RCC_CSR_BORRSTF_Pos) /*!< BOR reset flag */
461 #define RCC_FLAG_SFTRST ((CSR_REG_INDEX << 5U) | RCC_CSR_SFTRSTF_Pos) /*!< Software Reset flag */
462 #define RCC_FLAG_IWDGRST ((CSR_REG_INDEX << 5U) | RCC_CSR_IWDGRSTF_Pos) /*!< Independent Watchdog reset flag */
463 #define RCC_FLAG_WWDGRST ((CSR_REG_INDEX << 5U) | RCC_CSR_WWDGRSTF_Pos) /*!< Window watchdog reset flag */
464 #define RCC_FLAG_LPWRRST ((CSR_REG_INDEX << 5U) | RCC_CSR_LPWRRSTF_Pos) /*!< Low-Power reset flag */
466 /* Flags in the CRRCR register */
467 #define RCC_FLAG_HSI48RDY ((CRRCR_REG_INDEX << 5U) | RCC_CRRCR_HSI48RDY_Pos) /*!< HSI48 Ready flag */
469 * @}
472 /** @defgroup RCC_LSEDrive_Config LSE Drive Config
473 * @{
475 #define RCC_LSEDRIVE_LOW 0x00000000U /*!< LSE low drive capability */
476 #define RCC_LSEDRIVE_MEDIUMLOW RCC_BDCR_LSEDRV_0 /*!< LSE medium low drive capability */
477 #define RCC_LSEDRIVE_MEDIUMHIGH RCC_BDCR_LSEDRV_1 /*!< LSE medium high drive capability */
478 #define RCC_LSEDRIVE_HIGH RCC_BDCR_LSEDRV /*!< LSE high drive capability */
480 * @}
484 * @}
487 /* Exported macros -----------------------------------------------------------*/
489 /** @defgroup RCC_Exported_Macros RCC Exported Macros
490 * @{
493 /** @defgroup RCC_AHB1_Peripheral_Clock_Enable_Disable AHB1 Peripheral Clock Enable Disable
494 * @brief Enable or disable the AHB1 peripheral clock.
495 * @note After reset, the peripheral clock (used for registers read/write access)
496 * is disabled and the application software has to enable this clock before
497 * using it.
498 * @{
501 #define __HAL_RCC_DMA1_CLK_ENABLE() do { \
502 __IO uint32_t tmpreg; \
503 SET_BIT(RCC->AHB1ENR, RCC_AHB1ENR_DMA1EN); \
504 /* Delay after an RCC peripheral clock enabling */ \
505 tmpreg = READ_BIT(RCC->AHB1ENR, RCC_AHB1ENR_DMA1EN); \
506 UNUSED(tmpreg); \
507 } while(0)
509 #define __HAL_RCC_DMA2_CLK_ENABLE() do { \
510 __IO uint32_t tmpreg; \
511 SET_BIT(RCC->AHB1ENR, RCC_AHB1ENR_DMA2EN); \
512 /* Delay after an RCC peripheral clock enabling */ \
513 tmpreg = READ_BIT(RCC->AHB1ENR, RCC_AHB1ENR_DMA2EN); \
514 UNUSED(tmpreg); \
515 } while(0)
517 #define __HAL_RCC_DMAMUX1_CLK_ENABLE() do { \
518 __IO uint32_t tmpreg; \
519 SET_BIT(RCC->AHB1ENR, RCC_AHB1ENR_DMAMUX1EN); \
520 /* Delay after an RCC peripheral clock enabling */ \
521 tmpreg = READ_BIT(RCC->AHB1ENR, RCC_AHB1ENR_DMAMUX1EN); \
522 UNUSED(tmpreg); \
523 } while(0)
525 #define __HAL_RCC_CORDIC_CLK_ENABLE() do { \
526 __IO uint32_t tmpreg; \
527 SET_BIT(RCC->AHB1ENR, RCC_AHB1ENR_CORDICEN); \
528 /* Delay after an RCC peripheral clock enabling */ \
529 tmpreg = READ_BIT(RCC->AHB1ENR, RCC_AHB1ENR_CORDICEN); \
530 UNUSED(tmpreg); \
531 } while(0)
533 #define __HAL_RCC_FMAC_CLK_ENABLE() do { \
534 __IO uint32_t tmpreg; \
535 SET_BIT(RCC->AHB1ENR, RCC_AHB1ENR_FMACEN); \
536 /* Delay after an RCC peripheral clock enabling */ \
537 tmpreg = READ_BIT(RCC->AHB1ENR, RCC_AHB1ENR_FMACEN); \
538 UNUSED(tmpreg); \
539 } while(0)
541 #define __HAL_RCC_FLASH_CLK_ENABLE() do { \
542 __IO uint32_t tmpreg; \
543 SET_BIT(RCC->AHB1ENR, RCC_AHB1ENR_FLASHEN); \
544 /* Delay after an RCC peripheral clock enabling */ \
545 tmpreg = READ_BIT(RCC->AHB1ENR, RCC_AHB1ENR_FLASHEN); \
546 UNUSED(tmpreg); \
547 } while(0)
549 #define __HAL_RCC_CRC_CLK_ENABLE() do { \
550 __IO uint32_t tmpreg; \
551 SET_BIT(RCC->AHB1ENR, RCC_AHB1ENR_CRCEN); \
552 /* Delay after an RCC peripheral clock enabling */ \
553 tmpreg = READ_BIT(RCC->AHB1ENR, RCC_AHB1ENR_CRCEN); \
554 UNUSED(tmpreg); \
555 } while(0)
557 #define __HAL_RCC_DMA1_CLK_DISABLE() CLEAR_BIT(RCC->AHB1ENR, RCC_AHB1ENR_DMA1EN)
559 #define __HAL_RCC_DMA2_CLK_DISABLE() CLEAR_BIT(RCC->AHB1ENR, RCC_AHB1ENR_DMA2EN)
561 #define __HAL_RCC_DMAMUX1_CLK_DISABLE() CLEAR_BIT(RCC->AHB1ENR, RCC_AHB1ENR_DMAMUX1EN)
563 #define __HAL_RCC_CORDIC_CLK_DISABLE() CLEAR_BIT(RCC->AHB1ENR, RCC_AHB1ENR_CORDICEN)
565 #define __HAL_RCC_FMAC_CLK_DISABLE() CLEAR_BIT(RCC->AHB1ENR, RCC_AHB1ENR_FMACEN)
567 #define __HAL_RCC_FLASH_CLK_DISABLE() CLEAR_BIT(RCC->AHB1ENR, RCC_AHB1ENR_FLASHEN)
569 #define __HAL_RCC_CRC_CLK_DISABLE() CLEAR_BIT(RCC->AHB1ENR, RCC_AHB1ENR_CRCEN)
572 * @}
575 /** @defgroup RCC_AHB2_Peripheral_Clock_Enable_Disable AHB2 Peripheral Clock Enable Disable
576 * @brief Enable or disable the AHB2 peripheral clock.
577 * @note After reset, the peripheral clock (used for registers read/write access)
578 * is disabled and the application software has to enable this clock before
579 * using it.
580 * @{
583 #define __HAL_RCC_GPIOA_CLK_ENABLE() do { \
584 __IO uint32_t tmpreg; \
585 SET_BIT(RCC->AHB2ENR, RCC_AHB2ENR_GPIOAEN); \
586 /* Delay after an RCC peripheral clock enabling */ \
587 tmpreg = READ_BIT(RCC->AHB2ENR, RCC_AHB2ENR_GPIOAEN); \
588 UNUSED(tmpreg); \
589 } while(0)
591 #define __HAL_RCC_GPIOB_CLK_ENABLE() do { \
592 __IO uint32_t tmpreg; \
593 SET_BIT(RCC->AHB2ENR, RCC_AHB2ENR_GPIOBEN); \
594 /* Delay after an RCC peripheral clock enabling */ \
595 tmpreg = READ_BIT(RCC->AHB2ENR, RCC_AHB2ENR_GPIOBEN); \
596 UNUSED(tmpreg); \
597 } while(0)
599 #define __HAL_RCC_GPIOC_CLK_ENABLE() do { \
600 __IO uint32_t tmpreg; \
601 SET_BIT(RCC->AHB2ENR, RCC_AHB2ENR_GPIOCEN); \
602 /* Delay after an RCC peripheral clock enabling */ \
603 tmpreg = READ_BIT(RCC->AHB2ENR, RCC_AHB2ENR_GPIOCEN); \
604 UNUSED(tmpreg); \
605 } while(0)
607 #define __HAL_RCC_GPIOD_CLK_ENABLE() do { \
608 __IO uint32_t tmpreg; \
609 SET_BIT(RCC->AHB2ENR, RCC_AHB2ENR_GPIODEN); \
610 /* Delay after an RCC peripheral clock enabling */ \
611 tmpreg = READ_BIT(RCC->AHB2ENR, RCC_AHB2ENR_GPIODEN); \
612 UNUSED(tmpreg); \
613 } while(0)
615 #define __HAL_RCC_GPIOE_CLK_ENABLE() do { \
616 __IO uint32_t tmpreg; \
617 SET_BIT(RCC->AHB2ENR, RCC_AHB2ENR_GPIOEEN); \
618 /* Delay after an RCC peripheral clock enabling */ \
619 tmpreg = READ_BIT(RCC->AHB2ENR, RCC_AHB2ENR_GPIOEEN); \
620 UNUSED(tmpreg); \
621 } while(0)
623 #define __HAL_RCC_GPIOF_CLK_ENABLE() do { \
624 __IO uint32_t tmpreg; \
625 SET_BIT(RCC->AHB2ENR, RCC_AHB2ENR_GPIOFEN); \
626 /* Delay after an RCC peripheral clock enabling */ \
627 tmpreg = READ_BIT(RCC->AHB2ENR, RCC_AHB2ENR_GPIOFEN); \
628 UNUSED(tmpreg); \
629 } while(0)
631 #define __HAL_RCC_GPIOG_CLK_ENABLE() do { \
632 __IO uint32_t tmpreg; \
633 SET_BIT(RCC->AHB2ENR, RCC_AHB2ENR_GPIOGEN); \
634 /* Delay after an RCC peripheral clock enabling */ \
635 tmpreg = READ_BIT(RCC->AHB2ENR, RCC_AHB2ENR_GPIOGEN); \
636 UNUSED(tmpreg); \
637 } while(0)
639 #define __HAL_RCC_ADC12_CLK_ENABLE() do { \
640 __IO uint32_t tmpreg; \
641 SET_BIT(RCC->AHB2ENR, RCC_AHB2ENR_ADC12EN); \
642 /* Delay after an RCC peripheral clock enabling */ \
643 tmpreg = READ_BIT(RCC->AHB2ENR, RCC_AHB2ENR_ADC12EN); \
644 UNUSED(tmpreg); \
645 } while(0)
647 #if defined(ADC345_COMMON)
648 #define __HAL_RCC_ADC345_CLK_ENABLE() do { \
649 __IO uint32_t tmpreg; \
650 SET_BIT(RCC->AHB2ENR, RCC_AHB2ENR_ADC345EN); \
651 /* Delay after an RCC peripheral clock enabling */ \
652 tmpreg = READ_BIT(RCC->AHB2ENR, RCC_AHB2ENR_ADC345EN); \
653 UNUSED(tmpreg); \
654 } while(0)
655 #endif /* ADC345_COMMON */
657 #define __HAL_RCC_DAC1_CLK_ENABLE() do { \
658 __IO uint32_t tmpreg; \
659 SET_BIT(RCC->AHB2ENR, RCC_AHB2ENR_DAC1EN); \
660 /* Delay after an RCC peripheral clock enabling */ \
661 tmpreg = READ_BIT(RCC->AHB2ENR, RCC_AHB2ENR_DAC1EN); \
662 UNUSED(tmpreg); \
663 } while(0)
665 #if defined(DAC2)
666 #define __HAL_RCC_DAC2_CLK_ENABLE() do { \
667 __IO uint32_t tmpreg; \
668 SET_BIT(RCC->AHB2ENR, RCC_AHB2ENR_DAC2EN); \
669 /* Delay after an RCC peripheral clock enabling */ \
670 tmpreg = READ_BIT(RCC->AHB2ENR, RCC_AHB2ENR_DAC2EN); \
671 UNUSED(tmpreg); \
672 } while(0)
673 #endif /* DAC2 */
675 #define __HAL_RCC_DAC3_CLK_ENABLE() do { \
676 __IO uint32_t tmpreg; \
677 SET_BIT(RCC->AHB2ENR, RCC_AHB2ENR_DAC3EN); \
678 /* Delay after an RCC peripheral clock enabling */ \
679 tmpreg = READ_BIT(RCC->AHB2ENR, RCC_AHB2ENR_DAC3EN); \
680 UNUSED(tmpreg); \
681 } while(0)
683 #if defined(DAC4)
684 #define __HAL_RCC_DAC4_CLK_ENABLE() do { \
685 __IO uint32_t tmpreg; \
686 SET_BIT(RCC->AHB2ENR, RCC_AHB2ENR_DAC4EN); \
687 /* Delay after an RCC peripheral clock enabling */ \
688 tmpreg = READ_BIT(RCC->AHB2ENR, RCC_AHB2ENR_DAC4EN); \
689 UNUSED(tmpreg); \
690 } while(0)
691 #endif /* DAC4 */
693 #if defined(AES)
694 #define __HAL_RCC_AES_CLK_ENABLE() do { \
695 __IO uint32_t tmpreg; \
696 SET_BIT(RCC->AHB2ENR, RCC_AHB2ENR_AESEN); \
697 /* Delay after an RCC peripheral clock enabling */ \
698 tmpreg = READ_BIT(RCC->AHB2ENR, RCC_AHB2ENR_AESEN); \
699 UNUSED(tmpreg); \
700 } while(0)
701 #endif /* AES */
703 #define __HAL_RCC_RNG_CLK_ENABLE() do { \
704 __IO uint32_t tmpreg; \
705 SET_BIT(RCC->AHB2ENR, RCC_AHB2ENR_RNGEN); \
706 /* Delay after an RCC peripheral clock enabling */ \
707 tmpreg = READ_BIT(RCC->AHB2ENR, RCC_AHB2ENR_RNGEN); \
708 UNUSED(tmpreg); \
709 } while(0)
712 #define __HAL_RCC_GPIOA_CLK_DISABLE() CLEAR_BIT(RCC->AHB2ENR, RCC_AHB2ENR_GPIOAEN)
714 #define __HAL_RCC_GPIOB_CLK_DISABLE() CLEAR_BIT(RCC->AHB2ENR, RCC_AHB2ENR_GPIOBEN)
716 #define __HAL_RCC_GPIOC_CLK_DISABLE() CLEAR_BIT(RCC->AHB2ENR, RCC_AHB2ENR_GPIOCEN)
718 #define __HAL_RCC_GPIOD_CLK_DISABLE() CLEAR_BIT(RCC->AHB2ENR, RCC_AHB2ENR_GPIODEN)
720 #define __HAL_RCC_GPIOE_CLK_DISABLE() CLEAR_BIT(RCC->AHB2ENR, RCC_AHB2ENR_GPIOEEN)
722 #define __HAL_RCC_GPIOF_CLK_DISABLE() CLEAR_BIT(RCC->AHB2ENR, RCC_AHB2ENR_GPIOFEN)
724 #define __HAL_RCC_GPIOG_CLK_DISABLE() CLEAR_BIT(RCC->AHB2ENR, RCC_AHB2ENR_GPIOGEN)
726 #define __HAL_RCC_ADC12_CLK_DISABLE() CLEAR_BIT(RCC->AHB2ENR, RCC_AHB2ENR_ADC12EN)
728 #if defined(ADC345_COMMON)
729 #define __HAL_RCC_ADC345_CLK_DISABLE() CLEAR_BIT(RCC->AHB2ENR, RCC_AHB2ENR_ADC345EN)
730 #endif /* ADC345_COMMON */
732 #define __HAL_RCC_DAC1_CLK_DISABLE() CLEAR_BIT(RCC->AHB2ENR, RCC_AHB2ENR_DAC1EN)
734 #if defined(DAC2)
735 #define __HAL_RCC_DAC2_CLK_DISABLE() CLEAR_BIT(RCC->AHB2ENR, RCC_AHB2ENR_DAC2EN)
736 #endif /* DAC2 */
738 #define __HAL_RCC_DAC3_CLK_DISABLE() CLEAR_BIT(RCC->AHB2ENR, RCC_AHB2ENR_DAC3EN)
740 #if defined(DAC4)
741 #define __HAL_RCC_DAC4_CLK_DISABLE() CLEAR_BIT(RCC->AHB2ENR, RCC_AHB2ENR_DAC4EN)
742 #endif /* DAC4 */
744 #if defined(AES)
745 #define __HAL_RCC_AES_CLK_DISABLE() CLEAR_BIT(RCC->AHB2ENR, RCC_AHB2ENR_AESEN);
746 #endif /* AES */
748 #define __HAL_RCC_RNG_CLK_DISABLE() CLEAR_BIT(RCC->AHB2ENR, RCC_AHB2ENR_RNGEN)
751 * @}
754 /** @defgroup RCC_AHB3_Clock_Enable_Disable AHB3 Peripheral Clock Enable Disable
755 * @brief Enable or disable the AHB3 peripheral clock.
756 * @note After reset, the peripheral clock (used for registers read/write access)
757 * is disabled and the application software has to enable this clock before
758 * using it.
759 * @{
762 #if defined(FMC_BANK1)
763 #define __HAL_RCC_FMC_CLK_ENABLE() do { \
764 __IO uint32_t tmpreg; \
765 SET_BIT(RCC->AHB3ENR, RCC_AHB3ENR_FMCEN); \
766 /* Delay after an RCC peripheral clock enabling */ \
767 tmpreg = READ_BIT(RCC->AHB3ENR, RCC_AHB3ENR_FMCEN); \
768 UNUSED(tmpreg); \
769 } while(0)
770 #endif /* FMC_BANK1 */
772 #if defined(QUADSPI)
773 #define __HAL_RCC_QSPI_CLK_ENABLE() do { \
774 __IO uint32_t tmpreg; \
775 SET_BIT(RCC->AHB3ENR, RCC_AHB3ENR_QSPIEN); \
776 /* Delay after an RCC peripheral clock enabling */ \
777 tmpreg = READ_BIT(RCC->AHB3ENR, RCC_AHB3ENR_QSPIEN); \
778 UNUSED(tmpreg); \
779 } while(0)
780 #endif /* QUADSPI */
782 #if defined(FMC_BANK1)
783 #define __HAL_RCC_FMC_CLK_DISABLE() CLEAR_BIT(RCC->AHB3ENR, RCC_AHB3ENR_FMCEN)
784 #endif /* FMC_BANK1 */
786 #if defined(QUADSPI)
787 #define __HAL_RCC_QSPI_CLK_DISABLE() CLEAR_BIT(RCC->AHB3ENR, RCC_AHB3ENR_QSPIEN)
788 #endif /* QUADSPI */
791 * @}
794 /** @defgroup RCC_APB1_Clock_Enable_Disable APB1 Peripheral Clock Enable Disable
795 * @brief Enable or disable the APB1 peripheral clock.
796 * @note After reset, the peripheral clock (used for registers read/write access)
797 * is disabled and the application software has to enable this clock before
798 * using it.
799 * @{
802 #define __HAL_RCC_TIM2_CLK_ENABLE() do { \
803 __IO uint32_t tmpreg; \
804 SET_BIT(RCC->APB1ENR1, RCC_APB1ENR1_TIM2EN); \
805 /* Delay after an RCC peripheral clock enabling */ \
806 tmpreg = READ_BIT(RCC->APB1ENR1, RCC_APB1ENR1_TIM2EN); \
807 UNUSED(tmpreg); \
808 } while(0)
810 #define __HAL_RCC_TIM3_CLK_ENABLE() do { \
811 __IO uint32_t tmpreg; \
812 SET_BIT(RCC->APB1ENR1, RCC_APB1ENR1_TIM3EN); \
813 /* Delay after an RCC peripheral clock enabling */ \
814 tmpreg = READ_BIT(RCC->APB1ENR1, RCC_APB1ENR1_TIM3EN); \
815 UNUSED(tmpreg); \
816 } while(0)
818 #define __HAL_RCC_TIM4_CLK_ENABLE() do { \
819 __IO uint32_t tmpreg; \
820 SET_BIT(RCC->APB1ENR1, RCC_APB1ENR1_TIM4EN); \
821 /* Delay after an RCC peripheral clock enabling */ \
822 tmpreg = READ_BIT(RCC->APB1ENR1, RCC_APB1ENR1_TIM4EN); \
823 UNUSED(tmpreg); \
824 } while(0)
826 #if defined(TIM5)
827 #define __HAL_RCC_TIM5_CLK_ENABLE() do { \
828 __IO uint32_t tmpreg; \
829 SET_BIT(RCC->APB1ENR1, RCC_APB1ENR1_TIM5EN); \
830 /* Delay after an RCC peripheral clock enabling */ \
831 tmpreg = READ_BIT(RCC->APB1ENR1, RCC_APB1ENR1_TIM5EN); \
832 UNUSED(tmpreg); \
833 } while(0)
834 #endif /* TIM5 */
836 #define __HAL_RCC_TIM6_CLK_ENABLE() do { \
837 __IO uint32_t tmpreg; \
838 SET_BIT(RCC->APB1ENR1, RCC_APB1ENR1_TIM6EN); \
839 /* Delay after an RCC peripheral clock enabling */ \
840 tmpreg = READ_BIT(RCC->APB1ENR1, RCC_APB1ENR1_TIM6EN); \
841 UNUSED(tmpreg); \
842 } while(0)
844 #define __HAL_RCC_TIM7_CLK_ENABLE() do { \
845 __IO uint32_t tmpreg; \
846 SET_BIT(RCC->APB1ENR1, RCC_APB1ENR1_TIM7EN); \
847 /* Delay after an RCC peripheral clock enabling */ \
848 tmpreg = READ_BIT(RCC->APB1ENR1, RCC_APB1ENR1_TIM7EN); \
849 UNUSED(tmpreg); \
850 } while(0)
852 #define __HAL_RCC_CRS_CLK_ENABLE() do { \
853 __IO uint32_t tmpreg; \
854 SET_BIT(RCC->APB1ENR1, RCC_APB1ENR1_CRSEN); \
855 /* Delay after an RCC peripheral clock enabling */ \
856 tmpreg = READ_BIT(RCC->APB1ENR1, RCC_APB1ENR1_CRSEN); \
857 UNUSED(tmpreg); \
858 } while(0)
860 #define __HAL_RCC_RTCAPB_CLK_ENABLE() do { \
861 __IO uint32_t tmpreg; \
862 SET_BIT(RCC->APB1ENR1, RCC_APB1ENR1_RTCAPBEN); \
863 /* Delay after an RCC peripheral clock enabling */ \
864 tmpreg = READ_BIT(RCC->APB1ENR1, RCC_APB1ENR1_RTCAPBEN); \
865 UNUSED(tmpreg); \
866 } while(0)
868 #define __HAL_RCC_WWDG_CLK_ENABLE() do { \
869 __IO uint32_t tmpreg; \
870 SET_BIT(RCC->APB1ENR1, RCC_APB1ENR1_WWDGEN); \
871 /* Delay after an RCC peripheral clock enabling */ \
872 tmpreg = READ_BIT(RCC->APB1ENR1, RCC_APB1ENR1_WWDGEN); \
873 UNUSED(tmpreg); \
874 } while(0)
876 #define __HAL_RCC_SPI2_CLK_ENABLE() do { \
877 __IO uint32_t tmpreg; \
878 SET_BIT(RCC->APB1ENR1, RCC_APB1ENR1_SPI2EN); \
879 /* Delay after an RCC peripheral clock enabling */ \
880 tmpreg = READ_BIT(RCC->APB1ENR1, RCC_APB1ENR1_SPI2EN); \
881 UNUSED(tmpreg); \
882 } while(0)
884 #define __HAL_RCC_SPI3_CLK_ENABLE() do { \
885 __IO uint32_t tmpreg; \
886 SET_BIT(RCC->APB1ENR1, RCC_APB1ENR1_SPI3EN); \
887 /* Delay after an RCC peripheral clock enabling */ \
888 tmpreg = READ_BIT(RCC->APB1ENR1, RCC_APB1ENR1_SPI3EN); \
889 UNUSED(tmpreg); \
890 } while(0)
892 #define __HAL_RCC_USART2_CLK_ENABLE() do { \
893 __IO uint32_t tmpreg; \
894 SET_BIT(RCC->APB1ENR1, RCC_APB1ENR1_USART2EN); \
895 /* Delay after an RCC peripheral clock enabling */ \
896 tmpreg = READ_BIT(RCC->APB1ENR1, RCC_APB1ENR1_USART2EN); \
897 UNUSED(tmpreg); \
898 } while(0)
900 #define __HAL_RCC_USART3_CLK_ENABLE() do { \
901 __IO uint32_t tmpreg; \
902 SET_BIT(RCC->APB1ENR1, RCC_APB1ENR1_USART3EN); \
903 /* Delay after an RCC peripheral clock enabling */ \
904 tmpreg = READ_BIT(RCC->APB1ENR1, RCC_APB1ENR1_USART3EN); \
905 UNUSED(tmpreg); \
906 } while(0)
908 #if defined(UART4)
909 #define __HAL_RCC_UART4_CLK_ENABLE() do { \
910 __IO uint32_t tmpreg; \
911 SET_BIT(RCC->APB1ENR1, RCC_APB1ENR1_UART4EN); \
912 /* Delay after an RCC peripheral clock enabling */ \
913 tmpreg = READ_BIT(RCC->APB1ENR1, RCC_APB1ENR1_UART4EN); \
914 UNUSED(tmpreg); \
915 } while(0)
916 #endif /* UART4 */
918 #if defined(UART5)
919 #define __HAL_RCC_UART5_CLK_ENABLE() do { \
920 __IO uint32_t tmpreg; \
921 SET_BIT(RCC->APB1ENR1, RCC_APB1ENR1_UART5EN); \
922 /* Delay after an RCC peripheral clock enabling */ \
923 tmpreg = READ_BIT(RCC->APB1ENR1, RCC_APB1ENR1_UART5EN); \
924 UNUSED(tmpreg); \
925 } while(0)
926 #endif /* UART5 */
928 #define __HAL_RCC_I2C1_CLK_ENABLE() do { \
929 __IO uint32_t tmpreg; \
930 SET_BIT(RCC->APB1ENR1, RCC_APB1ENR1_I2C1EN); \
931 /* Delay after an RCC peripheral clock enabling */ \
932 tmpreg = READ_BIT(RCC->APB1ENR1, RCC_APB1ENR1_I2C1EN); \
933 UNUSED(tmpreg); \
934 } while(0)
936 #define __HAL_RCC_I2C2_CLK_ENABLE() do { \
937 __IO uint32_t tmpreg; \
938 SET_BIT(RCC->APB1ENR1, RCC_APB1ENR1_I2C2EN); \
939 /* Delay after an RCC peripheral clock enabling */ \
940 tmpreg = READ_BIT(RCC->APB1ENR1, RCC_APB1ENR1_I2C2EN); \
941 UNUSED(tmpreg); \
942 } while(0)
944 #define __HAL_RCC_USB_CLK_ENABLE() do { \
945 __IO uint32_t tmpreg; \
946 SET_BIT(RCC->APB1ENR1, RCC_APB1ENR1_USBEN); \
947 /* Delay after an RCC peripheral clock enabling */ \
948 tmpreg = READ_BIT(RCC->APB1ENR1, RCC_APB1ENR1_USBEN); \
949 UNUSED(tmpreg); \
950 } while(0)
952 #if defined(FDCAN1)
953 #define __HAL_RCC_FDCAN_CLK_ENABLE() do { \
954 __IO uint32_t tmpreg; \
955 SET_BIT(RCC->APB1ENR1, RCC_APB1ENR1_FDCANEN); \
956 /* Delay after an RCC peripheral clock enabling */ \
957 tmpreg = READ_BIT(RCC->APB1ENR1, RCC_APB1ENR1_FDCANEN); \
958 UNUSED(tmpreg); \
959 } while(0)
960 #endif /* FDCAN1 */
962 #define __HAL_RCC_PWR_CLK_ENABLE() do { \
963 __IO uint32_t tmpreg; \
964 SET_BIT(RCC->APB1ENR1, RCC_APB1ENR1_PWREN); \
965 /* Delay after an RCC peripheral clock enabling */ \
966 tmpreg = READ_BIT(RCC->APB1ENR1, RCC_APB1ENR1_PWREN); \
967 UNUSED(tmpreg); \
968 } while(0)
970 #define __HAL_RCC_I2C3_CLK_ENABLE() do { \
971 __IO uint32_t tmpreg; \
972 SET_BIT(RCC->APB1ENR1, RCC_APB1ENR1_I2C3EN); \
973 /* Delay after an RCC peripheral clock enabling */ \
974 tmpreg = READ_BIT(RCC->APB1ENR1, RCC_APB1ENR1_I2C3EN); \
975 UNUSED(tmpreg); \
976 } while(0)
978 #define __HAL_RCC_LPTIM1_CLK_ENABLE() do { \
979 __IO uint32_t tmpreg; \
980 SET_BIT(RCC->APB1ENR1, RCC_APB1ENR1_LPTIM1EN); \
981 /* Delay after an RCC peripheral clock enabling */ \
982 tmpreg = READ_BIT(RCC->APB1ENR1, RCC_APB1ENR1_LPTIM1EN); \
983 UNUSED(tmpreg); \
984 } while(0)
986 #define __HAL_RCC_LPUART1_CLK_ENABLE() do { \
987 __IO uint32_t tmpreg; \
988 SET_BIT(RCC->APB1ENR2, RCC_APB1ENR2_LPUART1EN); \
989 /* Delay after an RCC peripheral clock enabling */ \
990 tmpreg = READ_BIT(RCC->APB1ENR2, RCC_APB1ENR2_LPUART1EN); \
991 UNUSED(tmpreg); \
992 } while(0)
994 #if defined(I2C4)
995 #define __HAL_RCC_I2C4_CLK_ENABLE() do { \
996 __IO uint32_t tmpreg; \
997 SET_BIT(RCC->APB1ENR2, RCC_APB1ENR2_I2C4EN); \
998 /* Delay after an RCC peripheral clock enabling */ \
999 tmpreg = READ_BIT(RCC->APB1ENR2, RCC_APB1ENR2_I2C4EN); \
1000 UNUSED(tmpreg); \
1001 } while(0)
1002 #endif /* I2C4 */
1004 #define __HAL_RCC_UCPD1_CLK_ENABLE() do { \
1005 __IO uint32_t tmpreg; \
1006 SET_BIT(RCC->APB1ENR2, RCC_APB1ENR2_UCPD1EN); \
1007 /* Delay after an RCC peripheral clock enabling */ \
1008 tmpreg = READ_BIT(RCC->APB1ENR2, RCC_APB1ENR2_UCPD1EN); \
1009 UNUSED(tmpreg); \
1010 } while(0)
1012 #define __HAL_RCC_TIM2_CLK_DISABLE() CLEAR_BIT(RCC->APB1ENR1, RCC_APB1ENR1_TIM2EN)
1014 #define __HAL_RCC_TIM3_CLK_DISABLE() CLEAR_BIT(RCC->APB1ENR1, RCC_APB1ENR1_TIM3EN)
1016 #define __HAL_RCC_TIM4_CLK_DISABLE() CLEAR_BIT(RCC->APB1ENR1, RCC_APB1ENR1_TIM4EN)
1018 #if defined(TIM5)
1019 #define __HAL_RCC_TIM5_CLK_DISABLE() CLEAR_BIT(RCC->APB1ENR1, RCC_APB1ENR1_TIM5EN)
1020 #endif /* TIM5 */
1022 #define __HAL_RCC_TIM6_CLK_DISABLE() CLEAR_BIT(RCC->APB1ENR1, RCC_APB1ENR1_TIM6EN)
1024 #define __HAL_RCC_TIM7_CLK_DISABLE() CLEAR_BIT(RCC->APB1ENR1, RCC_APB1ENR1_TIM7EN)
1026 #define __HAL_RCC_CRS_CLK_DISABLE() CLEAR_BIT(RCC->APB1ENR1, RCC_APB1ENR1_CRSEN);
1028 #define __HAL_RCC_RTCAPB_CLK_DISABLE() CLEAR_BIT(RCC->APB1ENR1, RCC_APB1ENR1_RTCAPBEN);
1030 #define __HAL_RCC_WWDG_CLK_DISABLE() CLEAR_BIT(RCC->APB1ENR1, RCC_APB1ENR1_WWDG2EN)
1032 #define __HAL_RCC_SPI2_CLK_DISABLE() CLEAR_BIT(RCC->APB1ENR1, RCC_APB1ENR1_SPI2EN)
1034 #define __HAL_RCC_SPI3_CLK_DISABLE() CLEAR_BIT(RCC->APB1ENR1, RCC_APB1ENR1_SPI3EN)
1036 #define __HAL_RCC_USART2_CLK_DISABLE() CLEAR_BIT(RCC->APB1ENR1, RCC_APB1ENR1_USART2EN)
1038 #define __HAL_RCC_USART3_CLK_DISABLE() CLEAR_BIT(RCC->APB1ENR1, RCC_APB1ENR1_USART3EN)
1040 #if defined(UART4)
1041 #define __HAL_RCC_UART4_CLK_DISABLE() CLEAR_BIT(RCC->APB1ENR1, RCC_APB1ENR1_UART4EN)
1042 #endif /* UART4 */
1044 #if defined(UART5)
1045 #define __HAL_RCC_UART5_CLK_DISABLE() CLEAR_BIT(RCC->APB1ENR1, RCC_APB1ENR1_UART5EN)
1046 #endif /* UART5 */
1048 #define __HAL_RCC_I2C1_CLK_DISABLE() CLEAR_BIT(RCC->APB1ENR1, RCC_APB1ENR1_I2C1EN)
1050 #define __HAL_RCC_I2C2_CLK_DISABLE() CLEAR_BIT(RCC->APB1ENR1, RCC_APB1ENR1_I2C2EN)
1052 #define __HAL_RCC_USB_CLK_DISABLE() CLEAR_BIT(RCC->APB1ENR1, RCC_APB1ENR1_USBEN)
1054 #if defined(FDCAN1)
1055 #define __HAL_RCC_FDCAN_CLK_DISABLE() CLEAR_BIT(RCC->APB1ENR1, RCC_APB1ENR1_FDCANEN)
1056 #endif /* FDCAN1 */
1058 #define __HAL_RCC_PWR_CLK_DISABLE() CLEAR_BIT(RCC->APB1ENR1, RCC_APB1ENR1_PWREN)
1060 #define __HAL_RCC_I2C3_CLK_DISABLE() CLEAR_BIT(RCC->APB1ENR1, RCC_APB1ENR1_I2C3EN)
1062 #define __HAL_RCC_LPTIM1_CLK_DISABLE() CLEAR_BIT(RCC->APB1ENR1, RCC_APB1ENR1_LPTIM1EN)
1064 #define __HAL_RCC_LPUART1_CLK_DISABLE() CLEAR_BIT(RCC->APB1ENR2, RCC_APB1ENR2_LPUART1EN)
1066 #if defined(I2C4)
1067 #define __HAL_RCC_I2C4_CLK_DISABLE() CLEAR_BIT(RCC->APB1ENR2, RCC_APB1ENR2_I2C4EN)
1068 #endif /* I2C4 */
1070 #define __HAL_RCC_UCPD1_CLK_DISABLE() CLEAR_BIT(RCC->APB1ENR2, RCC_APB1ENR2_UCPD1EN)
1073 * @}
1076 /** @defgroup RCC_APB2_Clock_Enable_Disable APB2 Peripheral Clock Enable Disable
1077 * @brief Enable or disable the APB2 peripheral clock.
1078 * @note After reset, the peripheral clock (used for registers read/write access)
1079 * is disabled and the application software has to enable this clock before
1080 * using it.
1081 * @{
1084 #define __HAL_RCC_SYSCFG_CLK_ENABLE() do { \
1085 __IO uint32_t tmpreg; \
1086 SET_BIT(RCC->APB2ENR, RCC_APB2ENR_SYSCFGEN); \
1087 /* Delay after an RCC peripheral clock enabling */ \
1088 tmpreg = READ_BIT(RCC->APB2ENR, RCC_APB2ENR_SYSCFGEN); \
1089 UNUSED(tmpreg); \
1090 } while(0)
1092 #define __HAL_RCC_TIM1_CLK_ENABLE() do { \
1093 __IO uint32_t tmpreg; \
1094 SET_BIT(RCC->APB2ENR, RCC_APB2ENR_TIM1EN); \
1095 /* Delay after an RCC peripheral clock enabling */ \
1096 tmpreg = READ_BIT(RCC->APB2ENR, RCC_APB2ENR_TIM1EN); \
1097 UNUSED(tmpreg); \
1098 } while(0)
1100 #define __HAL_RCC_SPI1_CLK_ENABLE() do { \
1101 __IO uint32_t tmpreg; \
1102 SET_BIT(RCC->APB2ENR, RCC_APB2ENR_SPI1EN); \
1103 /* Delay after an RCC peripheral clock enabling */ \
1104 tmpreg = READ_BIT(RCC->APB2ENR, RCC_APB2ENR_SPI1EN); \
1105 UNUSED(tmpreg); \
1106 } while(0)
1108 #define __HAL_RCC_TIM8_CLK_ENABLE() do { \
1109 __IO uint32_t tmpreg; \
1110 SET_BIT(RCC->APB2ENR, RCC_APB2ENR_TIM8EN); \
1111 /* Delay after an RCC peripheral clock enabling */ \
1112 tmpreg = READ_BIT(RCC->APB2ENR, RCC_APB2ENR_TIM8EN); \
1113 UNUSED(tmpreg); \
1114 } while(0)
1116 #define __HAL_RCC_USART1_CLK_ENABLE() do { \
1117 __IO uint32_t tmpreg; \
1118 SET_BIT(RCC->APB2ENR, RCC_APB2ENR_USART1EN); \
1119 /* Delay after an RCC peripheral clock enabling */ \
1120 tmpreg = READ_BIT(RCC->APB2ENR, RCC_APB2ENR_USART1EN); \
1121 UNUSED(tmpreg); \
1122 } while(0)
1124 #if defined(SPI4)
1125 #define __HAL_RCC_SPI4_CLK_ENABLE() do { \
1126 __IO uint32_t tmpreg; \
1127 SET_BIT(RCC->APB2ENR, RCC_APB2ENR_SPI4EN); \
1128 /* Delay after an RCC peripheral clock enabling */ \
1129 tmpreg = READ_BIT(RCC->APB2ENR, RCC_APB2ENR_SPI4EN); \
1130 UNUSED(tmpreg); \
1131 } while(0)
1132 #endif /* SPI4 */
1134 #define __HAL_RCC_TIM15_CLK_ENABLE() do { \
1135 __IO uint32_t tmpreg; \
1136 SET_BIT(RCC->APB2ENR, RCC_APB2ENR_TIM15EN); \
1137 /* Delay after an RCC peripheral clock enabling */ \
1138 tmpreg = READ_BIT(RCC->APB2ENR, RCC_APB2ENR_TIM15EN); \
1139 UNUSED(tmpreg); \
1140 } while(0)
1142 #define __HAL_RCC_TIM16_CLK_ENABLE() do { \
1143 __IO uint32_t tmpreg; \
1144 SET_BIT(RCC->APB2ENR, RCC_APB2ENR_TIM16EN); \
1145 /* Delay after an RCC peripheral clock enabling */ \
1146 tmpreg = READ_BIT(RCC->APB2ENR, RCC_APB2ENR_TIM16EN); \
1147 UNUSED(tmpreg); \
1148 } while(0)
1150 #define __HAL_RCC_TIM17_CLK_ENABLE() do { \
1151 __IO uint32_t tmpreg; \
1152 SET_BIT(RCC->APB2ENR, RCC_APB2ENR_TIM17EN); \
1153 /* Delay after an RCC peripheral clock enabling */ \
1154 tmpreg = READ_BIT(RCC->APB2ENR, RCC_APB2ENR_TIM17EN); \
1155 UNUSED(tmpreg); \
1156 } while(0)
1158 #if defined(TIM20)
1159 #define __HAL_RCC_TIM20_CLK_ENABLE() do { \
1160 __IO uint32_t tmpreg; \
1161 SET_BIT(RCC->APB2ENR, RCC_APB2ENR_TIM20EN); \
1162 /* Delay after an RCC peripheral clock enabling */ \
1163 tmpreg = READ_BIT(RCC->APB2ENR, RCC_APB2ENR_TIM20EN); \
1164 UNUSED(tmpreg); \
1165 } while(0)
1166 #endif /* TIM20 */
1168 #define __HAL_RCC_SAI1_CLK_ENABLE() do { \
1169 __IO uint32_t tmpreg; \
1170 SET_BIT(RCC->APB2ENR, RCC_APB2ENR_SAI1EN); \
1171 /* Delay after an RCC peripheral clock enabling */ \
1172 tmpreg = READ_BIT(RCC->APB2ENR, RCC_APB2ENR_SAI1EN); \
1173 UNUSED(tmpreg); \
1174 } while(0)
1176 #if defined(HRTIM1)
1177 #define __HAL_RCC_HRTIM1_CLK_ENABLE() do { \
1178 __IO uint32_t tmpreg; \
1179 SET_BIT(RCC->APB2ENR, RCC_APB2ENR_HRTIM1EN); \
1180 /* Delay after an RCC peripheral clock enabling */ \
1181 tmpreg = READ_BIT(RCC->APB2ENR, RCC_APB2ENR_HRTIM1EN); \
1182 UNUSED(tmpreg); \
1183 } while(0)
1184 #endif /* HRTIM1 */
1186 #define __HAL_RCC_SYSCFG_CLK_DISABLE() CLEAR_BIT(RCC->APB2ENR, RCC_APB2ENR_SYSCFGEN)
1188 #define __HAL_RCC_TIM1_CLK_DISABLE() CLEAR_BIT(RCC->APB2ENR, RCC_APB2ENR_TIM1EN)
1190 #define __HAL_RCC_SPI1_CLK_DISABLE() CLEAR_BIT(RCC->APB2ENR, RCC_APB2ENR_SPI1EN)
1192 #define __HAL_RCC_TIM8_CLK_DISABLE() CLEAR_BIT(RCC->APB2ENR, RCC_APB2ENR_TIM8EN)
1194 #define __HAL_RCC_USART1_CLK_DISABLE() CLEAR_BIT(RCC->APB2ENR, RCC_APB2ENR_USART1EN)
1196 #if defined(SPI4)
1197 #define __HAL_RCC_SPI4_CLK_DISABLE() CLEAR_BIT(RCC->APB2ENR, RCC_APB2ENR_SPI4EN)
1198 #endif /* SPI4 */
1200 #define __HAL_RCC_TIM15_CLK_DISABLE() CLEAR_BIT(RCC->APB2ENR, RCC_APB2ENR_TIM15EN)
1202 #define __HAL_RCC_TIM16_CLK_DISABLE() CLEAR_BIT(RCC->APB2ENR, RCC_APB2ENR_TIM16EN)
1204 #define __HAL_RCC_TIM17_CLK_DISABLE() CLEAR_BIT(RCC->APB2ENR, RCC_APB2ENR_TIM17EN)
1206 #if defined(TIM20)
1207 #define __HAL_RCC_TIM20_CLK_DISABLE() CLEAR_BIT(RCC->APB2ENR, RCC_APB2ENR_TIM20EN)
1208 #endif /* TIM20 */
1210 #define __HAL_RCC_SAI1_CLK_DISABLE() CLEAR_BIT(RCC->APB2ENR, RCC_APB2ENR_SAI1EN)
1212 #if defined(HRTIM1)
1213 #define __HAL_RCC_HRTIM1_CLK_DISABLE() CLEAR_BIT(RCC->APB2ENR, RCC_APB2ENR_HRTIM1EN)
1214 #endif /* HRTIM1 */
1217 * @}
1220 /** @defgroup RCC_AHB1_Peripheral_Clock_Enable_Disable_Status AHB1 Peripheral Clock Enabled or Disabled Status
1221 * @brief Check whether the AHB1 peripheral clock is enabled or not.
1222 * @note After reset, the peripheral clock (used for registers read/write access)
1223 * is disabled and the application software has to enable this clock before
1224 * using it.
1225 * @{
1228 #define __HAL_RCC_DMA1_IS_CLK_ENABLED() (READ_BIT(RCC->AHB1ENR, RCC_AHB1ENR_DMA1EN) != 0U)
1230 #define __HAL_RCC_DMA2_IS_CLK_ENABLED() (READ_BIT(RCC->AHB1ENR, RCC_AHB1ENR_DMA2EN) != 0U)
1232 #define __HAL_RCC_DMAMUX1_IS_CLK_ENABLED() (READ_BIT(RCC->AHB1ENR, RCC_AHB1ENR_DMAMUX1EN) != 0U)
1234 #define __HAL_RCC_CORDIC_IS_CLK_ENABLED() (READ_BIT(RCC->AHB1ENR, RCC_AHB1ENR_CORDICEN) != 0U)
1236 #define __HAL_RCC_FMAC_IS_CLK_ENABLED() (READ_BIT(RCC->AHB1ENR, RCC_AHB1ENR_FMACEN) != 0U)
1238 #define __HAL_RCC_FLASH_IS_CLK_ENABLED() (READ_BIT(RCC->AHB1ENR, RCC_AHB1ENR_FLASHEN) != 0U)
1240 #define __HAL_RCC_CRC_IS_CLK_ENABLED() (READ_BIT(RCC->AHB1ENR, RCC_AHB1ENR_CRCEN) != 0U)
1242 #define __HAL_RCC_DMA1_IS_CLK_DISABLED() (READ_BIT(RCC->AHB1ENR, RCC_AHB1ENR_DMA1EN) == 0U)
1244 #define __HAL_RCC_DMA2_IS_CLK_DISABLED() (READ_BIT(RCC->AHB1ENR, RCC_AHB1ENR_DMA2EN) == 0U)
1246 #define __HAL_RCC_DMAMUX1_IS_CLK_DISABLED() (READ_BIT(RCC->AHB1ENR, RCC_AHB1ENR_DMAMUX1EN) == 0U)
1248 #define __HAL_RCC_CORDIC_IS_CLK_DISABLED() (READ_BIT(RCC->AHB1ENR, RCC_AHB1ENR_CORDICEN) == 0U)
1250 #define __HAL_RCC_FMAC_IS_CLK_DISABLED() (READ_BIT(RCC->AHB1ENR, RCC_AHB1ENR_FMACEN) == 0U)
1252 #define __HAL_RCC_FLASH_IS_CLK_DISABLED() (READ_BIT(RCC->AHB1ENR, RCC_AHB1ENR_FLASHEN) == 0U)
1254 #define __HAL_RCC_CRC_IS_CLK_DISABLED() (READ_BIT(RCC->AHB1ENR, RCC_AHB1ENR_CRCEN) == 0U)
1257 * @}
1260 /** @defgroup RCC_AHB2_Clock_Enable_Disable_Status AHB2 Peripheral Clock Enabled or Disabled Status
1261 * @brief Check whether the AHB2 peripheral clock is enabled or not.
1262 * @note After reset, the peripheral clock (used for registers read/write access)
1263 * is disabled and the application software has to enable this clock before
1264 * using it.
1265 * @{
1268 #define __HAL_RCC_GPIOA_IS_CLK_ENABLED() (READ_BIT(RCC->AHB2ENR, RCC_AHB2ENR_GPIOAEN) != 0U)
1270 #define __HAL_RCC_GPIOB_IS_CLK_ENABLED() (READ_BIT(RCC->AHB2ENR, RCC_AHB2ENR_GPIOBEN) != 0U)
1272 #define __HAL_RCC_GPIOC_IS_CLK_ENABLED() (READ_BIT(RCC->AHB2ENR, RCC_AHB2ENR_GPIOCEN) != 0U)
1274 #define __HAL_RCC_GPIOD_IS_CLK_ENABLED() (READ_BIT(RCC->AHB2ENR, RCC_AHB2ENR_GPIODEN) != 0U)
1276 #define __HAL_RCC_GPIOE_IS_CLK_ENABLED() (READ_BIT(RCC->AHB2ENR, RCC_AHB2ENR_GPIOEEN) != 0U)
1278 #define __HAL_RCC_GPIOF_IS_CLK_ENABLED() (READ_BIT(RCC->AHB2ENR, RCC_AHB2ENR_GPIOFEN) != 0U)
1280 #define __HAL_RCC_GPIOG_IS_CLK_ENABLED() (READ_BIT(RCC->AHB2ENR, RCC_AHB2ENR_GPIOGEN) != 0U)
1282 #define __HAL_RCC_ADC12_IS_CLK_ENABLED() (READ_BIT(RCC->AHB2ENR, RCC_AHB2ENR_ADC12EN) != 0U)
1284 #if defined(ADC345_COMMON)
1285 #define __HAL_RCC_ADC345_IS_CLK_ENABLED() (READ_BIT(RCC->AHB2ENR, RCC_AHB2ENR_ADC345EN) != 0U)
1286 #endif /* ADC345_COMMON */
1288 #define __HAL_RCC_DAC1_IS_CLK_ENABLED() (READ_BIT(RCC->AHB2ENR, RCC_AHB2ENR_DAC1EN) != 0U)
1290 #if defined(DAC2)
1291 #define __HAL_RCC_DAC2_IS_CLK_ENABLED() (READ_BIT(RCC->AHB2ENR, RCC_AHB2ENR_DAC2EN) != 0U)
1292 #endif /* DAC2 */
1294 #define __HAL_RCC_DAC3_IS_CLK_ENABLED() (READ_BIT(RCC->AHB2ENR, RCC_AHB2ENR_DAC3EN) != 0U)
1296 #if defined(DAC4)
1297 #define __HAL_RCC_DAC4_IS_CLK_ENABLED() (READ_BIT(RCC->AHB2ENR, RCC_AHB2ENR_DAC4EN) != 0U)
1298 #endif /* DAC4 */
1300 #if defined(AES)
1301 #define __HAL_RCC_AES_IS_CLK_ENABLED() (READ_BIT(RCC->AHB2ENR, RCC_AHB2ENR_AESEN) != 0U)
1302 #endif /* AES */
1304 #define __HAL_RCC_RNG_IS_CLK_ENABLED() (READ_BIT(RCC->AHB2ENR, RCC_AHB2ENR_RNGEN) != 0U)
1307 #define __HAL_RCC_GPIOA_IS_CLK_DISABLED() (READ_BIT(RCC->AHB2ENR, RCC_AHB2ENR_GPIOAEN) == 0U)
1309 #define __HAL_RCC_GPIOB_IS_CLK_DISABLED() (READ_BIT(RCC->AHB2ENR, RCC_AHB2ENR_GPIOBEN) == 0U)
1311 #define __HAL_RCC_GPIOC_IS_CLK_DISABLED() (READ_BIT(RCC->AHB2ENR, RCC_AHB2ENR_GPIOCEN) == 0U)
1313 #define __HAL_RCC_GPIOD_IS_CLK_DISABLED() (READ_BIT(RCC->AHB2ENR, RCC_AHB2ENR_GPIODEN) == 0U)
1315 #define __HAL_RCC_GPIOE_IS_CLK_DISABLED() (READ_BIT(RCC->AHB2ENR, RCC_AHB2ENR_GPIOEEN) == 0U)
1317 #define __HAL_RCC_GPIOF_IS_CLK_DISABLED() (READ_BIT(RCC->AHB2ENR, RCC_AHB2ENR_GPIOFEN) == 0U)
1319 #define __HAL_RCC_GPIOG_IS_CLK_DISABLED() (READ_BIT(RCC->AHB2ENR, RCC_AHB2ENR_GPIOGEN) == 0U)
1321 #define __HAL_RCC_ADC12_IS_CLK_DISABLED() (READ_BIT(RCC->AHB2ENR, RCC_AHB2ENR_ADC12EN) == 0U)
1323 #if defined(ADC345_COMMON)
1324 #define __HAL_RCC_ADC345_IS_CLK_DISABLED() (READ_BIT(RCC->AHB2ENR, RCC_AHB2ENR_ADC345EN) == 0U)
1325 #endif /* ADC345_COMMON */
1327 #define __HAL_RCC_DAC1_IS_CLK_DISABLED() (READ_BIT(RCC->AHB2ENR, RCC_AHB2ENR_DAC1EN) == 0U)
1329 #if defined(DAC2)
1330 #define __HAL_RCC_DAC2_IS_CLK_DISABLED() (READ_BIT(RCC->AHB2ENR, RCC_AHB2ENR_DAC2EN) == 0U)
1331 #endif /* DAC2 */
1333 #define __HAL_RCC_DAC3_IS_CLK_DISABLED() (READ_BIT(RCC->AHB2ENR, RCC_AHB2ENR_DAC3EN) == 0U)
1335 #if defined(DAC4)
1336 #define __HAL_RCC_DAC4_IS_CLK_DISABLED() (READ_BIT(RCC->AHB2ENR, RCC_AHB2ENR_DAC4EN) == 0U)
1337 #endif /* DAC4 */
1339 #if defined(AES)
1340 #define __HAL_RCC_AES_IS_CLK_DISABLED() (READ_BIT(RCC->AHB2ENR, RCC_AHB2ENR_AESEN) == 0U)
1341 #endif /* AES */
1343 #define __HAL_RCC_RNG_IS_CLK_DISABLED() (READ_BIT(RCC->AHB2ENR, RCC_AHB2ENR_RNGEN) == 0U)
1346 * @}
1349 /** @defgroup RCC_AHB3_Clock_Enable_Disable_Status AHB3 Peripheral Clock Enabled or Disabled Status
1350 * @brief Check whether the AHB3 peripheral clock is enabled or not.
1351 * @note After reset, the peripheral clock (used for registers read/write access)
1352 * is disabled and the application software has to enable this clock before
1353 * using it.
1354 * @{
1357 #if defined(FMC_BANK1)
1358 #define __HAL_RCC_FMC_IS_CLK_ENABLED() (READ_BIT(RCC->AHB3ENR, RCC_AHB3ENR_FMCEN) != 0U)
1359 #endif /* FMC_BANK1 */
1361 #if defined(QUADSPI)
1362 #define __HAL_RCC_QSPI_IS_CLK_ENABLED() (READ_BIT(RCC->AHB3ENR, RCC_AHB3ENR_QSPIEN) != 0U)
1363 #endif /* QUADSPI */
1365 #if defined(FMC_BANK1)
1366 #define __HAL_RCC_FMC_IS_CLK_DISABLED() (READ_BIT(RCC->AHB3ENR, RCC_AHB3ENR_FMCEN) == 0U)
1367 #endif /* FMC_BANK1 */
1369 #if defined(QUADSPI)
1370 #define __HAL_RCC_QSPI_IS_CLK_DISABLED() (READ_BIT(RCC->AHB3ENR, RCC_AHB3ENR_QSPIEN) == 0U)
1371 #endif /* QUADSPI */
1374 * @}
1377 /** @defgroup RCC_APB1_Clock_Enable_Disable_Status APB1 Peripheral Clock Enabled or Disabled Status
1378 * @brief Check whether the APB1 peripheral clock is enabled or not.
1379 * @note After reset, the peripheral clock (used for registers read/write access)
1380 * is disabled and the application software has to enable this clock before
1381 * using it.
1382 * @{
1385 #define __HAL_RCC_TIM2_IS_CLK_ENABLED() (READ_BIT(RCC->APB1ENR1, RCC_APB1ENR1_TIM2EN) != 0U)
1387 #define __HAL_RCC_TIM3_IS_CLK_ENABLED() (READ_BIT(RCC->APB1ENR1, RCC_APB1ENR1_TIM3EN) != 0U)
1389 #define __HAL_RCC_TIM4_IS_CLK_ENABLED() (READ_BIT(RCC->APB1ENR1, RCC_APB1ENR1_TIM4EN) != 0U)
1391 #if defined(TIM5)
1392 #define __HAL_RCC_TIM5_IS_CLK_ENABLED() (READ_BIT(RCC->APB1ENR1, RCC_APB1ENR1_TIM5EN) != 0U)
1393 #endif /* TIM5 */
1395 #define __HAL_RCC_TIM6_IS_CLK_ENABLED() (READ_BIT(RCC->APB1ENR1, RCC_APB1ENR1_TIM6EN) != 0U)
1397 #define __HAL_RCC_TIM7_IS_CLK_ENABLED() (READ_BIT(RCC->APB1ENR1, RCC_APB1ENR1_TIM7EN) != 0U)
1399 #define __HAL_RCC_CRS_IS_CLK_ENABLED() (READ_BIT(RCC->APB1ENR1, RCC_APB1ENR1_CRSEN) != 0U)
1401 #define __HAL_RCC_RTCAPB_IS_CLK_ENABLED() (READ_BIT(RCC->APB1ENR1, RCC_APB1ENR1_RTCAPBEN) != 0U)
1403 #define __HAL_RCC_WWDG_IS_CLK_ENABLED() (READ_BIT(RCC->APB1ENR1, RCC_APB1ENR1_WWDGEN) != 0U)
1405 #define __HAL_RCC_SPI2_IS_CLK_ENABLED() (READ_BIT(RCC->APB1ENR1, RCC_APB1ENR1_SPI2EN) != 0U)
1407 #define __HAL_RCC_SPI3_IS_CLK_ENABLED() (READ_BIT(RCC->APB1ENR1, RCC_APB1ENR1_SPI3EN) != 0U)
1409 #define __HAL_RCC_USART2_IS_CLK_ENABLED() (READ_BIT(RCC->APB1ENR1, RCC_APB1ENR1_USART2EN) != 0U)
1411 #define __HAL_RCC_USART3_IS_CLK_ENABLED() (READ_BIT(RCC->APB1ENR1, RCC_APB1ENR1_USART3EN) != 0U)
1413 #if defined(UART4)
1414 #define __HAL_RCC_UART4_IS_CLK_ENABLED() (READ_BIT(RCC->APB1ENR1, RCC_APB1ENR1_UART4EN) != 0U)
1415 #endif /* UART4 */
1417 #if defined(UART5)
1418 #define __HAL_RCC_UART5_IS_CLK_ENABLED() (READ_BIT(RCC->APB1ENR1, RCC_APB1ENR1_UART5EN) != 0U)
1419 #endif /* UART5 */
1421 #define __HAL_RCC_I2C1_IS_CLK_ENABLED() (READ_BIT(RCC->APB1ENR1, RCC_APB1ENR1_I2C1EN) != 0U)
1423 #define __HAL_RCC_I2C2_IS_CLK_ENABLED() (READ_BIT(RCC->APB1ENR1, RCC_APB1ENR1_I2C2EN) != 0U)
1425 #define __HAL_RCC_USB_IS_CLK_ENABLED() (READ_BIT(RCC->APB1ENR1, RCC_APB1ENR1_USBEN) != 0U)
1427 #if defined(FDCAN1)
1428 #define __HAL_RCC_FDCAN_IS_CLK_ENABLED() (READ_BIT(RCC->APB1ENR1, RCC_APB1ENR1_FDCANEN) != 0U)
1429 #endif /* FDCAN1 */
1431 #define __HAL_RCC_PWR_IS_CLK_ENABLED() (READ_BIT(RCC->APB1ENR1, RCC_APB1ENR1_PWREN) != 0U)
1433 #define __HAL_RCC_I2C3_IS_CLK_ENABLED() (READ_BIT(RCC->APB1ENR1, RCC_APB1ENR1_I2C3EN) != 0U)
1435 #define __HAL_RCC_LPTIM1_IS_CLK_ENABLED() (READ_BIT(RCC->APB1ENR1, RCC_APB1ENR1_LPTIM1EN) != 0U)
1437 #define __HAL_RCC_LPUART1_IS_CLK_ENABLED() (READ_BIT(RCC->APB1ENR2, RCC_APB1ENR2_LPUART1EN) != 0U)
1439 #if defined(I2C4)
1440 #define __HAL_RCC_I2C4_IS_CLK_ENABLED() (READ_BIT(RCC->APB1ENR2, RCC_APB1ENR2_I2C4EN) != 0U)
1441 #endif /* I2C4 */
1443 #define __HAL_RCC_UCPD1_IS_CLK_ENABLED() (READ_BIT(RCC->APB1ENR2, RCC_APB1ENR2_UCPD1EN) != 0U)
1445 #define __HAL_RCC_TIM2_IS_CLK_DISABLED() (READ_BIT(RCC->APB1ENR1, RCC_APB1ENR1_TIM2EN) == 0U)
1447 #define __HAL_RCC_TIM3_IS_CLK_DISABLED() (READ_BIT(RCC->APB1ENR1, RCC_APB1ENR1_TIM3EN) == 0U)
1449 #define __HAL_RCC_TIM4_IS_CLK_DISABLED() (READ_BIT(RCC->APB1ENR1, RCC_APB1ENR1_TIM4EN) == 0U)
1451 #if defined(TIM5)
1452 #define __HAL_RCC_TIM5_IS_CLK_DISABLED() (READ_BIT(RCC->APB1ENR1, RCC_APB1ENR1_TIM5EN) == 0U)
1453 #endif /* TIM5 */
1455 #define __HAL_RCC_TIM6_IS_CLK_DISABLED() (READ_BIT(RCC->APB1ENR1, RCC_APB1ENR1_TIM6EN) == 0U)
1457 #define __HAL_RCC_TIM7_IS_CLK_DISABLED() (READ_BIT(RCC->APB1ENR1, RCC_APB1ENR1_TIM7EN) == 0U)
1459 #define __HAL_RCC_CRS_IS_CLK_DISABLED() (READ_BIT(RCC->APB1ENR1, RCC_APB1ENR1_CRSEN) == 0U)
1461 #define __HAL_RCC_RTCAPB_IS_CLK_DISABLED() (READ_BIT(RCC->APB1ENR1, RCC_APB1ENR1_RTCAPBEN) == 0U)
1463 #define __HAL_RCC_WWDG_IS_CLK_DISABLED() (READ_BIT(RCC->APB1ENR1, RCC_APB1ENR1_WWDGEN) == 0U)
1465 #define __HAL_RCC_SPI2_IS_CLK_DISABLED() (READ_BIT(RCC->APB1ENR1, RCC_APB1ENR1_SPI2EN) == 0U)
1467 #define __HAL_RCC_SPI3_IS_CLK_DISABLED() (READ_BIT(RCC->APB1ENR1, RCC_APB1ENR1_SPI3EN) == 0U)
1469 #define __HAL_RCC_USART2_IS_CLK_DISABLED() (READ_BIT(RCC->APB1ENR1, RCC_APB1ENR1_USART2EN) == 0U)
1471 #define __HAL_RCC_USART3_IS_CLK_DISABLED() (READ_BIT(RCC->APB1ENR1, RCC_APB1ENR1_USART3EN) == 0U)
1473 #if defined(UART4)
1474 #define __HAL_RCC_UART4_IS_CLK_DISABLED() (READ_BIT(RCC->APB1ENR1, RCC_APB1ENR1_UART4EN) == 0U)
1475 #endif /* UART4 */
1477 #if defined(UART5)
1478 #define __HAL_RCC_UART5_IS_CLK_DISABLED() (READ_BIT(RCC->APB1ENR1, RCC_APB1ENR1_UART5EN) == 0U)
1479 #endif /* UART5 */
1481 #define __HAL_RCC_I2C1_IS_CLK_DISABLED() (READ_BIT(RCC->APB1ENR1, RCC_APB1ENR1_I2C1EN) == 0U)
1483 #define __HAL_RCC_I2C2_IS_CLK_DISABLED() (READ_BIT(RCC->APB1ENR1, RCC_APB1ENR1_I2C2EN) == 0U)
1485 #if defined(USB)
1486 #define __HAL_RCC_USB_IS_CLK_DISABLED() (READ_BIT(RCC->APB1ENR1, RCC_APB1ENR1_USBEN) == 0U)
1487 #endif /* USB */
1489 #if defined(FDCAN1)
1490 #define __HAL_RCC_FDCAN_IS_CLK_DISABLED() (READ_BIT(RCC->APB1ENR1, RCC_APB1ENR1_FDCANEN) == 0U)
1491 #endif /* FDCAN1 */
1493 #define __HAL_RCC_PWR_IS_CLK_DISABLED() (READ_BIT(RCC->APB1ENR1, RCC_APB1ENR1_PWREN) == 0U)
1495 #define __HAL_RCC_I2C3_IS_CLK_DISABLED() (READ_BIT(RCC->APB1ENR1, RCC_APB1ENR1_I2C3EN) == 0U)
1497 #define __HAL_RCC_LPTIM1_IS_CLK_DISABLED() (READ_BIT(RCC->APB1ENR1, RCC_APB1ENR1_LPTIM1EN) == 0U)
1499 #define __HAL_RCC_LPUART1_IS_CLK_DISABLED() (READ_BIT(RCC->APB1ENR2, RCC_APB1ENR2_LPUART1EN) == 0U)
1501 #if defined(I2C4)
1502 #define __HAL_RCC_I2C4_IS_CLK_DISABLED() (READ_BIT(RCC->APB1ENR2, RCC_APB1ENR2_I2C4EN) == 0U)
1503 #endif /* I2C4 */
1505 #define __HAL_RCC_UCPD1_IS_CLK_DISABLED() (READ_BIT(RCC->APB1ENR2, RCC_APB1ENR2_UCPD1EN) == 0U)
1508 * @}
1511 /** @defgroup RCC_APB2_Clock_Enable_Disable_Status APB2 Peripheral Clock Enabled or Disabled Status
1512 * @brief Check whether the APB2 peripheral clock is enabled or not.
1513 * @note After reset, the peripheral clock (used for registers read/write access)
1514 * is disabled and the application software has to enable this clock before
1515 * using it.
1516 * @{
1519 #define __HAL_RCC_SYSCFG_IS_CLK_ENABLED() (READ_BIT(RCC->APB2ENR, RCC_APB2ENR_SYSCFGEN) != 0U)
1521 #define __HAL_RCC_TIM1_IS_CLK_ENABLED() (READ_BIT(RCC->APB2ENR, RCC_APB2ENR_TIM1EN) != 0U)
1523 #define __HAL_RCC_SPI1_IS_CLK_ENABLED() (READ_BIT(RCC->APB2ENR, RCC_APB2ENR_SPI1EN) != 0U)
1525 #define __HAL_RCC_TIM8_IS_CLK_ENABLED() (READ_BIT(RCC->APB2ENR, RCC_APB2ENR_TIM8EN) != 0U)
1527 #define __HAL_RCC_USART1_IS_CLK_ENABLED() (READ_BIT(RCC->APB2ENR, RCC_APB2ENR_USART1EN) != 0U)
1529 #if defined(SPI4)
1530 #define __HAL_RCC_SPI4_IS_CLK_ENABLED() (READ_BIT(RCC->APB2ENR, RCC_APB2ENR_SPI4EN) != 0U)
1531 #endif /* SPI4 */
1533 #define __HAL_RCC_TIM15_IS_CLK_ENABLED() (READ_BIT(RCC->APB2ENR, RCC_APB2ENR_TIM15EN) != 0U)
1535 #define __HAL_RCC_TIM16_IS_CLK_ENABLED() (READ_BIT(RCC->APB2ENR, RCC_APB2ENR_TIM16EN) != 0U)
1537 #define __HAL_RCC_TIM17_IS_CLK_ENABLED() (READ_BIT(RCC->APB2ENR, RCC_APB2ENR_TIM17EN) != 0U)
1539 #if defined(TIM20)
1540 #define __HAL_RCC_TIM20_IS_CLK_ENABLED() (READ_BIT(RCC->APB2ENR, RCC_APB2ENR_TIM20EN) != 0U)
1541 #endif /* TIM20 */
1543 #define __HAL_RCC_SAI1_IS_CLK_ENABLED() (READ_BIT(RCC->APB2ENR, RCC_APB2ENR_SAI1EN) != 0U)
1545 #if defined(HRTIM1)
1546 #define __HAL_RCC_HRTIM1_IS_CLK_ENABLED() (READ_BIT(RCC->APB2ENR, RCC_APB2ENR_HRTIM1EN) != 0U)
1547 #endif /* HRTIM1 */
1550 #define __HAL_RCC_SYSCFG_IS_CLK_DISABLED() (READ_BIT(RCC->APB2ENR, RCC_APB2ENR_SYSCFGEN) == 0U)
1552 #define __HAL_RCC_TIM1_IS_CLK_DISABLED() (READ_BIT(RCC->APB2ENR, RCC_APB2ENR_TIM1EN) == 0U)
1554 #define __HAL_RCC_SPI1_IS_CLK_DISABLED() (READ_BIT(RCC->APB2ENR, RCC_APB2ENR_SPI1EN) == 0U)
1556 #define __HAL_RCC_TIM8_IS_CLK_DISABLED() (READ_BIT(RCC->APB2ENR, RCC_APB2ENR_TIM8EN) == 0U)
1558 #define __HAL_RCC_USART1_IS_CLK_DISABLED() (READ_BIT(RCC->APB2ENR, RCC_APB2ENR_USART1EN) == 0U)
1560 #if defined(SPI4)
1561 #define __HAL_RCC_SPI4_IS_CLK_DISABLED() (READ_BIT(RCC->APB2ENR, RCC_APB2ENR_SPI4EN) == 0U)
1562 #endif /* SPI4 */
1564 #define __HAL_RCC_TIM15_IS_CLK_DISABLED() (READ_BIT(RCC->APB2ENR, RCC_APB2ENR_TIM15EN) == 0U)
1566 #define __HAL_RCC_TIM16_IS_CLK_DISABLED() (READ_BIT(RCC->APB2ENR, RCC_APB2ENR_TIM16EN) == 0U)
1568 #define __HAL_RCC_TIM17_IS_CLK_DISABLED() (READ_BIT(RCC->APB2ENR, RCC_APB2ENR_TIM17EN) == 0U)
1570 #if defined(TIM20)
1571 #define __HAL_RCC_TIM20_IS_CLK_DISABLED() (READ_BIT(RCC->APB2ENR, RCC_APB2ENR_TIM20EN) == 0U)
1572 #endif /* TIM20 */
1574 #define __HAL_RCC_SAI1_IS_CLK_DISABLED() (READ_BIT(RCC->APB2ENR, RCC_APB2ENR_SAI1EN) == 0U)
1576 #if defined(HRTIM1)
1577 #define __HAL_RCC_HRTIM1_IS_CLK_DISABLED() (READ_BIT(RCC->APB2ENR, RCC_APB2ENR_HRTIM1EN) == 0U)
1578 #endif /* HRTIM1 */
1581 * @}
1584 /** @defgroup RCC_AHB1_Force_Release_Reset AHB1 Peripheral Force Release Reset
1585 * @brief Force or release AHB1 peripheral reset.
1586 * @{
1588 #define __HAL_RCC_AHB1_FORCE_RESET() WRITE_REG(RCC->AHB1RSTR, 0xFFFFFFFFU)
1590 #define __HAL_RCC_DMA1_FORCE_RESET() SET_BIT(RCC->AHB1RSTR, RCC_AHB1RSTR_DMA1RST)
1592 #define __HAL_RCC_DMA2_FORCE_RESET() SET_BIT(RCC->AHB1RSTR, RCC_AHB1RSTR_DMA2RST)
1594 #define __HAL_RCC_DMAMUX1_FORCE_RESET() SET_BIT(RCC->AHB1RSTR, RCC_AHB1RSTR_DMAMUX1RST)
1596 #define __HAL_RCC_CORDIC_FORCE_RESET() SET_BIT(RCC->AHB1RSTR, RCC_AHB1RSTR_CORDICRST)
1598 #define __HAL_RCC_FMAC_FORCE_RESET() SET_BIT(RCC->AHB1RSTR, RCC_AHB1RSTR_FMACRST)
1600 #define __HAL_RCC_FLASH_FORCE_RESET() SET_BIT(RCC->AHB1RSTR, RCC_AHB1RSTR_FLASHRST)
1602 #define __HAL_RCC_CRC_FORCE_RESET() SET_BIT(RCC->AHB1RSTR, RCC_AHB1RSTR_CRCRST)
1605 #define __HAL_RCC_AHB1_RELEASE_RESET() WRITE_REG(RCC->AHB1RSTR, 0x00000000U)
1607 #define __HAL_RCC_DMA1_RELEASE_RESET() CLEAR_BIT(RCC->AHB1RSTR, RCC_AHB1RSTR_DMA1RST)
1609 #define __HAL_RCC_DMA2_RELEASE_RESET() CLEAR_BIT(RCC->AHB1RSTR, RCC_AHB1RSTR_DMA2RST)
1611 #define __HAL_RCC_DMAMUX1_RELEASE_RESET() CLEAR_BIT(RCC->AHB1RSTR, RCC_AHB1RSTR_DMAMUX1RST)
1613 #define __HAL_RCC_CORDIC_RELEASE_RESET() CLEAR_BIT(RCC->AHB1RSTR, RCC_AHB1RSTR_CORDICRST)
1615 #define __HAL_RCC_FMAC_RELEASE_RESET() CLEAR_BIT(RCC->AHB1RSTR, RCC_AHB1RSTR_FMACRST)
1617 #define __HAL_RCC_FLASH_RELEASE_RESET() CLEAR_BIT(RCC->AHB1RSTR, RCC_AHB1RSTR_FLASHRST)
1619 #define __HAL_RCC_CRC_RELEASE_RESET() CLEAR_BIT(RCC->AHB1RSTR, RCC_AHB1RSTR_CRCRST)
1622 * @}
1625 /** @defgroup RCC_AHB2_Force_Release_Reset AHB2 Peripheral Force Release Reset
1626 * @brief Force or release AHB2 peripheral reset.
1627 * @{
1629 #define __HAL_RCC_AHB2_FORCE_RESET() WRITE_REG(RCC->AHB2RSTR, 0xFFFFFFFFU)
1631 #define __HAL_RCC_GPIOA_FORCE_RESET() SET_BIT(RCC->AHB2RSTR, RCC_AHB2RSTR_GPIOARST)
1633 #define __HAL_RCC_GPIOB_FORCE_RESET() SET_BIT(RCC->AHB2RSTR, RCC_AHB2RSTR_GPIOBRST)
1635 #define __HAL_RCC_GPIOC_FORCE_RESET() SET_BIT(RCC->AHB2RSTR, RCC_AHB2RSTR_GPIOCRST)
1637 #define __HAL_RCC_GPIOD_FORCE_RESET() SET_BIT(RCC->AHB2RSTR, RCC_AHB2RSTR_GPIODRST)
1639 #define __HAL_RCC_GPIOE_FORCE_RESET() SET_BIT(RCC->AHB2RSTR, RCC_AHB2RSTR_GPIOERST)
1641 #define __HAL_RCC_GPIOF_FORCE_RESET() SET_BIT(RCC->AHB2RSTR, RCC_AHB2RSTR_GPIOFRST)
1643 #define __HAL_RCC_GPIOG_FORCE_RESET() SET_BIT(RCC->AHB2RSTR, RCC_AHB2RSTR_GPIOGRST)
1645 #define __HAL_RCC_ADC12_FORCE_RESET() SET_BIT(RCC->AHB2RSTR, RCC_AHB2RSTR_ADC12RST)
1647 #if defined(ADC345_COMMON)
1648 #define __HAL_RCC_ADC345_FORCE_RESET() SET_BIT(RCC->AHB2RSTR, RCC_AHB2RSTR_ADC345RST)
1649 #endif /* ADC345_COMMON */
1651 #define __HAL_RCC_DAC1_FORCE_RESET() SET_BIT(RCC->AHB2RSTR, RCC_AHB2RSTR_DAC1RST)
1653 #if defined(DAC2)
1654 #define __HAL_RCC_DAC2_FORCE_RESET() SET_BIT(RCC->AHB2RSTR, RCC_AHB2RSTR_DAC2RST)
1655 #endif /* DAC2 */
1657 #define __HAL_RCC_DAC3_FORCE_RESET() SET_BIT(RCC->AHB2RSTR, RCC_AHB2RSTR_DAC3RST)
1659 #if defined(DAC4)
1660 #define __HAL_RCC_DAC4_FORCE_RESET() SET_BIT(RCC->AHB2RSTR, RCC_AHB2RSTR_DAC4RST)
1661 #endif /* DAC4 */
1663 #if defined(AES)
1664 #define __HAL_RCC_AES_FORCE_RESET() SET_BIT(RCC->AHB2RSTR, RCC_AHB2RSTR_AESRST)
1665 #endif /* AES */
1667 #define __HAL_RCC_RNG_FORCE_RESET() SET_BIT(RCC->AHB2RSTR, RCC_AHB2RSTR_RNGRST)
1670 #define __HAL_RCC_AHB2_RELEASE_RESET() WRITE_REG(RCC->AHB2RSTR, 0x00000000U)
1672 #define __HAL_RCC_GPIOA_RELEASE_RESET() CLEAR_BIT(RCC->AHB2RSTR, RCC_AHB2RSTR_GPIOARST)
1674 #define __HAL_RCC_GPIOB_RELEASE_RESET() CLEAR_BIT(RCC->AHB2RSTR, RCC_AHB2RSTR_GPIOBRST)
1676 #define __HAL_RCC_GPIOC_RELEASE_RESET() CLEAR_BIT(RCC->AHB2RSTR, RCC_AHB2RSTR_GPIOCRST)
1678 #define __HAL_RCC_GPIOD_RELEASE_RESET() CLEAR_BIT(RCC->AHB2RSTR, RCC_AHB2RSTR_GPIODRST)
1680 #define __HAL_RCC_GPIOE_RELEASE_RESET() CLEAR_BIT(RCC->AHB2RSTR, RCC_AHB2RSTR_GPIOERST)
1682 #define __HAL_RCC_GPIOF_RELEASE_RESET() CLEAR_BIT(RCC->AHB2RSTR, RCC_AHB2RSTR_GPIOFRST)
1684 #define __HAL_RCC_GPIOG_RELEASE_RESET() CLEAR_BIT(RCC->AHB2RSTR, RCC_AHB2RSTR_GPIOGRST)
1686 #define __HAL_RCC_ADC12_RELEASE_RESET() CLEAR_BIT(RCC->AHB2RSTR, RCC_AHB2RSTR_ADC12RST)
1688 #if defined(ADC345_COMMON)
1689 #define __HAL_RCC_ADC345_RELEASE_RESET() CLEAR_BIT(RCC->AHB2RSTR, RCC_AHB2RSTR_ADC345RST)
1690 #endif /* ADC345_COMMON */
1692 #define __HAL_RCC_DAC1_RELEASE_RESET() CLEAR_BIT(RCC->AHB2RSTR, RCC_AHB2RSTR_DAC1RST)
1694 #if defined(DAC2)
1695 #define __HAL_RCC_DAC2_RELEASE_RESET() CLEAR_BIT(RCC->AHB2RSTR, RCC_AHB2RSTR_DAC2RST)
1696 #endif /* DAC2 */
1698 #define __HAL_RCC_DAC3_RELEASE_RESET() CLEAR_BIT(RCC->AHB2RSTR, RCC_AHB2RSTR_DAC3RST)
1700 #if defined(DAC4)
1701 #define __HAL_RCC_DAC4_RELEASE_RESET() CLEAR_BIT(RCC->AHB2RSTR, RCC_AHB2RSTR_DAC4RST)
1702 #endif /* DAC4 */
1704 #if defined(AES)
1705 #define __HAL_RCC_AES_RELEASE_RESET() CLEAR_BIT(RCC->AHB2RSTR, RCC_AHB2RSTR_AESRST)
1706 #endif /* AES */
1708 #define __HAL_RCC_RNG_RELEASE_RESET() CLEAR_BIT(RCC->AHB2RSTR, RCC_AHB2RSTR_RNGRST)
1711 * @}
1714 /** @defgroup RCC_AHB3_Force_Release_Reset AHB3 Peripheral Force Release Reset
1715 * @brief Force or release AHB3 peripheral reset.
1716 * @{
1718 #define __HAL_RCC_AHB3_FORCE_RESET() WRITE_REG(RCC->AHB3RSTR, 0xFFFFFFFFU)
1720 #if defined(FMC_BANK1)
1721 #define __HAL_RCC_FMC_FORCE_RESET() SET_BIT(RCC->AHB3RSTR, RCC_AHB3RSTR_FMCRST)
1722 #endif /* FMC_BANK1 */
1724 #if defined(QUADSPI)
1725 #define __HAL_RCC_QSPI_FORCE_RESET() SET_BIT(RCC->AHB3RSTR, RCC_AHB3RSTR_QSPIRST)
1726 #endif /* QUADSPI */
1728 #define __HAL_RCC_AHB3_RELEASE_RESET() WRITE_REG(RCC->AHB3RSTR, 0x00000000U)
1730 #if defined(FMC_BANK1)
1731 #define __HAL_RCC_FMC_RELEASE_RESET() CLEAR_BIT(RCC->AHB3RSTR, RCC_AHB3RSTR_FMCRST)
1732 #endif /* FMC_BANK1 */
1734 #if defined(QUADSPI)
1735 #define __HAL_RCC_QSPI_RELEASE_RESET() CLEAR_BIT(RCC->AHB3RSTR, RCC_AHB3RSTR_QSPIRST)
1736 #endif /* QUADSPI */
1739 * @}
1742 /** @defgroup RCC_APB1_Force_Release_Reset APB1 Peripheral Force Release Reset
1743 * @brief Force or release APB1 peripheral reset.
1744 * @{
1746 #define __HAL_RCC_APB1_FORCE_RESET() WRITE_REG(RCC->APB1RSTR1, 0xFFFFFFFFU)
1748 #define __HAL_RCC_TIM2_FORCE_RESET() SET_BIT(RCC->APB1RSTR1, RCC_APB1RSTR1_TIM2RST)
1750 #define __HAL_RCC_TIM3_FORCE_RESET() SET_BIT(RCC->APB1RSTR1, RCC_APB1RSTR1_TIM3RST)
1752 #define __HAL_RCC_TIM4_FORCE_RESET() SET_BIT(RCC->APB1RSTR1, RCC_APB1RSTR1_TIM4RST)
1754 #if defined(TIM5)
1755 #define __HAL_RCC_TIM5_FORCE_RESET() SET_BIT(RCC->APB1RSTR1, RCC_APB1RSTR1_TIM5RST)
1756 #endif /* TIM5 */
1758 #define __HAL_RCC_TIM6_FORCE_RESET() SET_BIT(RCC->APB1RSTR1, RCC_APB1RSTR1_TIM6RST)
1760 #define __HAL_RCC_TIM7_FORCE_RESET() SET_BIT(RCC->APB1RSTR1, RCC_APB1RSTR1_TIM7RST)
1762 #define __HAL_RCC_CRS_FORCE_RESET() SET_BIT(RCC->APB1RSTR1, RCC_APB1RSTR1_CRSRST)
1764 #define __HAL_RCC_SPI2_FORCE_RESET() SET_BIT(RCC->APB1RSTR1, RCC_APB1RSTR1_SPI2RST)
1766 #define __HAL_RCC_SPI3_FORCE_RESET() SET_BIT(RCC->APB1RSTR1, RCC_APB1RSTR1_SPI3RST)
1768 #define __HAL_RCC_USART2_FORCE_RESET() SET_BIT(RCC->APB1RSTR1, RCC_APB1RSTR1_USART2RST)
1770 #define __HAL_RCC_USART3_FORCE_RESET() SET_BIT(RCC->APB1RSTR1, RCC_APB1RSTR1_USART3RST)
1772 #if defined(UART4)
1773 #define __HAL_RCC_UART4_FORCE_RESET() SET_BIT(RCC->APB1RSTR1, RCC_APB1RSTR1_UART4RST)
1774 #endif /* UART4 */
1776 #if defined(UART5)
1777 #define __HAL_RCC_UART5_FORCE_RESET() SET_BIT(RCC->APB1RSTR1, RCC_APB1RSTR1_UART5RST)
1778 #endif /* UART5 */
1780 #define __HAL_RCC_I2C1_FORCE_RESET() SET_BIT(RCC->APB1RSTR1, RCC_APB1RSTR1_I2C1RST)
1782 #define __HAL_RCC_I2C2_FORCE_RESET() SET_BIT(RCC->APB1RSTR1, RCC_APB1RSTR1_I2C2RST)
1784 #define __HAL_RCC_USB_FORCE_RESET() SET_BIT(RCC->APB1RSTR1, RCC_APB1RSTR1_USBRST)
1786 #if defined(FDCAN1)
1787 #define __HAL_RCC_FDCAN_FORCE_RESET() SET_BIT(RCC->APB1RSTR1, RCC_APB1RSTR1_FDCANRST)
1788 #endif /* FDCAN1 */
1790 #define __HAL_RCC_PWR_FORCE_RESET() SET_BIT(RCC->APB1RSTR1, RCC_APB1RSTR1_PWRRST)
1792 #define __HAL_RCC_I2C3_FORCE_RESET() SET_BIT(RCC->APB1RSTR1, RCC_APB1RSTR1_I2C3RST)
1794 #define __HAL_RCC_LPTIM1_FORCE_RESET() SET_BIT(RCC->APB1RSTR1, RCC_APB1RSTR1_LPTIM1RST)
1796 #define __HAL_RCC_LPUART1_FORCE_RESET() SET_BIT(RCC->APB1RSTR2, RCC_APB1RSTR2_LPUART1RST)
1798 #if defined(I2C4)
1799 #define __HAL_RCC_I2C4_FORCE_RESET() SET_BIT(RCC->APB1RSTR2, RCC_APB1RSTR2_I2C4RST)
1800 #endif /* I2C4 */
1802 #define __HAL_RCC_UCPD1_FORCE_RESET() SET_BIT(RCC->APB1RSTR2, RCC_APB1RSTR2_UCPD1RST)
1804 #define __HAL_RCC_APB1_RELEASE_RESET() WRITE_REG(RCC->APB1RSTR1, 0x00000000U)
1806 #define __HAL_RCC_TIM2_RELEASE_RESET() CLEAR_BIT(RCC->APB1RSTR1, RCC_APB1RSTR1_TIM2RST)
1808 #define __HAL_RCC_TIM3_RELEASE_RESET() CLEAR_BIT(RCC->APB1RSTR1, RCC_APB1RSTR1_TIM3RST)
1810 #define __HAL_RCC_TIM4_RELEASE_RESET() CLEAR_BIT(RCC->APB1RSTR1, RCC_APB1RSTR1_TIM4RST)
1812 #if defined(TIM5)
1813 #define __HAL_RCC_TIM5_RELEASE_RESET() CLEAR_BIT(RCC->APB1RSTR1, RCC_APB1RSTR1_TIM5RST)
1814 #endif /* TIM5 */
1816 #define __HAL_RCC_TIM6_RELEASE_RESET() CLEAR_BIT(RCC->APB1RSTR1, RCC_APB1RSTR1_TIM6RST)
1818 #define __HAL_RCC_TIM7_RELEASE_RESET() CLEAR_BIT(RCC->APB1RSTR1, RCC_APB1RSTR1_TIM7RST)
1820 #define __HAL_RCC_CRS_RELEASE_RESET() CLEAR_BIT(RCC->APB1RSTR1, RCC_APB1RSTR1_CRSRST)
1822 #define __HAL_RCC_SPI2_RELEASE_RESET() CLEAR_BIT(RCC->APB1RSTR1, RCC_APB1RSTR1_SPI2RST)
1824 #define __HAL_RCC_SPI3_RELEASE_RESET() CLEAR_BIT(RCC->APB1RSTR1, RCC_APB1RSTR1_SPI3RST)
1826 #define __HAL_RCC_USART2_RELEASE_RESET() CLEAR_BIT(RCC->APB1RSTR1, RCC_APB1RSTR1_USART2RST)
1828 #define __HAL_RCC_USART3_RELEASE_RESET() CLEAR_BIT(RCC->APB1RSTR1, RCC_APB1RSTR1_USART3RST)
1830 #if defined(UART4)
1831 #define __HAL_RCC_UART4_RELEASE_RESET() CLEAR_BIT(RCC->APB1RSTR1, RCC_APB1RSTR1_UART4RST)
1832 #endif /* UART4 */
1834 #if defined(UART5)
1835 #define __HAL_RCC_UART5_RELEASE_RESET() CLEAR_BIT(RCC->APB1RSTR1, RCC_APB1RSTR1_UART5RST)
1836 #endif /* UART5 */
1838 #define __HAL_RCC_I2C1_RELEASE_RESET() CLEAR_BIT(RCC->APB1RSTR1, RCC_APB1RSTR1_I2C1RST)
1840 #define __HAL_RCC_I2C2_RELEASE_RESET() CLEAR_BIT(RCC->APB1RSTR1, RCC_APB1RSTR1_I2C2RST)
1842 #define __HAL_RCC_USB_RELEASE_RESET() CLEAR_BIT(RCC->APB1RSTR1, RCC_APB1RSTR1_USBRST)
1844 #if defined(FDCAN1)
1845 #define __HAL_RCC_FDCAN_RELEASE_RESET() CLEAR_BIT(RCC->APB1RSTR1, RCC_APB1RSTR1_FDCANRST)
1846 #endif /* FDCAN1 */
1848 #define __HAL_RCC_PWR_RELEASE_RESET() CLEAR_BIT(RCC->APB1RSTR1, RCC_APB1RSTR1_PWRRST)
1850 #define __HAL_RCC_I2C3_RELEASE_RESET() CLEAR_BIT(RCC->APB1RSTR1, RCC_APB1RSTR1_I2C3RST)
1852 #define __HAL_RCC_LPTIM1_RELEASE_RESET() CLEAR_BIT(RCC->APB1RSTR1, RCC_APB1RSTR1_LPTIM1RST)
1854 #define __HAL_RCC_LPUART1_RELEASE_RESET() CLEAR_BIT(RCC->APB1RSTR2, RCC_APB1RSTR2_LPUART1RST)
1856 #if defined(I2C4)
1857 #define __HAL_RCC_I2C4_RELEASE_RESET() CLEAR_BIT(RCC->APB1RSTR2, RCC_APB1RSTR2_I2C4RST)
1858 #endif /* I2C4 */
1860 #define __HAL_RCC_UCPD1_RELEASE_RESET() CLEAR_BIT(RCC->APB1RSTR2, RCC_APB1RSTR2_UCPD1RST)
1863 * @}
1866 /** @defgroup RCC_APB2_Force_Release_Reset APB2 Peripheral Force Release Reset
1867 * @brief Force or release APB2 peripheral reset.
1868 * @{
1870 #define __HAL_RCC_APB2_FORCE_RESET() WRITE_REG(RCC->APB2RSTR, 0xFFFFFFFFU)
1872 #define __HAL_RCC_SYSCFG_FORCE_RESET() SET_BIT(RCC->APB2RSTR, RCC_APB2RSTR_SYSCFGRST)
1874 #define __HAL_RCC_TIM1_FORCE_RESET() SET_BIT(RCC->APB2RSTR, RCC_APB2RSTR_TIM1RST)
1876 #define __HAL_RCC_SPI1_FORCE_RESET() SET_BIT(RCC->APB2RSTR, RCC_APB2RSTR_SPI1RST)
1878 #define __HAL_RCC_TIM8_FORCE_RESET() SET_BIT(RCC->APB2RSTR, RCC_APB2RSTR_TIM8RST)
1880 #define __HAL_RCC_USART1_FORCE_RESET() SET_BIT(RCC->APB2RSTR, RCC_APB2RSTR_USART1RST)
1882 #if defined(SPI4)
1883 #define __HAL_RCC_SPI4_FORCE_RESET() SET_BIT(RCC->APB2RSTR, RCC_APB2RSTR_SPI4RST)
1884 #endif /* SPI4 */
1886 #define __HAL_RCC_TIM15_FORCE_RESET() SET_BIT(RCC->APB2RSTR, RCC_APB2RSTR_TIM15RST)
1888 #define __HAL_RCC_TIM16_FORCE_RESET() SET_BIT(RCC->APB2RSTR, RCC_APB2RSTR_TIM16RST)
1890 #define __HAL_RCC_TIM17_FORCE_RESET() SET_BIT(RCC->APB2RSTR, RCC_APB2RSTR_TIM17RST)
1892 #if defined(TIM20)
1893 #define __HAL_RCC_TIM20_FORCE_RESET() SET_BIT(RCC->APB2RSTR, RCC_APB2RSTR_TIM20RST)
1894 #endif /* TIM20 */
1896 #define __HAL_RCC_SAI1_FORCE_RESET() SET_BIT(RCC->APB2RSTR, RCC_APB2RSTR_SAI1RST)
1898 #if defined(HRTIM1)
1899 #define __HAL_RCC_HRTIM1_FORCE_RESET() SET_BIT(RCC->APB2RSTR, RCC_APB2RSTR_HRTIM1RST)
1900 #endif /* HRTIM1 */
1903 #define __HAL_RCC_APB2_RELEASE_RESET() WRITE_REG(RCC->APB2RSTR, 0x00000000U)
1905 #define __HAL_RCC_SYSCFG_RELEASE_RESET() CLEAR_BIT(RCC->APB2RSTR, RCC_APB2RSTR_SYSCFGRST)
1907 #define __HAL_RCC_TIM1_RELEASE_RESET() CLEAR_BIT(RCC->APB2RSTR, RCC_APB2RSTR_TIM1RST)
1909 #define __HAL_RCC_SPI1_RELEASE_RESET() CLEAR_BIT(RCC->APB2RSTR, RCC_APB2RSTR_SPI1RST)
1911 #define __HAL_RCC_TIM8_RELEASE_RESET() CLEAR_BIT(RCC->APB2RSTR, RCC_APB2RSTR_TIM8RST)
1913 #define __HAL_RCC_USART1_RELEASE_RESET() CLEAR_BIT(RCC->APB2RSTR, RCC_APB2RSTR_USART1RST)
1915 #if defined(SPI4)
1916 #define __HAL_RCC_SPI4_RELEASE_RESET() CLEAR_BIT(RCC->APB2RSTR, RCC_APB2RSTR_SPI4RST)
1917 #endif /* SPI4 */
1919 #define __HAL_RCC_TIM15_RELEASE_RESET() CLEAR_BIT(RCC->APB2RSTR, RCC_APB2RSTR_TIM15RST)
1921 #define __HAL_RCC_TIM16_RELEASE_RESET() CLEAR_BIT(RCC->APB2RSTR, RCC_APB2RSTR_TIM16RST)
1923 #define __HAL_RCC_TIM17_RELEASE_RESET() CLEAR_BIT(RCC->APB2RSTR, RCC_APB2RSTR_TIM17RST)
1925 #if defined(TIM20)
1926 #define __HAL_RCC_TIM20_RELEASE_RESET() CLEAR_BIT(RCC->APB2RSTR, RCC_APB2RSTR_TIM20RST)
1927 #endif /* TIM20 */
1929 #define __HAL_RCC_SAI1_RELEASE_RESET() CLEAR_BIT(RCC->APB2RSTR, RCC_APB2RSTR_SAI1RST)
1931 #if defined(HRTIM1)
1932 #define __HAL_RCC_HRTIM1_RELEASE_RESET() CLEAR_BIT(RCC->APB2RSTR, RCC_APB2RSTR_HRTIM1RST)
1933 #endif /* HRTIM1 */
1936 * @}
1939 /** @defgroup RCC_AHB1_Clock_Sleep_Enable_Disable AHB1 Peripheral Clock Sleep Enable Disable
1940 * @brief Enable or disable the AHB1 peripheral clock during Low Power (Sleep) mode.
1941 * @note Peripheral clock gating in SLEEP mode can be used to further reduce
1942 * power consumption.
1943 * @note After wakeup from SLEEP mode, the peripheral clock is enabled again.
1944 * @note By default, all peripheral clocks are enabled during SLEEP mode.
1945 * @{
1948 #define __HAL_RCC_DMA1_CLK_SLEEP_ENABLE() SET_BIT(RCC->AHB1SMENR, RCC_AHB1SMENR_DMA1SMEN)
1950 #define __HAL_RCC_DMA2_CLK_SLEEP_ENABLE() SET_BIT(RCC->AHB1SMENR, RCC_AHB1SMENR_DMA2SMEN)
1952 #define __HAL_RCC_DMAMUX1_CLK_SLEEP_ENABLE() SET_BIT(RCC->AHB1SMENR, RCC_AHB1SMENR_DMAMUX1SMEN)
1954 #define __HAL_RCC_CORDIC_CLK_SLEEP_ENABLE() SET_BIT(RCC->AHB1SMENR, RCC_AHB1SMENR_CORDICSMEN)
1956 #define __HAL_RCC_FMAC_CLK_SLEEP_ENABLE() SET_BIT(RCC->AHB1SMENR, RCC_AHB1SMENR_FMACSMEN)
1958 #define __HAL_RCC_FLASH_CLK_SLEEP_ENABLE() SET_BIT(RCC->AHB1SMENR, RCC_AHB1SMENR_FLASHSMEN)
1960 #define __HAL_RCC_SRAM1_CLK_SLEEP_ENABLE() SET_BIT(RCC->AHB1SMENR, RCC_AHB1SMENR_SRAM1SMEN)
1962 #define __HAL_RCC_CRC_CLK_SLEEP_ENABLE() SET_BIT(RCC->AHB1SMENR, RCC_AHB1SMENR_CRCSMEN)
1965 #define __HAL_RCC_DMA1_CLK_SLEEP_DISABLE() CLEAR_BIT(RCC->AHB1SMENR, RCC_AHB1SMENR_DMA1SMEN)
1967 #define __HAL_RCC_DMA2_CLK_SLEEP_DISABLE() CLEAR_BIT(RCC->AHB1SMENR, RCC_AHB1SMENR_DMA2SMEN)
1969 #define __HAL_RCC_DMAMUX1_CLK_SLEEP_DISABLE() CLEAR_BIT(RCC->AHB1SMENR, RCC_AHB1SMENR_DMAMUX1SMEN)
1971 #define __HAL_RCC_CORDIC_CLK_SLEEP_DISABLE() CLEAR_BIT(RCC->AHB1SMENR, RCC_AHB1SMENR_CORDICSMEN)
1973 #define __HAL_RCC_FMAC_CLK_SLEEP_DISABLE() CLEAR_BIT(RCC->AHB1SMENR, RCC_AHB1SMENR_FMACSMEN)
1975 #define __HAL_RCC_FLASH_CLK_SLEEP_DISABLE() CLEAR_BIT(RCC->AHB1SMENR, RCC_AHB1SMENR_FLASHSMEN)
1977 #define __HAL_RCC_SRAM1_CLK_SLEEP_DISABLE() CLEAR_BIT(RCC->AHB1SMENR, RCC_AHB1SMENR_SRAM1SMEN)
1979 #define __HAL_RCC_CRC_CLK_SLEEP_DISABLE() CLEAR_BIT(RCC->AHB1SMENR, RCC_AHB1SMENR_CRCSMEN)
1982 * @}
1985 /** @defgroup RCC_AHB2_Clock_Sleep_Enable_Disable AHB2 Peripheral Clock Sleep Enable Disable
1986 * @brief Enable or disable the AHB2 peripheral clock during Low Power (Sleep) mode.
1987 * @note Peripheral clock gating in SLEEP mode can be used to further reduce
1988 * power consumption.
1989 * @note After wakeup from SLEEP mode, the peripheral clock is enabled again.
1990 * @note By default, all peripheral clocks are enabled during SLEEP mode.
1991 * @{
1994 #define __HAL_RCC_GPIOA_CLK_SLEEP_ENABLE() SET_BIT(RCC->AHB2SMENR, RCC_AHB2SMENR_GPIOASMEN)
1996 #define __HAL_RCC_GPIOB_CLK_SLEEP_ENABLE() SET_BIT(RCC->AHB2SMENR, RCC_AHB2SMENR_GPIOBSMEN)
1998 #define __HAL_RCC_GPIOC_CLK_SLEEP_ENABLE() SET_BIT(RCC->AHB2SMENR, RCC_AHB2SMENR_GPIOCSMEN)
2000 #define __HAL_RCC_GPIOD_CLK_SLEEP_ENABLE() SET_BIT(RCC->AHB2SMENR, RCC_AHB2SMENR_GPIODSMEN)
2002 #define __HAL_RCC_GPIOE_CLK_SLEEP_ENABLE() SET_BIT(RCC->AHB2SMENR, RCC_AHB2SMENR_GPIOESMEN)
2004 #define __HAL_RCC_GPIOF_CLK_SLEEP_ENABLE() SET_BIT(RCC->AHB2SMENR, RCC_AHB2SMENR_GPIOFSMEN)
2006 #define __HAL_RCC_GPIOG_CLK_SLEEP_ENABLE() SET_BIT(RCC->AHB2SMENR, RCC_AHB2SMENR_GPIOGSMEN)
2008 #define __HAL_RCC_SRAM2_CLK_SLEEP_ENABLE() SET_BIT(RCC->AHB2SMENR, RCC_AHB2SMENR_SRAM2SMEN)
2010 #define __HAL_RCC_CCM_CLK_SLEEP_ENABLE() SET_BIT(RCC->AHB2SMENR, RCC_AHB2SMENR_CCMSRAMSMEN)
2012 #define __HAL_RCC_ADC12_CLK_SLEEP_ENABLE() SET_BIT(RCC->AHB2SMENR, RCC_AHB2SMENR_ADC12SMEN)
2014 #if defined(ADC345_COMMON)
2015 #define __HAL_RCC_ADC345_CLK_SLEEP_ENABLE() SET_BIT(RCC->AHB2SMENR, RCC_AHB2SMENR_ADC345SMEN)
2016 #endif /* ADC345_COMMON */
2018 #define __HAL_RCC_DAC1_CLK_SLEEP_ENABLE() SET_BIT(RCC->AHB2SMENR, RCC_AHB2SMENR_DAC1SMEN)
2020 #if defined(DAC2)
2021 #define __HAL_RCC_DAC2_CLK_SLEEP_ENABLE() SET_BIT(RCC->AHB2SMENR, RCC_AHB2SMENR_DAC2SMEN)
2022 #endif /* DAC2 */
2024 #define __HAL_RCC_DAC3_CLK_SLEEP_ENABLE() SET_BIT(RCC->AHB2SMENR, RCC_AHB2SMENR_DAC3SMEN)
2026 #if defined(DAC4)
2027 #define __HAL_RCC_DAC4_CLK_SLEEP_ENABLE() SET_BIT(RCC->AHB2SMENR, RCC_AHB2SMENR_DAC4SMEN)
2028 #endif /* DAC4 */
2030 #if defined(AES)
2031 #define __HAL_RCC_AES_CLK_SLEEP_ENABLE() SET_BIT(RCC->AHB2SMENR, RCC_AHB2SMENR_AESSMEN)
2032 #endif /* AES */
2034 #define __HAL_RCC_RNG_CLK_SLEEP_ENABLE() SET_BIT(RCC->AHB2SMENR, RCC_AHB2SMENR_RNGSMEN)
2037 #define __HAL_RCC_GPIOA_CLK_SLEEP_DISABLE() CLEAR_BIT(RCC->AHB2SMENR, RCC_AHB2SMENR_GPIOASMEN)
2039 #define __HAL_RCC_GPIOB_CLK_SLEEP_DISABLE() CLEAR_BIT(RCC->AHB2SMENR, RCC_AHB2SMENR_GPIOBSMEN)
2041 #define __HAL_RCC_GPIOC_CLK_SLEEP_DISABLE() CLEAR_BIT(RCC->AHB2SMENR, RCC_AHB2SMENR_GPIOCSMEN)
2043 #define __HAL_RCC_GPIOD_CLK_SLEEP_DISABLE() CLEAR_BIT(RCC->AHB2SMENR, RCC_AHB2SMENR_GPIODSMEN)
2045 #define __HAL_RCC_GPIOE_CLK_SLEEP_DISABLE() CLEAR_BIT(RCC->AHB2SMENR, RCC_AHB2SMENR_GPIOESMEN)
2047 #define __HAL_RCC_GPIOF_CLK_SLEEP_DISABLE() CLEAR_BIT(RCC->AHB2SMENR, RCC_AHB2SMENR_GPIOFSMEN)
2049 #define __HAL_RCC_GPIOG_CLK_SLEEP_DISABLE() CLEAR_BIT(RCC->AHB2SMENR, RCC_AHB2SMENR_GPIOGSMEN)
2051 #define __HAL_RCC_SRAM2_CLK_SLEEP_DISABLE() CLEAR_BIT(RCC->AHB2SMENR, RCC_AHB2SMENR_SRAM2SMEN)
2053 #define __HAL_RCC_CCM_CLK_SLEEP_DISABLE() CLEAR_BIT(RCC->AHB2SMENR, RCC_AHB2SMENR_CCMSRAMSMEN)
2055 #define __HAL_RCC_ADC12_CLK_SLEEP_DISABLE() CLEAR_BIT(RCC->AHB2SMENR, RCC_AHB2SMENR_ADC12SMEN)
2057 #if defined(ADC345_COMMON)
2058 #define __HAL_RCC_ADC345_CLK_SLEEP_DISABLE() CLEAR_BIT(RCC->AHB2SMENR, RCC_AHB2SMENR_ADC345SMEN)
2059 #endif /* ADC345_COMMON */
2061 #define __HAL_RCC_DAC1_CLK_SLEEP_DISABLE() CLEAR_BIT(RCC->AHB2SMENR, RCC_AHB2SMENR_DAC1SMEN)
2063 #if defined(DAC2)
2064 #define __HAL_RCC_DAC2_CLK_SLEEP_DISABLE() CLEAR_BIT(RCC->AHB2SMENR, RCC_AHB2SMENR_DAC2SMEN)
2065 #endif /* DAC2 */
2067 #define __HAL_RCC_DAC3_CLK_SLEEP_DISABLE() CLEAR_BIT(RCC->AHB2SMENR, RCC_AHB2SMENR_DAC3SMEN)
2069 #if defined(DAC4)
2070 #define __HAL_RCC_DAC4_CLK_SLEEP_DISABLE() CLEAR_BIT(RCC->AHB2SMENR, RCC_AHB2SMENR_DAC4SMEN)
2071 #endif /* DAC4 */
2073 #if defined(AES)
2074 #define __HAL_RCC_AES_CLK_SLEEP_DISABLE() CLEAR_BIT(RCC->AHB2SMENR, RCC_AHB2SMENR_AESSMEN)
2075 #endif /* AES */
2077 #define __HAL_RCC_RNG_CLK_SLEEP_DISABLE() CLEAR_BIT(RCC->AHB2SMENR, RCC_AHB2SMENR_RNGSMEN)
2080 * @}
2083 /** @defgroup RCC_AHB3_Clock_Sleep_Enable_Disable AHB3 Peripheral Clock Sleep Enable Disable
2084 * @brief Enable or disable the AHB3 peripheral clock during Low Power (Sleep) mode.
2085 * @note Peripheral clock gating in SLEEP mode can be used to further reduce
2086 * power consumption.
2087 * @note After wakeup from SLEEP mode, the peripheral clock is enabled again.
2088 * @note By default, all peripheral clocks are enabled during SLEEP mode.
2089 * @{
2092 #if defined(FMC_BANK1)
2093 #define __HAL_RCC_FMC_CLK_SLEEP_ENABLE() SET_BIT(RCC->AHB3SMENR, RCC_AHB3SMENR_FMCSMEN)
2094 #endif /* FMC_BANK1 */
2096 #if defined(QUADSPI)
2097 #define __HAL_RCC_QSPI_CLK_SLEEP_ENABLE() SET_BIT(RCC->AHB3SMENR, RCC_AHB3SMENR_QSPISMEN)
2098 #endif /* QUADSPI */
2100 #if defined(FMC_BANK1)
2101 #define __HAL_RCC_FMC_CLK_SLEEP_DISABLE() CLEAR_BIT(RCC->AHB3SMENR, RCC_AHB3SMENR_FMCSMEN)
2102 #endif /* FMC_BANK1 */
2104 #if defined(QUADSPI)
2105 #define __HAL_RCC_QSPI_CLK_SLEEP_DISABLE() CLEAR_BIT(RCC->AHB3SMENR, RCC_AHB3SMENR_QSPISMEN)
2106 #endif /* QUADSPI */
2109 * @}
2112 /** @defgroup RCC_APB1_Clock_Sleep_Enable_Disable APB1 Peripheral Clock Sleep Enable Disable
2113 * @brief Enable or disable the APB1 peripheral clock during Low Power (Sleep) mode.
2114 * @note Peripheral clock gating in SLEEP mode can be used to further reduce
2115 * power consumption.
2116 * @note After wakeup from SLEEP mode, the peripheral clock is enabled again.
2117 * @note By default, all peripheral clocks are enabled during SLEEP mode.
2118 * @{
2121 #define __HAL_RCC_TIM2_CLK_SLEEP_ENABLE() SET_BIT(RCC->APB1SMENR1, RCC_APB1SMENR1_TIM2SMEN)
2123 #define __HAL_RCC_TIM3_CLK_SLEEP_ENABLE() SET_BIT(RCC->APB1SMENR1, RCC_APB1SMENR1_TIM3SMEN)
2125 #define __HAL_RCC_TIM4_CLK_SLEEP_ENABLE() SET_BIT(RCC->APB1SMENR1, RCC_APB1SMENR1_TIM4SMEN)
2127 #if defined(TIM5)
2128 #define __HAL_RCC_TIM5_CLK_SLEEP_ENABLE() SET_BIT(RCC->APB1SMENR1, RCC_APB1SMENR1_TIM5SMEN)
2129 #endif /* TIM5 */
2131 #define __HAL_RCC_TIM6_CLK_SLEEP_ENABLE() SET_BIT(RCC->APB1SMENR1, RCC_APB1SMENR1_TIM6SMEN)
2133 #define __HAL_RCC_TIM7_CLK_SLEEP_ENABLE() SET_BIT(RCC->APB1SMENR1, RCC_APB1SMENR1_TIM7SMEN)
2135 #define __HAL_RCC_CRS_CLK_SLEEP_ENABLE() SET_BIT(RCC->APB1SMENR1, RCC_APB1SMENR1_CRSSMEN)
2137 #define __HAL_RCC_RTCAPB_CLK_SLEEP_ENABLE() SET_BIT(RCC->APB1SMENR1, RCC_APB1SMENR1_RTCAPBSMEN)
2139 #define __HAL_RCC_WWDG_CLK_SLEEP_ENABLE() SET_BIT(RCC->APB1SMENR1, RCC_APB1SMENR1_WWDGSMEN)
2141 #define __HAL_RCC_SPI2_CLK_SLEEP_ENABLE() SET_BIT(RCC->APB1SMENR1, RCC_APB1SMENR1_SPI2SMEN)
2143 #define __HAL_RCC_SPI3_CLK_SLEEP_ENABLE() SET_BIT(RCC->APB1SMENR1, RCC_APB1SMENR1_SPI3SMEN)
2145 #define __HAL_RCC_USART2_CLK_SLEEP_ENABLE() SET_BIT(RCC->APB1SMENR1, RCC_APB1SMENR1_USART2SMEN)
2147 #define __HAL_RCC_USART3_CLK_SLEEP_ENABLE() SET_BIT(RCC->APB1SMENR1, RCC_APB1SMENR1_USART3SMEN)
2149 #if defined(UART4)
2150 #define __HAL_RCC_UART4_CLK_SLEEP_ENABLE() SET_BIT(RCC->APB1SMENR1, RCC_APB1SMENR1_UART4SMEN)
2151 #endif /* UART4 */
2153 #if defined(UART5)
2154 #define __HAL_RCC_UART5_CLK_SLEEP_ENABLE() SET_BIT(RCC->APB1SMENR1, RCC_APB1SMENR1_UART5SMEN)
2155 #endif /* UART5 */
2157 #define __HAL_RCC_I2C1_CLK_SLEEP_ENABLE() SET_BIT(RCC->APB1SMENR1, RCC_APB1SMENR1_I2C1SMEN)
2159 #define __HAL_RCC_I2C2_CLK_SLEEP_ENABLE() SET_BIT(RCC->APB1SMENR1, RCC_APB1SMENR1_I2C2SMEN)
2161 #if defined(USB)
2162 #define __HAL_RCC_USB_CLK_SLEEP_ENABLE() SET_BIT(RCC->APB1SMENR1, RCC_APB1SMENR1_USBSMEN)
2163 #endif /* USB */
2165 #if defined(FDCAN1)
2166 #define __HAL_RCC_FDCAN_CLK_SLEEP_ENABLE() SET_BIT(RCC->APB1SMENR1, RCC_APB1SMENR1_FDCANSMEN)
2167 #endif /* FDCAN1 */
2169 #define __HAL_RCC_PWR_CLK_SLEEP_ENABLE() SET_BIT(RCC->APB1SMENR1, RCC_APB1SMENR1_PWRSMEN)
2171 #define __HAL_RCC_I2C3_CLK_SLEEP_ENABLE() SET_BIT(RCC->APB1SMENR1, RCC_APB1SMENR1_I2C3SMEN)
2173 #define __HAL_RCC_LPTIM1_CLK_SLEEP_ENABLE() SET_BIT(RCC->APB1SMENR1, RCC_APB1SMENR1_LPTIM1SMEN)
2175 #define __HAL_RCC_LPUART1_CLK_SLEEP_ENABLE() SET_BIT(RCC->APB1SMENR2, RCC_APB1SMENR2_LPUART1SMEN)
2177 #if defined(I2C4)
2178 #define __HAL_RCC_I2C4_CLK_SLEEP_ENABLE() SET_BIT(RCC->APB1SMENR2, RCC_APB1SMENR2_I2C4SMEN)
2179 #endif /* I2C4 */
2181 #define __HAL_RCC_UCPD1_CLK_SLEEP_ENABLE() SET_BIT(RCC->APB1SMENR2, RCC_APB1SMENR2_UCPD1SMEN)
2184 #define __HAL_RCC_TIM2_CLK_SLEEP_DISABLE() CLEAR_BIT(RCC->APB1SMENR1, RCC_APB1SMENR1_TIM2SMEN)
2186 #define __HAL_RCC_TIM3_CLK_SLEEP_DISABLE() CLEAR_BIT(RCC->APB1SMENR1, RCC_APB1SMENR1_TIM3SMEN)
2188 #define __HAL_RCC_TIM4_CLK_SLEEP_DISABLE() CLEAR_BIT(RCC->APB1SMENR1, RCC_APB1SMENR1_TIM4SMEN)
2190 #if defined(TIM5)
2191 #define __HAL_RCC_TIM5_CLK_SLEEP_DISABLE() CLEAR_BIT(RCC->APB1SMENR1, RCC_APB1SMENR1_TIM5SMEN)
2192 #endif /* TIM5 */
2194 #define __HAL_RCC_TIM6_CLK_SLEEP_DISABLE() CLEAR_BIT(RCC->APB1SMENR1, RCC_APB1SMENR1_TIM6SMEN)
2196 #define __HAL_RCC_TIM7_CLK_SLEEP_DISABLE() CLEAR_BIT(RCC->APB1SMENR1, RCC_APB1SMENR1_TIM7SMEN)
2198 #define __HAL_RCC_CRS_CLK_SLEEP_DISABLE() CLEAR_BIT(RCC->APB1SMENR1, RCC_APB1SMENR1_CRSSMEN)
2200 #define __HAL_RCC_RTCAPB_CLK_SLEEP_DISABLE() CLEAR_BIT(RCC->APB1SMENR1, RCC_APB1SMENR1_RTCAPBSMEN)
2202 #define __HAL_RCC_WWDG_CLK_SLEEP_DISABLE() CLEAR_BIT(RCC->APB1SMENR1, RCC_APB1SMENR1_WWDGSMEN)
2204 #define __HAL_RCC_SPI2_CLK_SLEEP_DISABLE() CLEAR_BIT(RCC->APB1SMENR1, RCC_APB1SMENR1_SPI2SMEN)
2206 #define __HAL_RCC_SPI3_CLK_SLEEP_DISABLE() CLEAR_BIT(RCC->APB1SMENR1, RCC_APB1SMENR1_SPI3SMEN)
2208 #define __HAL_RCC_USART2_CLK_SLEEP_DISABLE() CLEAR_BIT(RCC->APB1SMENR1, RCC_APB1SMENR1_USART2SMEN)
2210 #define __HAL_RCC_USART3_CLK_SLEEP_DISABLE() CLEAR_BIT(RCC->APB1SMENR1, RCC_APB1SMENR1_USART3SMEN)
2212 #if defined(UART4)
2213 #define __HAL_RCC_UART4_CLK_SLEEP_DISABLE() CLEAR_BIT(RCC->APB1SMENR1, RCC_APB1SMENR1_UART4SMEN)
2214 #endif /* UART4 */
2216 #if defined(UART5)
2217 #define __HAL_RCC_UART5_CLK_SLEEP_DISABLE() CLEAR_BIT(RCC->APB1SMENR1, RCC_APB1SMENR1_UART5SMEN)
2218 #endif /* UART5 */
2220 #define __HAL_RCC_I2C1_CLK_SLEEP_DISABLE() CLEAR_BIT(RCC->APB1SMENR1, RCC_APB1SMENR1_I2C1SMEN)
2222 #define __HAL_RCC_I2C2_CLK_SLEEP_DISABLE() CLEAR_BIT(RCC->APB1SMENR1, RCC_APB1SMENR1_I2C2SMEN)
2224 #if defined(USB)
2225 #define __HAL_RCC_USB_CLK_SLEEP_DISABLE() CLEAR_BIT(RCC->APB1SMENR1, RCC_APB1SMENR1_USBSMEN)
2226 #endif /* USB */
2228 #if defined(FDCAN1)
2229 #define __HAL_RCC_FDCAN_CLK_SLEEP_DISABLE() CLEAR_BIT(RCC->APB1SMENR1, RCC_APB1SMENR1_FDCANSMEN)
2230 #endif /* FDCAN1 */
2232 #define __HAL_RCC_PWR_CLK_SLEEP_DISABLE() CLEAR_BIT(RCC->APB1SMENR1, RCC_APB1SMENR1_PWRSMEN)
2234 #define __HAL_RCC_I2C3_CLK_SLEEP_DISABLE() CLEAR_BIT(RCC->APB1SMENR1, RCC_APB1SMENR1_I2C3SMEN)
2236 #define __HAL_RCC_LPTIM1_CLK_SLEEP_DISABLE() CLEAR_BIT(RCC->APB1SMENR1, RCC_APB1SMENR1_LPTIM1SMEN)
2238 #define __HAL_RCC_LPUART1_CLK_SLEEP_DISABLE() CLEAR_BIT(RCC->APB1SMENR2, RCC_APB1SMENR2_LPUART1SMEN)
2240 #if defined(I2C4)
2241 #define __HAL_RCC_I2C4_CLK_SLEEP_DISABLE() CLEAR_BIT(RCC->APB1SMENR2, RCC_APB1SMENR2_I2C4SMEN)
2242 #endif /* I2C4 */
2244 #define __HAL_RCC_UCPD1_CLK_SLEEP_DISABLE() CLEAR_BIT(RCC->APB1SMENR2, RCC_APB1SMENR2_UCPD1SMEN)
2247 * @}
2250 /** @defgroup RCC_APB2_Clock_Sleep_Enable_Disable APB2 Peripheral Clock Sleep Enable Disable
2251 * @brief Enable or disable the APB2 peripheral clock during Low Power (Sleep) mode.
2252 * @note Peripheral clock gating in SLEEP mode can be used to further reduce
2253 * power consumption.
2254 * @note After wakeup from SLEEP mode, the peripheral clock is enabled again.
2255 * @note By default, all peripheral clocks are enabled during SLEEP mode.
2256 * @{
2259 #define __HAL_RCC_SYSCFG_CLK_SLEEP_ENABLE() SET_BIT(RCC->APB2SMENR, RCC_APB2SMENR_SYSCFGSMEN)
2261 #define __HAL_RCC_TIM1_CLK_SLEEP_ENABLE() SET_BIT(RCC->APB2SMENR, RCC_APB2SMENR_TIM1SMEN)
2263 #define __HAL_RCC_SPI1_CLK_SLEEP_ENABLE() SET_BIT(RCC->APB2SMENR, RCC_APB2SMENR_SPI1SMEN)
2265 #define __HAL_RCC_TIM8_CLK_SLEEP_ENABLE() SET_BIT(RCC->APB2SMENR, RCC_APB2SMENR_TIM8SMEN)
2267 #define __HAL_RCC_USART1_CLK_SLEEP_ENABLE() SET_BIT(RCC->APB2SMENR, RCC_APB2SMENR_USART1SMEN)
2269 #if defined(SPI4)
2270 #define __HAL_RCC_SPI4_CLK_SLEEP_ENABLE() SET_BIT(RCC->APB2SMENR, RCC_APB2SMENR_SPI4SMEN)
2271 #endif /* SPI4 */
2273 #define __HAL_RCC_TIM15_CLK_SLEEP_ENABLE() SET_BIT(RCC->APB2SMENR, RCC_APB2SMENR_TIM15SMEN)
2275 #define __HAL_RCC_TIM16_CLK_SLEEP_ENABLE() SET_BIT(RCC->APB2SMENR, RCC_APB2SMENR_TIM16SMEN)
2277 #define __HAL_RCC_TIM17_CLK_SLEEP_ENABLE() SET_BIT(RCC->APB2SMENR, RCC_APB2SMENR_TIM17SMEN)
2279 #if defined(TIM20)
2280 #define __HAL_RCC_TIM20_CLK_SLEEP_ENABLE() SET_BIT(RCC->APB2SMENR, RCC_APB2SMENR_TIM20SMEN)
2281 #endif /* TIM20 */
2283 #define __HAL_RCC_SAI1_CLK_SLEEP_ENABLE() SET_BIT(RCC->APB2SMENR, RCC_APB2SMENR_SAI1SMEN)
2285 #if defined(HRTIM1)
2286 #define __HAL_RCC_HRTIM1_CLK_SLEEP_ENABLE() SET_BIT(RCC->APB2SMENR, RCC_APB2SMENR_HRTIM1SMEN)
2287 #endif /* HRTIM1 */
2290 #define __HAL_RCC_SYSCFG_CLK_SLEEP_DISABLE() CLEAR_BIT(RCC->APB2SMENR, RCC_APB2SMENR_SYSCFGSMEN)
2292 #define __HAL_RCC_TIM1_CLK_SLEEP_DISABLE() CLEAR_BIT(RCC->APB2SMENR, RCC_APB2SMENR_TIM1SMEN)
2294 #define __HAL_RCC_SPI1_CLK_SLEEP_DISABLE() CLEAR_BIT(RCC->APB2SMENR, RCC_APB2SMENR_SPI1SMEN)
2296 #define __HAL_RCC_TIM8_CLK_SLEEP_DISABLE() CLEAR_BIT(RCC->APB2SMENR, RCC_APB2SMENR_TIM8SMEN)
2298 #define __HAL_RCC_USART1_CLK_SLEEP_DISABLE() CLEAR_BIT(RCC->APB2SMENR, RCC_APB2SMENR_USART1SMEN)
2300 #if defined(SPI4)
2301 #define __HAL_RCC_SPI4_CLK_SLEEP_DISABLE() CLEAR_BIT(RCC->APB2SMENR, RCC_APB2SMENR_SPI4SMEN)
2302 #endif /* SPI4 */
2304 #define __HAL_RCC_TIM15_CLK_SLEEP_DISABLE() CLEAR_BIT(RCC->APB2SMENR, RCC_APB2SMENR_TIM15SMEN)
2306 #define __HAL_RCC_TIM16_CLK_SLEEP_DISABLE() CLEAR_BIT(RCC->APB2SMENR, RCC_APB2SMENR_TIM16SMEN)
2308 #define __HAL_RCC_TIM17_CLK_SLEEP_DISABLE() CLEAR_BIT(RCC->APB2SMENR, RCC_APB2SMENR_TIM17SMEN)
2310 #if defined(TIM20)
2311 #define __HAL_RCC_TIM20_CLK_SLEEP_DISABLE() CLEAR_BIT(RCC->APB2SMENR, RCC_APB2SMENR_TIM20SMEN)
2312 #endif /* TIM20 */
2314 #define __HAL_RCC_SAI1_CLK_SLEEP_DISABLE() CLEAR_BIT(RCC->APB2SMENR, RCC_APB2SMENR_SAI1SMEN)
2316 #if defined(HRTIM1)
2317 #define __HAL_RCC_HRTIM1_CLK_SLEEP_DISABLE() CLEAR_BIT(RCC->APB2SMENR, RCC_APB2SMENR_HRTIM1SMEN)
2318 #endif /* HRTIM1 */
2321 * @}
2324 /** @defgroup RCC_AHB1_Clock_Sleep_Enable_Disable_Status AHB1 Peripheral Clock Sleep Enabled or Disabled Status
2325 * @brief Check whether the AHB1 peripheral clock during Low Power (Sleep) mode is enabled or not.
2326 * @note Peripheral clock gating in SLEEP mode can be used to further reduce
2327 * power consumption.
2328 * @note After wakeup from SLEEP mode, the peripheral clock is enabled again.
2329 * @note By default, all peripheral clocks are enabled during SLEEP mode.
2330 * @{
2333 #define __HAL_RCC_DMA1_IS_CLK_SLEEP_ENABLED() (READ_BIT(RCC->AHB1SMENR, RCC_AHB1SMENR_DMA1SMEN) != 0U)
2335 #define __HAL_RCC_DMA2_IS_CLK_SLEEP_ENABLED() (READ_BIT(RCC->AHB1SMENR, RCC_AHB1SMENR_DMA2SMEN) != 0U)
2337 #define __HAL_RCC_DMAMUX1_IS_CLK_SLEEP_ENABLED() (READ_BIT(RCC->AHB1SMENR, RCC_AHB1SMENR_DMAMUX1SMEN) != 0U)
2339 #define __HAL_RCC_CORDIC_IS_CLK_SLEEP_ENABLED() (READ_BIT(RCC->AHB1SMENR, RCC_AHB1SMENR_CORDICSMEN) != 0U)
2341 #define __HAL_RCC_FMAC_IS_CLK_SLEEP_ENABLED() (READ_BIT(RCC->AHB1SMENR, RCC_AHB1SMENR_FMACSMEN) != 0U)
2343 #define __HAL_RCC_FLASH_IS_CLK_SLEEP_ENABLED() (READ_BIT(RCC->AHB1SMENR, RCC_AHB1SMENR_FLASHSMEN) != 0U)
2345 #define __HAL_RCC_SRAM1_IS_CLK_SLEEP_ENABLED() (READ_BIT(RCC->AHB1SMENR, RCC_AHB1SMENR_SRAM1SMEN) != 0U)
2347 #define __HAL_RCC_CRC_IS_CLK_SLEEP_ENABLED() (READ_BIT(RCC->AHB1SMENR, RCC_AHB1SMENR_CRCSMEN) != 0U)
2350 #define __HAL_RCC_DMA1_IS_CLK_SLEEP_DISABLED() (READ_BIT(RCC->AHB1SMENR, RCC_AHB1SMENR_DMA1SMEN) == 0U)
2352 #define __HAL_RCC_DMA2_IS_CLK_SLEEP_DISABLED() (READ_BIT(RCC->AHB1SMENR, RCC_AHB1SMENR_DMA2SMEN) == 0U)
2354 #define __HAL_RCC_DMAMUX1_IS_CLK_SLEEP_DISABLED() (READ_BIT(RCC->AHB1SMENR, RCC_AHB1SMENR_DMAMUX1SMEN) == 0U)
2356 #define __HAL_RCC_CORDIC_IS_CLK_SLEEP_DISABLED() (READ_BIT(RCC->AHB1SMENR, RCC_AHB1SMENR_CORDICSMEN) == 0U)
2358 #define __HAL_RCC_FMAC_IS_CLK_SLEEP_DISABLED() (READ_BIT(RCC->AHB1SMENR, RCC_AHB1SMENR_FMACSMEN) == 0U)
2360 #define __HAL_RCC_FLASH_IS_CLK_SLEEP_DISABLED() (READ_BIT(RCC->AHB1SMENR, RCC_AHB1SMENR_FLASHSMEN) == 0U)
2362 #define __HAL_RCC_SRAM1_IS_CLK_SLEEP_DISABLED() (READ_BIT(RCC->AHB1SMENR, RCC_AHB1SMENR_SRAM1SMEN) == 0U)
2364 #define __HAL_RCC_CRC_IS_CLK_SLEEP_DISABLED() (READ_BIT(RCC->AHB1SMENR, RCC_AHB1SMENR_CRCSMEN) == 0U)
2367 * @}
2370 /** @defgroup RCC_AHB2_Clock_Sleep_Enable_Disable_Status AHB2 Peripheral Clock Sleep Enabled or Disabled Status
2371 * @brief Check whether the AHB2 peripheral clock during Low Power (Sleep) mode is enabled or not.
2372 * @note Peripheral clock gating in SLEEP mode can be used to further reduce
2373 * power consumption.
2374 * @note After wakeup from SLEEP mode, the peripheral clock is enabled again.
2375 * @note By default, all peripheral clocks are enabled during SLEEP mode.
2376 * @{
2379 #define __HAL_RCC_GPIOA_IS_CLK_SLEEP_ENABLED() (READ_BIT(RCC->AHB2SMENR, RCC_AHB2SMENR_GPIOASMEN) != 0U)
2381 #define __HAL_RCC_GPIOB_IS_CLK_SLEEP_ENABLED() (READ_BIT(RCC->AHB2SMENR, RCC_AHB2SMENR_GPIOBSMEN) != 0U)
2383 #define __HAL_RCC_GPIOC_IS_CLK_SLEEP_ENABLED() (READ_BIT(RCC->AHB2SMENR, RCC_AHB2SMENR_GPIOCSMEN) != 0U)
2385 #define __HAL_RCC_GPIOD_IS_CLK_SLEEP_ENABLED() (READ_BIT(RCC->AHB2SMENR, RCC_AHB2SMENR_GPIODSMEN) != 0U)
2387 #define __HAL_RCC_GPIOE_IS_CLK_SLEEP_ENABLED() (READ_BIT(RCC->AHB2SMENR, RCC_AHB2SMENR_GPIOESMEN) != 0U)
2389 #define __HAL_RCC_GPIOF_IS_CLK_SLEEP_ENABLED() (READ_BIT(RCC->AHB2SMENR, RCC_AHB2SMENR_GPIOFSMEN) != 0U)
2391 #define __HAL_RCC_GPIOG_IS_CLK_SLEEP_ENABLED() (READ_BIT(RCC->AHB2SMENR, RCC_AHB2SMENR_GPIOGSMEN) != 0U)
2393 #define __HAL_RCC_SRAM2_IS_CLK_SLEEP_ENABLED() (READ_BIT(RCC->AHB2SMENR, RCC_AHB2SMENR_SRAM2SMEN) != 0U)
2395 #define __HAL_RCC_CCM_IS_CLK_SLEEP_ENABLED() (READ_BIT(RCC->AHB2SMENR, RCC_AHB2SMENR_CCMSRAMSMEN) != 0U)
2397 #define __HAL_RCC_ADC12_IS_CLK_SLEEP_ENABLED() (READ_BIT(RCC->AHB2SMENR, RCC_AHB2SMENR_ADC12SMEN) != 0U)
2399 #if defined(ADC345_COMMON)
2400 #define __HAL_RCC_ADC345_IS_CLK_SLEEP_ENABLED() (READ_BIT(RCC->AHB2SMENR, RCC_AHB2SMENR_ADC345SMEN) != 0U)
2401 #endif /* ADC345_COMMON */
2403 #define __HAL_RCC_DAC1_IS_CLK_SLEEP_ENABLED() (READ_BIT(RCC->AHB2SMENR, RCC_AHB2SMENR_DAC1SMEN) != 0U)
2405 #if defined(DAC2)
2406 #define __HAL_RCC_DAC2_IS_CLK_SLEEP_ENABLED() (READ_BIT(RCC->AHB2SMENR, RCC_AHB2SMENR_DAC2SMEN) != 0U)
2407 #endif /* DAC2 */
2409 #define __HAL_RCC_DAC3_IS_CLK_SLEEP_ENABLED() (READ_BIT(RCC->AHB2SMENR, RCC_AHB2SMENR_DAC3SMEN) != 0U)
2411 #if defined(DAC4)
2412 #define __HAL_RCC_DAC4_IS_CLK_SLEEP_ENABLED() (READ_BIT(RCC->AHB2SMENR, RCC_AHB2SMENR_DAC4SMEN) != 0U)
2413 #endif /* DAC4 */
2415 #if defined(AES)
2416 #define __HAL_RCC_AES_IS_CLK_SLEEP_ENABLED() (READ_BIT(RCC->AHB2SMENR, RCC_AHB2SMENR_AESSMEN) != 0U)
2417 #endif /* AES */
2419 #define __HAL_RCC_RNG_IS_CLK_SLEEP_ENABLED() (READ_BIT(RCC->AHB2SMENR, RCC_AHB2SMENR_RNGSMEN) != 0U)
2422 #define __HAL_RCC_GPIOA_IS_CLK_SLEEP_DISABLED() (READ_BIT(RCC->AHB2SMENR, RCC_AHB2SMENR_GPIOASMEN) == 0U)
2424 #define __HAL_RCC_GPIOB_IS_CLK_SLEEP_DISABLED() (READ_BIT(RCC->AHB2SMENR, RCC_AHB2SMENR_GPIOBSMEN) == 0U)
2426 #define __HAL_RCC_GPIOC_IS_CLK_SLEEP_DISABLED() (READ_BIT(RCC->AHB2SMENR, RCC_AHB2SMENR_GPIOCSMEN) == 0U)
2428 #define __HAL_RCC_GPIOD_IS_CLK_SLEEP_DISABLED() (READ_BIT(RCC->AHB2SMENR, RCC_AHB2SMENR_GPIODSMEN) == 0U)
2430 #define __HAL_RCC_GPIOE_IS_CLK_SLEEP_DISABLED() (READ_BIT(RCC->AHB2SMENR, RCC_AHB2SMENR_GPIOESMEN) == 0U)
2432 #define __HAL_RCC_GPIOF_IS_CLK_SLEEP_DISABLED() (READ_BIT(RCC->AHB2SMENR, RCC_AHB2SMENR_GPIOFSMEN) == 0U)
2434 #define __HAL_RCC_GPIOG_IS_CLK_SLEEP_DISABLED() (READ_BIT(RCC->AHB2SMENR, RCC_AHB2SMENR_GPIOGSMEN) == 0U)
2436 #define __HAL_RCC_SRAM2_IS_CLK_SLEEP_DISABLED() (READ_BIT(RCC->AHB2SMENR, RCC_AHB2SMENR_SRAM2SMEN) == 0U)
2438 #define __HAL_RCC_CCM_IS_CLK_SLEEP_DISABLED() (READ_BIT(RCC->AHB2SMENR, RCC_AHB2SMENR_CCMSRAMSMEN) == 0U)
2440 #define __HAL_RCC_ADC12_IS_CLK_SLEEP_DISABLED() (READ_BIT(RCC->AHB2SMENR, RCC_AHB2SMENR_ADC12SMEN) == 0U)
2442 #if defined(ADC345_COMMON)
2443 #define __HAL_RCC_ADC345_IS_CLK_SLEEP_DISABLED() (READ_BIT(RCC->AHB2SMENR, RCC_AHB2SMENR_ADC345SMEN) == 0U)
2444 #endif /* ADC345_COMMON */
2446 #define __HAL_RCC_DAC1_IS_CLK_SLEEP_DISABLED() (READ_BIT(RCC->AHB2SMENR, RCC_AHB2SMENR_DAC1SMEN) == 0U)
2448 #if defined(DAC2)
2449 #define __HAL_RCC_DAC2_IS_CLK_SLEEP_DISABLED() (READ_BIT(RCC->AHB2SMENR, RCC_AHB2SMENR_DAC2SMEN) == 0U)
2450 #endif /* DAC2 */
2452 #define __HAL_RCC_DAC3_IS_CLK_SLEEP_DISABLED() (READ_BIT(RCC->AHB2SMENR, RCC_AHB2SMENR_DAC3SMEN) == 0U)
2454 #if defined(DAC4)
2455 #define __HAL_RCC_DAC4_IS_CLK_SLEEP_DISABLED() (READ_BIT(RCC->AHB2SMENR, RCC_AHB2SMENR_DAC4SMEN) == 0U)
2456 #endif /* DAC4 */
2458 #if defined(AES)
2459 #define __HAL_RCC_AES_IS_CLK_SLEEP_DISABLED() (READ_BIT(RCC->AHB2SMENR, RCC_AHB2SMENR_AESSMEN) == 0U)
2460 #endif /* AES */
2462 #define __HAL_RCC_RNG_IS_CLK_SLEEP_DISABLED() (READ_BIT(RCC->AHB2SMENR, RCC_AHB2SMENR_RNGSMEN) == 0U)
2465 * @}
2468 /** @defgroup RCC_AHB3_Clock_Sleep_Enable_Disable_Status AHB3 Peripheral Clock Sleep Enabled or Disabled Status
2469 * @brief Check whether the AHB3 peripheral clock during Low Power (Sleep) mode is enabled or not.
2470 * @note Peripheral clock gating in SLEEP mode can be used to further reduce
2471 * power consumption.
2472 * @note After wakeup from SLEEP mode, the peripheral clock is enabled again.
2473 * @note By default, all peripheral clocks are enabled during SLEEP mode.
2474 * @{
2477 #if defined(FMC_BANK1)
2478 #define __HAL_RCC_FMC_IS_CLK_SLEEP_ENABLED() (READ_BIT(RCC->AHB3SMENR, RCC_AHB3SMENR_FMCSMEN) != 0U)
2479 #endif /* FMC_BANK1 */
2481 #if defined(QUADSPI)
2482 #define __HAL_RCC_QSPI_IS_CLK_SLEEP_ENABLED() (READ_BIT(RCC->AHB3SMENR, RCC_AHB3SMENR_QSPISMEN) != 0U)
2483 #endif /* QUADSPI */
2485 #if defined(FMC_BANK1)
2486 #define __HAL_RCC_FMC_IS_CLK_SLEEP_DISABLED() (READ_BIT(RCC->AHB3SMENR, RCC_AHB3SMENR_FMCSMEN) == 0U)
2487 #endif /* FMC_BANK1 */
2489 #if defined(QUADSPI)
2490 #define __HAL_RCC_QSPI_IS_CLK_SLEEP_DISABLED() (READ_BIT(RCC->AHB3SMENR, RCC_AHB3SMENR_QSPISMEN) == 0U)
2491 #endif /* QUADSPI */
2494 * @}
2497 /** @defgroup RCC_APB1_Clock_Sleep_Enable_Disable_Status APB1 Peripheral Clock Sleep Enabled or Disabled Status
2498 * @brief Check whether the APB1 peripheral clock during Low Power (Sleep) mode is enabled or not.
2499 * @note Peripheral clock gating in SLEEP mode can be used to further reduce
2500 * power consumption.
2501 * @note After wakeup from SLEEP mode, the peripheral clock is enabled again.
2502 * @note By default, all peripheral clocks are enabled during SLEEP mode.
2503 * @{
2506 #define __HAL_RCC_TIM2_IS_CLK_SLEEP_ENABLED() (READ_BIT(RCC->APB1SMENR1, RCC_APB1SMENR1_TIM2SMEN) != 0U)
2508 #define __HAL_RCC_TIM3_IS_CLK_SLEEP_ENABLED() (READ_BIT(RCC->APB1SMENR1, RCC_APB1SMENR1_TIM3SMEN) != 0U)
2510 #define __HAL_RCC_TIM4_IS_CLK_SLEEP_ENABLED() (READ_BIT(RCC->APB1SMENR1, RCC_APB1SMENR1_TIM4SMEN) != 0U)
2512 #if defined(TIM5)
2513 #define __HAL_RCC_TIM5_IS_CLK_SLEEP_ENABLED() (READ_BIT(RCC->APB1SMENR1, RCC_APB1SMENR1_TIM5SMEN) != 0U)
2514 #endif /* TIM5 */
2516 #define __HAL_RCC_TIM6_IS_CLK_SLEEP_ENABLED() (READ_BIT(RCC->APB1SMENR1, RCC_APB1SMENR1_TIM6SMEN) != 0U)
2518 #define __HAL_RCC_TIM7_IS_CLK_SLEEP_ENABLED() (READ_BIT(RCC->APB1SMENR1, RCC_APB1SMENR1_TIM7SMEN) != 0U)
2520 #define __HAL_RCC_CRS_IS_CLK_SLEEP_ENABLED() (READ_BIT(RCC->APB1SMENR1, RCC_APB1SMENR1_CRSSMEN) != 0U)
2522 #define __HAL_RCC_RTCAPB_IS_CLK_SLEEP_ENABLED() (READ_BIT(RCC->APB1SMENR1, RCC_APB1SMENR1_RTCAPBSMEN) != 0U)
2524 #define __HAL_RCC_WWDG_IS_CLK_SLEEP_ENABLED() (READ_BIT(RCC->APB1SMENR1, RCC_APB1SMENR1_WWDGSMEN) != 0U)
2526 #define __HAL_RCC_SPI2_IS_CLK_SLEEP_ENABLED() (READ_BIT(RCC->APB1SMENR1, RCC_APB1SMENR1_SPI2SMEN) != 0U)
2528 #define __HAL_RCC_SPI3_IS_CLK_SLEEP_ENABLED() (READ_BIT(RCC->APB1SMENR1, RCC_APB1SMENR1_SPI3SMEN) != 0U)
2530 #define __HAL_RCC_USART2_IS_CLK_SLEEP_ENABLED() (READ_BIT(RCC->APB1SMENR1, RCC_APB1SMENR1_USART2SMEN) != 0U)
2532 #define __HAL_RCC_USART3_IS_CLK_SLEEP_ENABLED() (READ_BIT(RCC->APB1SMENR1, RCC_APB1SMENR1_USART3SMEN) != 0U)
2534 #if defined(UART4)
2535 #define __HAL_RCC_UART4_IS_CLK_SLEEP_ENABLED() (READ_BIT(RCC->APB1SMENR1, RCC_APB1SMENR1_UART4SMEN) != 0U)
2536 #endif /* UART4 */
2538 #if defined(UART5)
2539 #define __HAL_RCC_UART5_IS_CLK_SLEEP_ENABLED() (READ_BIT(RCC->APB1SMENR1, RCC_APB1SMENR1_UART5SMEN) != 0U)
2540 #endif /* UART5 */
2542 #define __HAL_RCC_I2C1_IS_CLK_SLEEP_ENABLED() (READ_BIT(RCC->APB1SMENR1, RCC_APB1SMENR1_I2C1SMEN) != 0U)
2544 #define __HAL_RCC_I2C2_IS_CLK_SLEEP_ENABLED() (READ_BIT(RCC->APB1SMENR1, RCC_APB1SMENR1_I2C2SMEN) != 0U)
2546 #define __HAL_RCC_USB_IS_CLK_SLEEP_ENABLED() (READ_BIT(RCC->APB1SMENR1, RCC_APB1SMENR1_USBSMEN) != 0U)
2548 #if defined(FDCAN1)
2549 #define __HAL_RCC_FDCAN_IS_CLK_SLEEP_ENABLED() (READ_BIT(RCC->APB1SMENR1, RCC_APB1SMENR1_FDCANSMEN) != 0U)
2550 #endif /* FDCAN1 */
2552 #define __HAL_RCC_PWR_IS_CLK_SLEEP_ENABLED() (READ_BIT(RCC->APB1SMENR1, RCC_APB1SMENR1_PWRSMEN) != 0U)
2554 #define __HAL_RCC_I2C3_IS_CLK_SLEEP_ENABLED() (READ_BIT(RCC->APB1SMENR1, RCC_APB1SMENR1_I2C3SMEN) != 0U)
2556 #define __HAL_RCC_LPTIM1_IS_CLK_SLEEP_ENABLED() (READ_BIT(RCC->APB1SMENR1, RCC_APB1SMENR1_LPTIM1SMEN) != 0U)
2558 #define __HAL_RCC_LPUART1_IS_CLK_SLEEP_ENABLED() (READ_BIT(RCC->APB1SMENR2, RCC_APB1SMENR2_LPUART1SMEN) != 0U)
2560 #if defined(I2C4)
2561 #define __HAL_RCC_I2C4_IS_CLK_SLEEP_ENABLED() (READ_BIT(RCC->APB1SMENR2, RCC_APB1SMENR2_I2C4SMEN) != 0U)
2562 #endif /* I2C4 */
2564 #define __HAL_RCC_UCPD1_IS_CLK_SLEEP_ENABLED() (READ_BIT(RCC->APB1SMENR2, RCC_APB1SMENR2_UCPD1SMEN) != 0U)
2567 #define __HAL_RCC_TIM2_IS_CLK_SLEEP_DISABLED() (READ_BIT(RCC->APB1SMENR1, RCC_APB1SMENR1_TIM2SMEN) == 0U)
2569 #define __HAL_RCC_TIM3_IS_CLK_SLEEP_DISABLED() (READ_BIT(RCC->APB1SMENR1, RCC_APB1SMENR1_TIM3SMEN) == 0U)
2571 #define __HAL_RCC_TIM4_IS_CLK_SLEEP_DISABLED() (READ_BIT(RCC->APB1SMENR1, RCC_APB1SMENR1_TIM4SMEN) == 0U)
2573 #if defined(TIM5)
2574 #define __HAL_RCC_TIM5_IS_CLK_SLEEP_DISABLED() (READ_BIT(RCC->APB1SMENR1, RCC_APB1SMENR1_TIM5SMEN) == 0U)
2575 #endif /* TIM5 */
2577 #define __HAL_RCC_TIM6_IS_CLK_SLEEP_DISABLED() (READ_BIT(RCC->APB1SMENR1, RCC_APB1SMENR1_TIM6SMEN) == 0U)
2579 #define __HAL_RCC_TIM7_IS_CLK_SLEEP_DISABLED() (READ_BIT(RCC->APB1SMENR1, RCC_APB1SMENR1_TIM7SMEN) == 0U)
2581 #define __HAL_RCC_CRS_IS_CLK_SLEEP_DISABLED() (READ_BIT(RCC->APB1SMENR1, RCC_APB1SMENR1_CRSSMEN) == 0U)
2583 #define __HAL_RCC_RTCAPB_IS_CLK_SLEEP_DISABLED() (READ_BIT(RCC->APB1SMENR1, RCC_APB1SMENR1_RTCAPBSMEN) == 0U)
2585 #define __HAL_RCC_WWDG_IS_CLK_SLEEP_DISABLED() (READ_BIT(RCC->APB1SMENR1, RCC_APB1SMENR1_WWDGSMEN) == 0U)
2587 #define __HAL_RCC_SPI2_IS_CLK_SLEEP_DISABLED() (READ_BIT(RCC->APB1SMENR1, RCC_APB1SMENR1_SPI2SMEN) == 0U)
2589 #define __HAL_RCC_SPI3_IS_CLK_SLEEP_DISABLED() (READ_BIT(RCC->APB1SMENR1, RCC_APB1SMENR1_SPI3SMEN) == 0U)
2591 #define __HAL_RCC_USART2_IS_CLK_SLEEP_DISABLED() (READ_BIT(RCC->APB1SMENR1, RCC_APB1SMENR1_USART2SMEN) == 0U)
2593 #define __HAL_RCC_USART3_IS_CLK_SLEEP_DISABLED() (READ_BIT(RCC->APB1SMENR1, RCC_APB1SMENR1_USART3SMEN) == 0U)
2595 #if defined(UART4)
2596 #define __HAL_RCC_UART4_IS_CLK_SLEEP_DISABLED() (READ_BIT(RCC->APB1SMENR1, RCC_APB1SMENR1_UART4SMEN) == 0U)
2597 #endif /* UART4 */
2599 #if defined(UART5)
2600 #define __HAL_RCC_UART5_IS_CLK_SLEEP_DISABLED() (READ_BIT(RCC->APB1SMENR1, RCC_APB1SMENR1_UART5SMEN) == 0U)
2601 #endif /* UART5 */
2603 #define __HAL_RCC_I2C1_IS_CLK_SLEEP_DISABLED() (READ_BIT(RCC->APB1SMENR1, RCC_APB1SMENR1_I2C1SMEN) == 0U)
2605 #define __HAL_RCC_I2C2_IS_CLK_SLEEP_DISABLED() (READ_BIT(RCC->APB1SMENR1, RCC_APB1SMENR1_I2C2SMEN) == 0U)
2607 #define __HAL_RCC_USB_IS_CLK_SLEEP_DISABLED() (READ_BIT(RCC->APB1SMENR1, RCC_APB1SMENR1_USBSMEN) == 0U)
2609 #if defined(FDCAN1)
2610 #define __HAL_RCC_FDCAN_IS_CLK_SLEEP_DISABLED() (READ_BIT(RCC->APB1SMENR1, RCC_APB1SMENR1_FDCANSMEN) == 0U)
2611 #endif /* FDCAN1 */
2613 #define __HAL_RCC_PWR_IS_CLK_SLEEP_DISABLED() (READ_BIT(RCC->APB1SMENR1, RCC_APB1SMENR1_PWRSMEN) == 0U)
2615 #define __HAL_RCC_I2C3_IS_CLK_SLEEP_DISABLED() (READ_BIT(RCC->APB1SMENR1, RCC_APB1SMENR1_I2C3SMEN) == 0U)
2617 #define __HAL_RCC_LPTIM1_IS_CLK_SLEEP_DISABLED() (READ_BIT(RCC->APB1SMENR1, RCC_APB1SMENR1_LPTIM1SMEN) == 0U)
2619 #define __HAL_RCC_LPUART1_IS_CLK_SLEEP_DISABLED() (READ_BIT(RCC->APB1SMENR2, RCC_APB1SMENR2_LPUART1SMEN) == 0U)
2621 #if defined(I2C4)
2622 #define __HAL_RCC_I2C4_IS_CLK_SLEEP_DISABLED() (READ_BIT(RCC->APB1SMENR2, RCC_APB1SMENR2_I2C4SMEN) == 0U)
2623 #endif /* I2C4 */
2625 #define __HAL_RCC_UCPD1_IS_CLK_SLEEP_DISABLED() (READ_BIT(RCC->APB1SMENR2, RCC_APB1SMENR2_UCPD1SMEN) == 0U)
2628 * @}
2631 /** @defgroup RCC_APB2_Clock_Sleep_Enable_Disable_Status APB2 Peripheral Clock Sleep Enabled or Disabled Status
2632 * @brief Check whether the APB2 peripheral clock during Low Power (Sleep) mode is enabled or not.
2633 * @note Peripheral clock gating in SLEEP mode can be used to further reduce
2634 * power consumption.
2635 * @note After wakeup from SLEEP mode, the peripheral clock is enabled again.
2636 * @note By default, all peripheral clocks are enabled during SLEEP mode.
2637 * @{
2640 #define __HAL_RCC_SYSCFG_IS_CLK_SLEEP_ENABLED() (READ_BIT(RCC->APB2SMENR, RCC_APB2SMENR_SYSCFGSMEN) != 0U)
2642 #define __HAL_RCC_TIM1_IS_CLK_SLEEP_ENABLED() (READ_BIT(RCC->APB2SMENR, RCC_APB2SMENR_TIM1SMEN) != 0U)
2644 #define __HAL_RCC_SPI1_IS_CLK_SLEEP_ENABLED() (READ_BIT(RCC->APB2SMENR, RCC_APB2SMENR_SPI1SMEN) != 0U)
2646 #define __HAL_RCC_TIM8_IS_CLK_SLEEP_ENABLED() (READ_BIT(RCC->APB2SMENR, RCC_APB2SMENR_TIM8SMEN) != 0U)
2648 #define __HAL_RCC_USART1_IS_CLK_SLEEP_ENABLED() (READ_BIT(RCC->APB2SMENR, RCC_APB2SMENR_USART1SMEN) != 0U)
2650 #if defined(SPI4)
2651 #define __HAL_RCC_SPI4_IS_CLK_SLEEP_ENABLED() (READ_BIT(RCC->APB2SMENR, RCC_APB2SMENR_SPI4SMEN) != 0U)
2652 #endif /* SPI4 */
2654 #define __HAL_RCC_TIM15_IS_CLK_SLEEP_ENABLED() (READ_BIT(RCC->APB2SMENR, RCC_APB2SMENR_TIM15SMEN) != 0U)
2656 #define __HAL_RCC_TIM16_IS_CLK_SLEEP_ENABLED() (READ_BIT(RCC->APB2SMENR, RCC_APB2SMENR_TIM16SMEN) != 0U)
2658 #define __HAL_RCC_TIM17_IS_CLK_SLEEP_ENABLED() (READ_BIT(RCC->APB2SMENR, RCC_APB2SMENR_TIM17SMEN) != 0U)
2660 #if defined(TIM20)
2661 #define __HAL_RCC_TIM20_IS_CLK_SLEEP_ENABLED() (READ_BIT(RCC->APB2SMENR, RCC_APB2SMENR_TIM20SMEN) != 0U)
2662 #endif /* TIM20 */
2664 #define __HAL_RCC_SAI1_IS_CLK_SLEEP_ENABLED() (READ_BIT(RCC->APB2SMENR, RCC_APB2SMENR_SAI1SMEN) != 0U)
2666 #if defined(HRTIM1)
2667 #define __HAL_RCC_HRTIM1_IS_CLK_SLEEP_ENABLED() (READ_BIT(RCC->APB2SMENR, RCC_APB2SMENR_HRTIM1SMEN) != 0U)
2668 #endif /* HRTIM1 */
2671 #define __HAL_RCC_SYSCFG_IS_CLK_SLEEP_DISABLED() (READ_BIT(RCC->APB2SMENR, RCC_APB2SMENR_SYSCFGSMEN) == 0U)
2673 #define __HAL_RCC_TIM1_IS_CLK_SLEEP_DISABLED() (READ_BIT(RCC->APB2SMENR, RCC_APB2SMENR_TIM1SMEN) == 0U)
2675 #define __HAL_RCC_SPI1_IS_CLK_SLEEP_DISABLED() (READ_BIT(RCC->APB2SMENR, RCC_APB2SMENR_SPI1SMEN) == 0U)
2677 #define __HAL_RCC_TIM8_IS_CLK_SLEEP_DISABLED() (READ_BIT(RCC->APB2SMENR, RCC_APB2SMENR_TIM8SMEN) == 0U)
2679 #define __HAL_RCC_USART1_IS_CLK_SLEEP_DISABLED() (READ_BIT(RCC->APB2SMENR, RCC_APB2SMENR_USART1SMEN) == 0U)
2681 #if defined(SPI4)
2682 #define __HAL_RCC_SPI4_IS_CLK_SLEEP_DISABLED() (READ_BIT(RCC->APB2SMENR, RCC_APB2SMENR_SPI4SMEN) == 0U)
2683 #endif /* SPI4 */
2685 #define __HAL_RCC_TIM15_IS_CLK_SLEEP_DISABLED() (READ_BIT(RCC->APB2SMENR, RCC_APB2SMENR_TIM15SMEN) == 0U)
2687 #define __HAL_RCC_TIM16_IS_CLK_SLEEP_DISABLED() (READ_BIT(RCC->APB2SMENR, RCC_APB2SMENR_TIM16SMEN) == 0U)
2689 #define __HAL_RCC_TIM17_IS_CLK_SLEEP_DISABLED() (READ_BIT(RCC->APB2SMENR, RCC_APB2SMENR_TIM17SMEN) == 0U)
2691 #if defined(TIM20)
2692 #define __HAL_RCC_TIM20_IS_CLK_SLEEP_DISABLED() (READ_BIT(RCC->APB2SMENR, RCC_APB2SMENR_TIM20SMEN) == 0U)
2693 #endif /* TIM20 */
2695 #define __HAL_RCC_SAI1_IS_CLK_SLEEP_DISABLED() (READ_BIT(RCC->APB2SMENR, RCC_APB2SMENR_SAI1SMEN) == 0U)
2697 #if defined(HRTIM1)
2698 #define __HAL_RCC_HRTIM1_IS_CLK_SLEEP_DISABLED() (READ_BIT(RCC->APB2SMENR, RCC_APB2SMENR_HRTIM1SMEN) == 0U)
2699 #endif /* HRTIM1 */
2703 * @}
2706 /** @defgroup RCC_Backup_Domain_Reset RCC Backup Domain Reset
2707 * @{
2710 /** @brief Macros to force or release the Backup domain reset.
2711 * @note This function resets the RTC peripheral (including the backup registers)
2712 * and the RTC clock source selection in RCC_CSR register.
2713 * @note The BKPSRAM is not affected by this reset.
2714 * @retval None
2716 #define __HAL_RCC_BACKUPRESET_FORCE() SET_BIT(RCC->BDCR, RCC_BDCR_BDRST)
2718 #define __HAL_RCC_BACKUPRESET_RELEASE() CLEAR_BIT(RCC->BDCR, RCC_BDCR_BDRST)
2721 * @}
2724 /** @defgroup RCC_RTC_Clock_Configuration RCC RTC Clock Configuration
2725 * @{
2728 /** @brief Macros to enable or disable the RTC clock.
2729 * @note As the RTC is in the Backup domain and write access is denied to
2730 * this domain after reset, you have to enable write access using
2731 * HAL_PWR_EnableBkUpAccess() function before to configure the RTC
2732 * (to be done once after reset).
2733 * @note These macros must be used after the RTC clock source was selected.
2734 * @retval None
2736 #define __HAL_RCC_RTC_ENABLE() SET_BIT(RCC->BDCR, RCC_BDCR_RTCEN)
2738 #define __HAL_RCC_RTC_DISABLE() CLEAR_BIT(RCC->BDCR, RCC_BDCR_RTCEN)
2741 * @}
2744 /** @brief Macros to enable or disable the Internal High Speed 16MHz oscillator (HSI).
2745 * @note The HSI is stopped by hardware when entering STOP and STANDBY modes.
2746 * It is used (enabled by hardware) as system clock source after startup
2747 * from Reset, wakeup from STOP and STANDBY mode, or in case of failure
2748 * of the HSE used directly or indirectly as system clock (if the Clock
2749 * Security System CSS is enabled).
2750 * @note HSI can not be stopped if it is used as system clock source. In this case,
2751 * you have to select another source of the system clock then stop the HSI.
2752 * @note After enabling the HSI, the application software should wait on HSIRDY
2753 * flag to be set indicating that HSI clock is stable and can be used as
2754 * system clock source.
2755 * This parameter can be: ENABLE or DISABLE.
2756 * @note When the HSI is stopped, HSIRDY flag goes low after 6 HSI oscillator
2757 * clock cycles.
2758 * @retval None
2760 #define __HAL_RCC_HSI_ENABLE() SET_BIT(RCC->CR, RCC_CR_HSION)
2762 #define __HAL_RCC_HSI_DISABLE() CLEAR_BIT(RCC->CR, RCC_CR_HSION)
2764 /** @brief Macro to adjust the Internal High Speed 16MHz oscillator (HSI) calibration value.
2765 * @note The calibration is used to compensate for the variations in voltage
2766 * and temperature that influence the frequency of the internal HSI RC.
2767 * @param __HSICALIBRATIONVALUE__ specifies the calibration trimming value
2768 * (default is RCC_HSICALIBRATION_DEFAULT).
2769 * This parameter must be a number between 0 and 0x7F.
2770 * @retval None
2772 #define __HAL_RCC_HSI_CALIBRATIONVALUE_ADJUST(__HSICALIBRATIONVALUE__) \
2773 MODIFY_REG(RCC->ICSCR, RCC_ICSCR_HSITRIM, (__HSICALIBRATIONVALUE__) << RCC_ICSCR_HSITRIM_Pos)
2776 * @brief Macros to enable or disable the force of the Internal High Speed oscillator (HSI)
2777 * in STOP mode to be quickly available as kernel clock for USARTs and I2Cs.
2778 * @note Keeping the HSI ON in STOP mode allows to avoid slowing down the communication
2779 * speed because of the HSI startup time.
2780 * @note The enable of this function has not effect on the HSION bit.
2781 * This parameter can be: ENABLE or DISABLE.
2782 * @retval None
2784 #define __HAL_RCC_HSISTOP_ENABLE() SET_BIT(RCC->CR, RCC_CR_HSIKERON)
2786 #define __HAL_RCC_HSISTOP_DISABLE() CLEAR_BIT(RCC->CR, RCC_CR_HSIKERON)
2788 /** @brief Macros to enable or disable the Internal Low Speed oscillator (LSI).
2789 * @note After enabling the LSI, the application software should wait on
2790 * LSIRDY flag to be set indicating that LSI clock is stable and can
2791 * be used to clock the IWDG and/or the RTC.
2792 * @note LSI can not be disabled if the IWDG is running.
2793 * @note When the LSI is stopped, LSIRDY flag goes low after 6 LSI oscillator
2794 * clock cycles.
2795 * @retval None
2797 #define __HAL_RCC_LSI_ENABLE() SET_BIT(RCC->CSR, RCC_CSR_LSION)
2799 #define __HAL_RCC_LSI_DISABLE() CLEAR_BIT(RCC->CSR, RCC_CSR_LSION)
2802 * @brief Macro to configure the External High Speed oscillator (HSE).
2803 * @note Transition HSE Bypass to HSE On and HSE On to HSE Bypass are not
2804 * supported by this macro. User should request a transition to HSE Off
2805 * first and then HSE On or HSE Bypass.
2806 * @note After enabling the HSE (RCC_HSE_ON or RCC_HSE_Bypass), the application
2807 * software should wait on HSERDY flag to be set indicating that HSE clock
2808 * is stable and can be used to clock the PLL and/or system clock.
2809 * @note HSE state can not be changed if it is used directly or through the
2810 * PLL as system clock. In this case, you have to select another source
2811 * of the system clock then change the HSE state (ex. disable it).
2812 * @note The HSE is stopped by hardware when entering STOP and STANDBY modes.
2813 * @note This function reset the CSSON bit, so if the clock security system(CSS)
2814 * was previously enabled you have to enable it again after calling this
2815 * function.
2816 * @param __STATE__ specifies the new state of the HSE.
2817 * This parameter can be one of the following values:
2818 * @arg @ref RCC_HSE_OFF Turn OFF the HSE oscillator, HSERDY flag goes low after
2819 * 6 HSE oscillator clock cycles.
2820 * @arg @ref RCC_HSE_ON Turn ON the HSE oscillator.
2821 * @arg @ref RCC_HSE_BYPASS HSE oscillator bypassed with external clock.
2822 * @retval None
2824 #define __HAL_RCC_HSE_CONFIG(__STATE__) \
2825 do { \
2826 if((__STATE__) == RCC_HSE_ON) \
2828 SET_BIT(RCC->CR, RCC_CR_HSEON); \
2830 else if((__STATE__) == RCC_HSE_BYPASS) \
2832 SET_BIT(RCC->CR, RCC_CR_HSEBYP); \
2833 SET_BIT(RCC->CR, RCC_CR_HSEON); \
2835 else \
2837 CLEAR_BIT(RCC->CR, RCC_CR_HSEON); \
2838 CLEAR_BIT(RCC->CR, RCC_CR_HSEBYP); \
2840 } while(0)
2843 * @brief Macro to configure the External Low Speed oscillator (LSE).
2844 * @note Transitions LSE Bypass to LSE On and LSE On to LSE Bypass are not
2845 * supported by this macro. User should request a transition to LSE Off
2846 * first and then LSE On or LSE Bypass.
2847 * @note As the LSE is in the Backup domain and write access is denied to
2848 * this domain after reset, you have to enable write access using
2849 * HAL_PWR_EnableBkUpAccess() function before to configure the LSE
2850 * (to be done once after reset).
2851 * @note After enabling the LSE (RCC_LSE_ON or RCC_LSE_BYPASS), the application
2852 * software should wait on LSERDY flag to be set indicating that LSE clock
2853 * is stable and can be used to clock the RTC.
2854 * @param __STATE__ specifies the new state of the LSE.
2855 * This parameter can be one of the following values:
2856 * @arg @ref RCC_LSE_OFF Turn OFF the LSE oscillator, LSERDY flag goes low after
2857 * 6 LSE oscillator clock cycles.
2858 * @arg @ref RCC_LSE_ON Turn ON the LSE oscillator.
2859 * @arg @ref RCC_LSE_BYPASS LSE oscillator bypassed with external clock.
2860 * @retval None
2862 #define __HAL_RCC_LSE_CONFIG(__STATE__) \
2863 do { \
2864 if((__STATE__) == RCC_LSE_ON) \
2866 SET_BIT(RCC->BDCR, RCC_BDCR_LSEON); \
2868 else if((__STATE__) == RCC_LSE_BYPASS) \
2870 SET_BIT(RCC->BDCR, RCC_BDCR_LSEBYP); \
2871 SET_BIT(RCC->BDCR, RCC_BDCR_LSEON); \
2873 else \
2875 CLEAR_BIT(RCC->BDCR, RCC_BDCR_LSEON); \
2876 CLEAR_BIT(RCC->BDCR, RCC_BDCR_LSEBYP); \
2878 } while(0)
2880 /** @brief Macros to enable or disable the Internal High Speed 48MHz oscillator (HSI48).
2881 * @note The HSI48 is stopped by hardware when entering STOP and STANDBY modes.
2882 * @note After enabling the HSI48, the application software should wait on HSI48RDY
2883 * flag to be set indicating that HSI48 clock is stable.
2884 * This parameter can be: ENABLE or DISABLE.
2885 * @retval None
2887 #define __HAL_RCC_HSI48_ENABLE() SET_BIT(RCC->CRRCR, RCC_CRRCR_HSI48ON)
2889 #define __HAL_RCC_HSI48_DISABLE() CLEAR_BIT(RCC->CRRCR, RCC_CRRCR_HSI48ON)
2891 /** @brief Macros to configure the RTC clock (RTCCLK).
2892 * @note As the RTC clock configuration bits are in the Backup domain and write
2893 * access is denied to this domain after reset, you have to enable write
2894 * access using the Power Backup Access macro before to configure
2895 * the RTC clock source (to be done once after reset).
2896 * @note Once the RTC clock is configured it cannot be changed unless the
2897 * Backup domain is reset using __HAL_RCC_BACKUPRESET_FORCE() macro, or by
2898 * a Power On Reset (POR).
2900 * @param __RTC_CLKSOURCE__ specifies the RTC clock source.
2901 * This parameter can be one of the following values:
2902 * @arg @ref RCC_RTCCLKSOURCE_NONE No clock selected as RTC clock.
2903 * @arg @ref RCC_RTCCLKSOURCE_LSE LSE selected as RTC clock.
2904 * @arg @ref RCC_RTCCLKSOURCE_LSI LSI selected as RTC clock.
2905 * @arg @ref RCC_RTCCLKSOURCE_HSE_DIV32 HSE clock divided by 32 selected
2907 * @note If the LSE or LSI is used as RTC clock source, the RTC continues to
2908 * work in STOP and STANDBY modes, and can be used as wakeup source.
2909 * However, when the HSE clock is used as RTC clock source, the RTC
2910 * cannot be used in STOP and STANDBY modes.
2911 * @note The maximum input clock frequency for RTC is 1MHz (when using HSE as
2912 * RTC clock source).
2913 * @retval None
2915 #define __HAL_RCC_RTC_CONFIG(__RTC_CLKSOURCE__) \
2916 MODIFY_REG( RCC->BDCR, RCC_BDCR_RTCSEL, (__RTC_CLKSOURCE__))
2919 /** @brief Macro to get the RTC clock source.
2920 * @retval The returned value can be one of the following:
2921 * @arg @ref RCC_RTCCLKSOURCE_NONE No clock selected as RTC clock.
2922 * @arg @ref RCC_RTCCLKSOURCE_LSE LSE selected as RTC clock.
2923 * @arg @ref RCC_RTCCLKSOURCE_LSI LSI selected as RTC clock.
2924 * @arg @ref RCC_RTCCLKSOURCE_HSE_DIV32 HSE clock divided by 32 selected
2926 #define __HAL_RCC_GET_RTC_SOURCE() (READ_BIT(RCC->BDCR, RCC_BDCR_RTCSEL))
2928 /** @brief Macros to enable or disable the main PLL.
2929 * @note After enabling the main PLL, the application software should wait on
2930 * PLLRDY flag to be set indicating that PLL clock is stable and can
2931 * be used as system clock source.
2932 * @note The main PLL can not be disabled if it is used as system clock source
2933 * @note The main PLL is disabled by hardware when entering STOP and STANDBY modes.
2934 * @retval None
2936 #define __HAL_RCC_PLL_ENABLE() SET_BIT(RCC->CR, RCC_CR_PLLON)
2938 #define __HAL_RCC_PLL_DISABLE() CLEAR_BIT(RCC->CR, RCC_CR_PLLON)
2940 /** @brief Macro to configure the PLL clock source.
2941 * @note This function must be used only when the main PLL is disabled.
2942 * @param __PLLSOURCE__ specifies the PLL entry clock source.
2943 * This parameter can be one of the following values:
2944 * @arg @ref RCC_PLLSOURCE_NONE No clock selected as PLL clock entry
2945 * @arg @ref RCC_PLLSOURCE_HSI HSI oscillator clock selected as PLL clock entry
2946 * @arg @ref RCC_PLLSOURCE_HSE HSE oscillator clock selected as PLL clock entry
2947 * @retval None
2950 #define __HAL_RCC_PLL_PLLSOURCE_CONFIG(__PLLSOURCE__) \
2951 MODIFY_REG(RCC->PLLCFGR, RCC_PLLCFGR_PLLSRC, (__PLLSOURCE__))
2953 /** @brief Macro to configure the PLL source division factor M.
2954 * @note This function must be used only when the main PLL is disabled.
2955 * @param __PLLM__ specifies the division factor for PLL VCO input clock
2956 * This parameter must be a value of @ref RCC_PLLM_Clock_Divider.
2957 * @note You have to set the PLLM parameter correctly to ensure that the VCO input
2958 * frequency ranges from 2.66 to 8 MHz. It is recommended to select a frequency
2959 * of 8 MHz to limit PLL jitter.
2960 * @retval None
2963 #define __HAL_RCC_PLL_PLLM_CONFIG(__PLLM__) \
2964 MODIFY_REG(RCC->PLLCFGR, RCC_PLLCFGR_PLLM, ((__PLLM__) - 1) << RCC_PLLCFGR_PLLM_Pos)
2967 * @brief Macro to configure the main PLL clock source, multiplication and division factors.
2968 * @note This macro must be used only when the main PLL is disabled.
2969 * @note This macro preserves the PLL's output clocks enable state.
2971 * @param __PLLSOURCE__ specifies the PLL entry clock source.
2972 * This parameter can be one of the following values:
2973 * @arg @ref RCC_PLLSOURCE_NONE No clock selected as PLL clock entry
2974 * @arg @ref RCC_PLLSOURCE_HSI HSI oscillator clock selected as PLL clock entry
2975 * @arg @ref RCC_PLLSOURCE_HSE HSE oscillator clock selected as PLL clock entry
2977 * @param __PLLM__ specifies the division factor for PLL VCO input clock.
2978 * This parameter must be a value of @ref RCC_PLLM_Clock_Divider
2979 * @note You have to set the PLLM parameter correctly to ensure that the VCO input
2980 * frequency ranges from 2.66 to 8 MHz. It is recommended to select a frequency
2981 * of 8 MHz to limit PLL jitter.
2983 * @param __PLLN__ specifies the multiplication factor for PLL VCO output clock.
2984 * This parameter must be a number between 8 and 127.
2985 * @note You have to set the PLLN parameter correctly to ensure that the VCO
2986 * output frequency is between 64 and 344 MHz.
2988 * @param __PLLP__ specifies the division factor for SAI clock.
2989 * This parameter must be a number in the range (2 to 31).
2991 * @param __PLLQ__ specifies the division factor for OTG FS, SDMMC1 and RNG clocks.
2992 * This parameter must be in the range (2, 4, 6 or 8).
2993 * @note If the USB OTG FS is used in your application, you have to set the
2994 * PLLQ parameter correctly to have 48 MHz clock for the USB. However,
2995 * the SDMMC1 and RNG need a frequency lower than or equal to 48 MHz to work
2996 * correctly.
2997 * @param __PLLR__ specifies the division factor for the main system clock.
2998 * @note You have to set the PLLR parameter correctly to not exceed 170MHZ.
2999 * This parameter must be in the range (2, 4, 6 or 8).
3000 * @retval None
3002 #define __HAL_RCC_PLL_CONFIG(__PLLSOURCE__, __PLLM__, __PLLN__, __PLLP__, __PLLQ__,__PLLR__ ) \
3003 MODIFY_REG(RCC->PLLCFGR, \
3004 (RCC_PLLCFGR_PLLSRC | RCC_PLLCFGR_PLLM | RCC_PLLCFGR_PLLN | \
3005 RCC_PLLCFGR_PLLQ | RCC_PLLCFGR_PLLR | RCC_PLLCFGR_PLLPDIV), \
3006 ((__PLLSOURCE__) | \
3007 (((__PLLM__) - 1U) << RCC_PLLCFGR_PLLM_Pos) | \
3008 ((__PLLN__) << RCC_PLLCFGR_PLLN_Pos) | \
3009 ((((__PLLQ__) >> 1U) - 1U) << RCC_PLLCFGR_PLLQ_Pos) | \
3010 ((((__PLLR__) >> 1U) - 1U) << RCC_PLLCFGR_PLLR_Pos) | \
3011 ((__PLLP__) << RCC_PLLCFGR_PLLPDIV_Pos)))
3013 /** @brief Macro to get the oscillator used as PLL clock source.
3014 * @retval The oscillator used as PLL clock source. The returned value can be one
3015 * of the following:
3016 * - RCC_PLLSOURCE_NONE: No oscillator is used as PLL clock source.
3017 * - RCC_PLLSOURCE_HSI: HSI oscillator is used as PLL clock source.
3018 * - RCC_PLLSOURCE_HSE: HSE oscillator is used as PLL clock source.
3020 #define __HAL_RCC_GET_PLL_OSCSOURCE() (READ_BIT(RCC->PLLCFGR, RCC_PLLCFGR_PLLSRC))
3023 * @brief Enable or disable each clock output (RCC_PLL_SYSCLK, RCC_PLL_48M1CLK, RCC_PLL_ADCCLK)
3024 * @note Enabling/disabling clock outputs RCC_PLL_ADCCLK and RCC_PLL_48M1CLK can be done at anytime
3025 * without the need to stop the PLL in order to save power. But RCC_PLL_SYSCLK cannot
3026 * be stopped if used as System Clock.
3027 * @param __PLLCLOCKOUT__ specifies the PLL clock to be output.
3028 * This parameter can be one or a combination of the following values:
3029 * @arg @ref RCC_PLL_ADCCLK This clock is used to generate a clock on ADC.
3030 * @arg @ref RCC_PLL_48M1CLK This Clock is used to generate the clock for the USB (48 MHz),
3031 * FDCAN (<=48 MHz) and QSPI (<=48 MHz).
3032 * @arg @ref RCC_PLL_SYSCLK This Clock is used to generate the high speed system clock (up to 170MHz)
3033 * @retval None
3035 #define __HAL_RCC_PLLCLKOUT_ENABLE(__PLLCLOCKOUT__) SET_BIT(RCC->PLLCFGR, (__PLLCLOCKOUT__))
3037 #define __HAL_RCC_PLLCLKOUT_DISABLE(__PLLCLOCKOUT__) CLEAR_BIT(RCC->PLLCFGR, (__PLLCLOCKOUT__))
3040 * @brief Get clock output enable status (RCC_PLL_SYSCLK, RCC_PLL_48M1CLK, RCC_PLL_SAI3CLK)
3041 * @param __PLLCLOCKOUT__ specifies the output PLL clock to be checked.
3042 * This parameter can be one of the following values:
3043 * @arg @ref RCC_PLL_ADCCLK This clock is used to generate a clock on ADC.
3044 * @arg @ref RCC_PLL_48M1CLK This Clock is used to generate the clock for the USB (48 MHz),
3045 * FDCAN (<=48 MHz) and QSPI (<=48 MHz).
3046 * @arg @ref RCC_PLL_SYSCLK This Clock is used to generate the high speed system clock (up to 170MHz)
3047 * @retval SET / RESET
3049 #define __HAL_RCC_GET_PLLCLKOUT_CONFIG(__PLLCLOCKOUT__) READ_BIT(RCC->PLLCFGR, (__PLLCLOCKOUT__))
3052 * @brief Macro to configure the system clock source.
3053 * @param __SYSCLKSOURCE__ specifies the system clock source.
3054 * This parameter can be one of the following values:
3055 * - RCC_SYSCLKSOURCE_HSI: HSI oscillator is used as system clock source.
3056 * - RCC_SYSCLKSOURCE_HSE: HSE oscillator is used as system clock source.
3057 * - RCC_SYSCLKSOURCE_PLLCLK: PLL output is used as system clock source.
3058 * @retval None
3060 #define __HAL_RCC_SYSCLK_CONFIG(__SYSCLKSOURCE__) \
3061 MODIFY_REG(RCC->CFGR, RCC_CFGR_SW, (__SYSCLKSOURCE__))
3063 /** @brief Macro to get the clock source used as system clock.
3064 * @retval The clock source used as system clock. The returned value can be one
3065 * of the following:
3066 * - RCC_SYSCLKSOURCE_STATUS_HSI: HSI used as system clock.
3067 * - RCC_SYSCLKSOURCE_STATUS_HSE: HSE used as system clock.
3068 * - RCC_SYSCLKSOURCE_STATUS_PLLCLK: PLL used as system clock.
3070 #define __HAL_RCC_GET_SYSCLK_SOURCE() (READ_BIT(RCC->CFGR, RCC_CFGR_SWS))
3073 * @brief Macro to configure the External Low Speed oscillator (LSE) drive capability.
3074 * @note As the LSE is in the Backup domain and write access is denied to
3075 * this domain after reset, you have to enable write access using
3076 * HAL_PWR_EnableBkUpAccess() function before to configure the LSE
3077 * (to be done once after reset).
3078 * @param __LSEDRIVE__ specifies the new state of the LSE drive capability.
3079 * This parameter can be one of the following values:
3080 * @arg @ref RCC_LSEDRIVE_LOW LSE oscillator low drive capability.
3081 * @arg @ref RCC_LSEDRIVE_MEDIUMLOW LSE oscillator medium low drive capability.
3082 * @arg @ref RCC_LSEDRIVE_MEDIUMHIGH LSE oscillator medium high drive capability.
3083 * @arg @ref RCC_LSEDRIVE_HIGH LSE oscillator high drive capability.
3084 * @retval None
3086 #define __HAL_RCC_LSEDRIVE_CONFIG(__LSEDRIVE__) \
3087 MODIFY_REG(RCC->BDCR, RCC_BDCR_LSEDRV, (__LSEDRIVE__))
3089 /** @brief Macro to configure the MCO clock.
3090 * @param __MCOCLKSOURCE__ specifies the MCO clock source.
3091 * This parameter can be one of the following values:
3092 * @arg @ref RCC_MCO1SOURCE_NOCLOCK MCO output disabled
3093 * @arg @ref RCC_MCO1SOURCE_SYSCLK System clock selected as MCO source
3094 * @arg @ref RCC_MCO1SOURCE_HSI HSI clock selected as MCO source
3095 * @arg @ref RCC_MCO1SOURCE_HSE HSE clock selected as MCO sourcee
3096 * @arg @ref RCC_MCO1SOURCE_PLLCLK Main PLL clock selected as MCO source
3097 * @arg @ref RCC_MCO1SOURCE_LSI LSI clock selected as MCO source
3098 * @arg @ref RCC_MCO1SOURCE_LSE LSE clock selected as MCO source
3099 * @arg @ref RCC_MCO1SOURCE_HSI48 HSI48 clock selected as MCO source for devices with HSI48
3100 * @param __MCODIV__ specifies the MCO clock prescaler.
3101 * This parameter can be one of the following values:
3102 * @arg @ref RCC_MCODIV_1 MCO clock source is divided by 1
3103 * @arg @ref RCC_MCODIV_2 MCO clock source is divided by 2
3104 * @arg @ref RCC_MCODIV_4 MCO clock source is divided by 4
3105 * @arg @ref RCC_MCODIV_8 MCO clock source is divided by 8
3106 * @arg @ref RCC_MCODIV_16 MCO clock source is divided by 16
3108 #define __HAL_RCC_MCO1_CONFIG(__MCOCLKSOURCE__, __MCODIV__) \
3109 MODIFY_REG(RCC->CFGR, (RCC_CFGR_MCOSEL | RCC_CFGR_MCOPRE), ((__MCOCLKSOURCE__) | (__MCODIV__)))
3111 /** @defgroup RCC_Flags_Interrupts_Management Flags Interrupts Management
3112 * @brief macros to manage the specified RCC Flags and interrupts.
3113 * @{
3116 /** @brief Enable RCC interrupt (Perform Byte access to RCC_CIR[14:8] bits to enable
3117 * the selected interrupts).
3118 * @param __INTERRUPT__ specifies the RCC interrupt sources to be enabled.
3119 * This parameter can be any combination of the following values:
3120 * @arg @ref RCC_IT_LSIRDY LSI ready interrupt
3121 * @arg @ref RCC_IT_LSERDY LSE ready interrupt
3122 * @arg @ref RCC_IT_HSIRDY HSI ready interrupt
3123 * @arg @ref RCC_IT_HSERDY HSE ready interrupt
3124 * @arg @ref RCC_IT_PLLRDY Main PLL ready interrupt
3125 * @arg @ref RCC_IT_LSECSS LSE Clock security system interrupt
3126 * @arg @ref RCC_IT_HSI48RDY HSI48 ready interrupt for devices with HSI48
3127 * @retval None
3129 #define __HAL_RCC_ENABLE_IT(__INTERRUPT__) SET_BIT(RCC->CIER, (__INTERRUPT__))
3131 /** @brief Disable RCC interrupt (Perform Byte access to RCC_CIR[14:8] bits to disable
3132 * the selected interrupts).
3133 * @param __INTERRUPT__ specifies the RCC interrupt sources to be disabled.
3134 * This parameter can be any combination of the following values:
3135 * @arg @ref RCC_IT_LSIRDY LSI ready interrupt
3136 * @arg @ref RCC_IT_LSERDY LSE ready interrupt
3137 * @arg @ref RCC_IT_HSIRDY HSI ready interrupt
3138 * @arg @ref RCC_IT_HSERDY HSE ready interrupt
3139 * @arg @ref RCC_IT_PLLRDY Main PLL ready interrupt
3140 * @arg @ref RCC_IT_LSECSS LSE Clock security system interrupt
3141 * @arg @ref RCC_IT_HSI48RDY HSI48 ready interrupt for devices with HSI48
3142 * @retval None
3144 #define __HAL_RCC_DISABLE_IT(__INTERRUPT__) CLEAR_BIT(RCC->CIER, (__INTERRUPT__))
3146 /** @brief Clear the RCC's interrupt pending bits (Perform Byte access to RCC_CIR[23:16]
3147 * bits to clear the selected interrupt pending bits.
3148 * @param __INTERRUPT__ specifies the interrupt pending bit to clear.
3149 * This parameter can be any combination of the following values:
3150 * @arg @ref RCC_IT_LSIRDY LSI ready interrupt
3151 * @arg @ref RCC_IT_LSERDY LSE ready interrupt
3152 * @arg @ref RCC_IT_HSIRDY HSI ready interrupt
3153 * @arg @ref RCC_IT_HSERDY HSE ready interrupt
3154 * @arg @ref RCC_IT_PLLRDY Main PLL ready interrupt
3155 * @arg @ref RCC_IT_CSS HSE Clock security system interrupt
3156 * @arg @ref RCC_IT_LSECSS LSE Clock security system interrupt
3157 * @arg @ref RCC_IT_HSI48RDY HSI48 ready interrupt for devices with HSI48
3158 * @retval None
3160 #define __HAL_RCC_CLEAR_IT(__INTERRUPT__) (RCC->CICR = (__INTERRUPT__))
3162 /** @brief Check whether the RCC interrupt has occurred or not.
3163 * @param __INTERRUPT__ specifies the RCC interrupt source to check.
3164 * This parameter can be one of the following values:
3165 * @arg @ref RCC_IT_LSIRDY LSI ready interrupt
3166 * @arg @ref RCC_IT_LSERDY LSE ready interrupt
3167 * @arg @ref RCC_IT_HSIRDY HSI ready interrupt
3168 * @arg @ref RCC_IT_HSERDY HSE ready interrupt
3169 * @arg @ref RCC_IT_PLLRDY Main PLL ready interrupt
3170 * @arg @ref RCC_IT_CSS HSE Clock security system interrupt
3171 * @arg @ref RCC_IT_LSECSS LSE Clock security system interrupt
3172 * @arg @ref RCC_IT_HSI48RDY HSI48 ready interrupt for devices with HSI48
3173 * @retval The new state of __INTERRUPT__ (TRUE or FALSE).
3175 #define __HAL_RCC_GET_IT(__INTERRUPT__) ((RCC->CIFR & (__INTERRUPT__)) == (__INTERRUPT__))
3177 /** @brief Set RMVF bit to clear the reset flags.
3178 * The reset flags are: RCC_FLAG_FWRRST, RCC_FLAG_OBLRST, RCC_FLAG_PINRST, RCC_FLAG_BORRST,
3179 * RCC_FLAG_SFTRST, RCC_FLAG_IWDGRST, RCC_FLAG_WWDGRST and RCC_FLAG_LPWRRST.
3180 * @retval None
3182 #define __HAL_RCC_CLEAR_RESET_FLAGS() (RCC->CSR |= RCC_CSR_RMVF)
3184 /** @brief Check whether the selected RCC flag is set or not.
3185 * @param __FLAG__ specifies the flag to check.
3186 * This parameter can be one of the following values:
3187 * @arg @ref RCC_FLAG_HSIRDY HSI oscillator clock ready
3188 * @arg @ref RCC_FLAG_HSERDY HSE oscillator clock ready
3189 * @arg @ref RCC_FLAG_PLLRDY Main PLL clock ready
3190 * @arg @ref RCC_FLAG_HSI48RDY HSI48 clock ready for devices with HSI48
3191 * @arg @ref RCC_FLAG_LSERDY LSE oscillator clock ready
3192 * @arg @ref RCC_FLAG_LSECSSD Clock security system failure on LSE oscillator detection
3193 * @arg @ref RCC_FLAG_LSIRDY LSI oscillator clock ready
3194 * @arg @ref RCC_FLAG_BORRST BOR reset
3195 * @arg @ref RCC_FLAG_OBLRST OBLRST reset
3196 * @arg @ref RCC_FLAG_PINRST Pin reset
3197 * @arg @ref RCC_FLAG_SFTRST Software reset
3198 * @arg @ref RCC_FLAG_IWDGRST Independent Watchdog reset
3199 * @arg @ref RCC_FLAG_WWDGRST Window Watchdog reset
3200 * @arg @ref RCC_FLAG_LPWRRST Low Power reset
3201 * @retval The new state of __FLAG__ (TRUE or FALSE).
3203 #define __HAL_RCC_GET_FLAG(__FLAG__) (((((((__FLAG__) >> 5U) == 1U) ? RCC->CR : \
3204 ((((__FLAG__) >> 5U) == 4U) ? RCC->CRRCR : \
3205 ((((__FLAG__) >> 5U) == 2U) ? RCC->BDCR : \
3206 ((((__FLAG__) >> 5U) == 3U) ? RCC->CSR : RCC->CIFR)))) & \
3207 ((uint32_t)1U << ((__FLAG__) & RCC_FLAG_MASK))) != 0U) \
3208 ? 1U : 0U)
3211 * @}
3215 * @}
3218 /* Private constants ---------------------------------------------------------*/
3219 /** @addtogroup RCC_Private_Constants
3220 * @{
3222 /* Defines used for Flags */
3223 #define CR_REG_INDEX 1U
3224 #define BDCR_REG_INDEX 2U
3225 #define CSR_REG_INDEX 3U
3226 #define CRRCR_REG_INDEX 4U
3228 #define RCC_FLAG_MASK 0x1FU
3230 /* Define used for IS_RCC_CLOCKTYPE() */
3231 #define RCC_CLOCKTYPE_ALL (RCC_CLOCKTYPE_SYSCLK | RCC_CLOCKTYPE_HCLK | RCC_CLOCKTYPE_PCLK1 | RCC_CLOCKTYPE_PCLK2) /*!< All clcoktype to configure */
3234 * @}
3237 /* Private macros ------------------------------------------------------------*/
3238 /** @addtogroup RCC_Private_Macros
3239 * @{
3242 #define IS_RCC_OSCILLATORTYPE(__OSCILLATOR__) (((__OSCILLATOR__) == RCC_OSCILLATORTYPE_NONE) || \
3243 (((__OSCILLATOR__) & RCC_OSCILLATORTYPE_HSE) == RCC_OSCILLATORTYPE_HSE) || \
3244 (((__OSCILLATOR__) & RCC_OSCILLATORTYPE_HSI) == RCC_OSCILLATORTYPE_HSI) || \
3245 (((__OSCILLATOR__) & RCC_OSCILLATORTYPE_HSI48) == RCC_OSCILLATORTYPE_HSI48) || \
3246 (((__OSCILLATOR__) & RCC_OSCILLATORTYPE_LSI) == RCC_OSCILLATORTYPE_LSI) || \
3247 (((__OSCILLATOR__) & RCC_OSCILLATORTYPE_LSE) == RCC_OSCILLATORTYPE_LSE))
3249 #define IS_RCC_HSE(__HSE__) (((__HSE__) == RCC_HSE_OFF) || ((__HSE__) == RCC_HSE_ON) || \
3250 ((__HSE__) == RCC_HSE_BYPASS))
3252 #define IS_RCC_LSE(__LSE__) (((__LSE__) == RCC_LSE_OFF) || ((__LSE__) == RCC_LSE_ON) || \
3253 ((__LSE__) == RCC_LSE_BYPASS))
3255 #define IS_RCC_HSI(__HSI__) (((__HSI__) == RCC_HSI_OFF) || ((__HSI__) == RCC_HSI_ON))
3257 #define IS_RCC_HSI_CALIBRATION_VALUE(__VALUE__) ((__VALUE__) <= (RCC_ICSCR_HSITRIM >> RCC_ICSCR_HSITRIM_Pos))
3259 #define IS_RCC_LSI(__LSI__) (((__LSI__) == RCC_LSI_OFF) || ((__LSI__) == RCC_LSI_ON))
3261 #define IS_RCC_HSI48(__HSI48__) (((__HSI48__) == RCC_HSI48_OFF) || ((__HSI48__) == RCC_HSI48_ON))
3263 #define IS_RCC_PLL(__PLL__) (((__PLL__) == RCC_PLL_NONE) ||((__PLL__) == RCC_PLL_OFF) || \
3264 ((__PLL__) == RCC_PLL_ON))
3266 #define IS_RCC_PLLSOURCE(__SOURCE__) (((__SOURCE__) == RCC_PLLSOURCE_NONE) || \
3267 ((__SOURCE__) == RCC_PLLSOURCE_HSI) || \
3268 ((__SOURCE__) == RCC_PLLSOURCE_HSE))
3270 #define IS_RCC_PLLM_VALUE(__VALUE__) ((1U <= (__VALUE__)) && ((__VALUE__) <= 16U))
3272 #define IS_RCC_PLLN_VALUE(__VALUE__) ((8U <= (__VALUE__)) && ((__VALUE__) <= 127U))
3274 #define IS_RCC_PLLP_VALUE(__VALUE__) (((__VALUE__) >= 2U) && ((__VALUE__) <= 31U))
3276 #define IS_RCC_PLLQ_VALUE(__VALUE__) (((__VALUE__) == 2U) || ((__VALUE__) == 4U) || \
3277 ((__VALUE__) == 6U) || ((__VALUE__) == 8U))
3279 #define IS_RCC_PLLR_VALUE(__VALUE__) (((__VALUE__) == 2U) || ((__VALUE__) == 4U) || \
3280 ((__VALUE__) == 6U) || ((__VALUE__) == 8U))
3282 #define IS_RCC_CLOCKTYPE(__CLK__) ((((__CLK__) & RCC_CLOCKTYPE_ALL) != 0x00UL) && (((__CLK__) & ~RCC_CLOCKTYPE_ALL) == 0x00UL))
3284 #define IS_RCC_SYSCLKSOURCE(__SOURCE__) (((__SOURCE__) == RCC_SYSCLKSOURCE_HSI) || \
3285 ((__SOURCE__) == RCC_SYSCLKSOURCE_HSE) || \
3286 ((__SOURCE__) == RCC_SYSCLKSOURCE_PLLCLK))
3288 #define IS_RCC_HCLK(__HCLK__) (((__HCLK__) == RCC_SYSCLK_DIV1) || ((__HCLK__) == RCC_SYSCLK_DIV2) || \
3289 ((__HCLK__) == RCC_SYSCLK_DIV4) || ((__HCLK__) == RCC_SYSCLK_DIV8) || \
3290 ((__HCLK__) == RCC_SYSCLK_DIV16) || ((__HCLK__) == RCC_SYSCLK_DIV64) || \
3291 ((__HCLK__) == RCC_SYSCLK_DIV128) || ((__HCLK__) == RCC_SYSCLK_DIV256) || \
3292 ((__HCLK__) == RCC_SYSCLK_DIV512))
3294 #define IS_RCC_PCLK(__PCLK__) (((__PCLK__) == RCC_HCLK_DIV1) || ((__PCLK__) == RCC_HCLK_DIV2) || \
3295 ((__PCLK__) == RCC_HCLK_DIV4) || ((__PCLK__) == RCC_HCLK_DIV8) || \
3296 ((__PCLK__) == RCC_HCLK_DIV16))
3298 #define IS_RCC_RTCCLKSOURCE(__SOURCE__) (((__SOURCE__) == RCC_RTCCLKSOURCE_NONE) || \
3299 ((__SOURCE__) == RCC_RTCCLKSOURCE_LSE) || \
3300 ((__SOURCE__) == RCC_RTCCLKSOURCE_LSI) || \
3301 ((__SOURCE__) == RCC_RTCCLKSOURCE_HSE_DIV32))
3303 #define IS_RCC_MCO(__MCOX__) ((__MCOX__) == RCC_MCO1)
3305 #define IS_RCC_MCO1SOURCE(__SOURCE__) (((__SOURCE__) == RCC_MCO1SOURCE_NOCLOCK) || \
3306 ((__SOURCE__) == RCC_MCO1SOURCE_SYSCLK) || \
3307 ((__SOURCE__) == RCC_MCO1SOURCE_HSI) || \
3308 ((__SOURCE__) == RCC_MCO1SOURCE_HSE) || \
3309 ((__SOURCE__) == RCC_MCO1SOURCE_PLLCLK) || \
3310 ((__SOURCE__) == RCC_MCO1SOURCE_LSI) || \
3311 ((__SOURCE__) == RCC_MCO1SOURCE_LSE) || \
3312 ((__SOURCE__) == RCC_MCO1SOURCE_HSI48))
3314 #define IS_RCC_MCODIV(__DIV__) (((__DIV__) == RCC_MCODIV_1) || ((__DIV__) == RCC_MCODIV_2) || \
3315 ((__DIV__) == RCC_MCODIV_4) || ((__DIV__) == RCC_MCODIV_8) || \
3316 ((__DIV__) == RCC_MCODIV_16))
3318 #define IS_RCC_LSE_DRIVE(__DRIVE__) (((__DRIVE__) == RCC_LSEDRIVE_LOW) || \
3319 ((__DRIVE__) == RCC_LSEDRIVE_MEDIUMLOW) || \
3320 ((__DRIVE__) == RCC_LSEDRIVE_MEDIUMHIGH) || \
3321 ((__DRIVE__) == RCC_LSEDRIVE_HIGH))
3324 * @}
3327 /* Include RCC HAL Extended module */
3328 #include "stm32g4xx_hal_rcc_ex.h"
3330 /* Exported functions --------------------------------------------------------*/
3331 /** @addtogroup RCC_Exported_Functions
3332 * @{
3336 /** @addtogroup RCC_Exported_Functions_Group1
3337 * @{
3340 /* Initialization and de-initialization functions ******************************/
3341 HAL_StatusTypeDef HAL_RCC_DeInit(void);
3342 HAL_StatusTypeDef HAL_RCC_OscConfig(RCC_OscInitTypeDef *RCC_OscInitStruct);
3343 HAL_StatusTypeDef HAL_RCC_ClockConfig(RCC_ClkInitTypeDef *RCC_ClkInitStruct, uint32_t FLatency);
3346 * @}
3349 /** @addtogroup RCC_Exported_Functions_Group2
3350 * @{
3353 /* Peripheral Control functions ************************************************/
3354 void HAL_RCC_MCOConfig(uint32_t RCC_MCOx, uint32_t RCC_MCOSource, uint32_t RCC_MCODiv);
3355 void HAL_RCC_EnableCSS(void);
3356 void HAL_RCC_EnableLSECSS(void);
3357 void HAL_RCC_DisableLSECSS(void);
3358 uint32_t HAL_RCC_GetSysClockFreq(void);
3359 uint32_t HAL_RCC_GetHCLKFreq(void);
3360 uint32_t HAL_RCC_GetPCLK1Freq(void);
3361 uint32_t HAL_RCC_GetPCLK2Freq(void);
3362 void HAL_RCC_GetOscConfig(RCC_OscInitTypeDef *RCC_OscInitStruct);
3363 void HAL_RCC_GetClockConfig(RCC_ClkInitTypeDef *RCC_ClkInitStruct, uint32_t *pFLatency);
3364 /* CSS NMI IRQ handler */
3365 void HAL_RCC_NMI_IRQHandler(void);
3366 /* User Callbacks in non blocking mode (IT mode) */
3367 void HAL_RCC_CSSCallback(void);
3370 * @}
3374 * @}
3378 * @}
3382 * @}
3385 #ifdef __cplusplus
3387 #endif
3389 #endif /* STM32G4xx_HAL_RCC_H */
3391 /************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/