2 ******************************************************************************
3 * @file stm32f7xx_ll_pwr.h
4 * @author MCD Application Team
7 * @brief Header file of PWR LL module.
8 ******************************************************************************
11 * <h2><center>© COPYRIGHT(c) 2017 STMicroelectronics</center></h2>
13 * Redistribution and use in source and binary forms, with or without modification,
14 * are permitted provided that the following conditions are met:
15 * 1. Redistributions of source code must retain the above copyright notice,
16 * this list of conditions and the following disclaimer.
17 * 2. Redistributions in binary form must reproduce the above copyright notice,
18 * this list of conditions and the following disclaimer in the documentation
19 * and/or other materials provided with the distribution.
20 * 3. Neither the name of STMicroelectronics nor the names of its contributors
21 * may be used to endorse or promote products derived from this software
22 * without specific prior written permission.
24 * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
25 * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
26 * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE
27 * DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE
28 * FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL
29 * DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR
30 * SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
31 * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY,
32 * OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE
33 * OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
35 ******************************************************************************
38 /* Define to prevent recursive inclusion -------------------------------------*/
39 #ifndef __STM32F7xx_LL_PWR_H
40 #define __STM32F7xx_LL_PWR_H
46 /* Includes ------------------------------------------------------------------*/
47 #include "stm32f7xx.h"
49 /** @addtogroup STM32F7xx_LL_Driver
55 /** @defgroup PWR_LL PWR
59 /* Private types -------------------------------------------------------------*/
60 /* Private variables ---------------------------------------------------------*/
61 /* Private constants ---------------------------------------------------------*/
62 /* Private macros ------------------------------------------------------------*/
63 /* Exported types ------------------------------------------------------------*/
64 /* Exported constants --------------------------------------------------------*/
65 /** @defgroup PWR_LL_Exported_Constants PWR Exported Constants
69 /** @defgroup PWR_LL_EC_CLEAR_FLAG Clear Flags Defines
70 * @brief Flags defines which can be used with LL_PWR_WriteReg function
73 #define LL_PWR_CR1_CSBF PWR_CR1_CSBF /*!< Clear standby flag */
75 #define LL_PWR_CR2_CWUF6 PWR_CR2_CWUF6 /*!< Clear WKUP pin 6 */
76 #define LL_PWR_CR2_CWUF5 PWR_CR2_CWUF5 /*!< Clear WKUP pin 5 */
77 #define LL_PWR_CR2_CWUF4 PWR_CR2_CWUF4 /*!< Clear WKUP pin 4 */
78 #define LL_PWR_CR2_CWUF3 PWR_CR2_CWUF3 /*!< Clear WKUP pin 3 */
79 #define LL_PWR_CR2_CWUF2 PWR_CR2_CWUF2 /*!< Clear WKUP pin 2 */
80 #define LL_PWR_CR2_CWUF1 PWR_CR2_CWUF1 /*!< Clear WKUP pin 1 */
85 /** @defgroup PWR_LL_EC_GET_FLAG Get Flags Defines
86 * @brief Flags defines which can be used with LL_PWR_ReadReg function
89 #define LL_PWR_CSR1_WUIF PWR_CSR1_WUIF /*!< Wakeup flag */
90 #define LL_PWR_CSR1_SBF PWR_CSR1_SBF /*!< Standby flag */
91 #define LL_PWR_CSR1_PVDO PWR_CSR1_PVDO /*!< Power voltage detector output flag */
92 #define LL_PWR_CSR1_BRR PWR_CSR1_BRR /*!< Backup Regulator ready flag */
93 #define LL_PWR_CSR1_VOSRDY PWR_CSR1_VOSRDY /*!< Voltage scaling select flag */
94 #define LL_PWR_CSR1_ODRDY PWR_CSR1_ODRDY /*!< Over-drive mode ready */
95 #define LL_PWR_CSR1_ODSWRDY PWR_CSR1_ODSWRDY /*!< Over-drive mode switching ready */
96 #define LL_PWR_CSR1_UDRDY PWR_CSR1_UDRDY /*!< Under-drive ready flag */
98 #define LL_PWR_CSR2_EWUP1 PWR_CSR2_EWUP1 /*!< Enable WKUP pin 1 */
99 #define LL_PWR_CSR2_EWUP2 PWR_CSR2_EWUP2 /*!< Enable WKUP pin 2 */
100 #define LL_PWR_CSR2_EWUP3 PWR_CSR2_EWUP3 /*!< Enable WKUP pin 3 */
101 #define LL_PWR_CSR2_EWUP4 PWR_CSR2_EWUP4 /*!< Enable WKUP pin 4 */
102 #define LL_PWR_CSR2_EWUP5 PWR_CSR2_EWUP5 /*!< Enable WKUP pin 5 */
103 #define LL_PWR_CSR2_EWUP6 PWR_CSR2_EWUP6 /*!< Enable WKUP pin 6 */
108 /** @defgroup PWR_LL_EC_MODE_PWR Mode Power
111 #define LL_PWR_MODE_STOP_MAINREGU 0x00000000U /*!< Enter Stop mode (with main Regulator ON) when the CPU enters deepsleep */
112 #define LL_PWR_MODE_STOP_MAINREGU_UNDERDRIVE (PWR_CR1_MRUDS | PWR_CR1_FPDS) /*!< Enter Stop mode (with main Regulator in under-drive mode) when the CPU enters deepsleep */
113 #define LL_PWR_MODE_STOP_LPREGU PWR_CR1_LPDS /*!< Enter Stop mode (with low power Regulator ON) when the CPU enters deepsleep */
114 #define LL_PWR_MODE_STOP_LPREGU_UNDERDRIVE (PWR_CR1_LPDS | PWR_CR1_LPUDS | PWR_CR1_FPDS) /*!< Enter Stop mode (with low power Regulator in under-drive mode) when the CPU enters deepsleep */
115 #define LL_PWR_MODE_STANDBY PWR_CR1_PDDS /*!< Enter Standby mode when the CPU enters deepsleep */
120 /** @defgroup PWR_LL_EC_REGU_VOLTAGE Regulator Voltage
123 #define LL_PWR_REGU_VOLTAGE_SCALE3 PWR_CR1_VOS_0
124 #define LL_PWR_REGU_VOLTAGE_SCALE2 PWR_CR1_VOS_1
125 #define LL_PWR_REGU_VOLTAGE_SCALE1 (PWR_CR1_VOS_0 | PWR_CR1_VOS_1)
130 /** @defgroup PWR_LL_EC_REGU_MODE_DS_MODE Regulator Mode In Deep Sleep Mode
133 #define LL_PWR_REGU_DSMODE_MAIN 0x00000000U /*!< Voltage Regulator in main mode during deepsleep mode */
134 #define LL_PWR_REGU_DSMODE_LOW_POWER PWR_CR1_LPDS /*!< Voltage Regulator in low-power mode during deepsleep mode */
139 /** @defgroup PWR_LL_EC_PVDLEVEL Power Voltage Detector Level
142 #define LL_PWR_PVDLEVEL_0 PWR_CR1_PLS_LEV0 /*!< Voltage threshold detected by PVD 2.0 V */
143 #define LL_PWR_PVDLEVEL_1 PWR_CR1_PLS_LEV1 /*!< Voltage threshold detected by PVD 2.1 V */
144 #define LL_PWR_PVDLEVEL_2 PWR_CR1_PLS_LEV2 /*!< Voltage threshold detected by PVD 2.3 V */
145 #define LL_PWR_PVDLEVEL_3 PWR_CR1_PLS_LEV3 /*!< Voltage threshold detected by PVD 2.5 V */
146 #define LL_PWR_PVDLEVEL_4 PWR_CR1_PLS_LEV4 /*!< Voltage threshold detected by PVD 2.6 V */
147 #define LL_PWR_PVDLEVEL_5 PWR_CR1_PLS_LEV5 /*!< Voltage threshold detected by PVD 2.7 V */
148 #define LL_PWR_PVDLEVEL_6 PWR_CR1_PLS_LEV6 /*!< Voltage threshold detected by PVD 2.8 V */
149 #define LL_PWR_PVDLEVEL_7 PWR_CR1_PLS_LEV7 /*!< Voltage threshold detected by PVD 2.9 V */
154 /** @defgroup PWR_LL_EC_WAKEUP_PIN Wakeup Pins
157 #define LL_PWR_WAKEUP_PIN1 PWR_CSR2_EWUP1 /*!< WKUP pin 1 : PA0 */
158 #define LL_PWR_WAKEUP_PIN2 PWR_CSR2_EWUP2 /*!< WKUP pin 2 : PA2 */
159 #define LL_PWR_WAKEUP_PIN3 PWR_CSR2_EWUP3 /*!< WKUP pin 3 : PC1 */
160 #define LL_PWR_WAKEUP_PIN4 PWR_CSR2_EWUP4 /*!< WKUP pin 4 : PC13 */
161 #define LL_PWR_WAKEUP_PIN5 PWR_CSR2_EWUP5 /*!< WKUP pin 5 : PI8 */
162 #define LL_PWR_WAKEUP_PIN6 PWR_CSR2_EWUP6 /*!< WKUP pin 6 : PI11 */
170 /* Exported macro ------------------------------------------------------------*/
171 /** @defgroup PWR_LL_Exported_Macros PWR Exported Macros
175 /** @defgroup PWR_LL_EM_WRITE_READ Common write and read registers Macros
180 * @brief Write a value in PWR register
181 * @param __REG__ Register to be written
182 * @param __VALUE__ Value to be written in the register
185 #define LL_PWR_WriteReg(__REG__, __VALUE__) WRITE_REG(PWR->__REG__, (__VALUE__))
188 * @brief Read a value in PWR register
189 * @param __REG__ Register to be read
190 * @retval Register value
192 #define LL_PWR_ReadReg(__REG__) READ_REG(PWR->__REG__)
200 /* Exported functions --------------------------------------------------------*/
201 /** @defgroup PWR_LL_Exported_Functions PWR Exported Functions
205 /** @defgroup PWR_LL_EF_Configuration Configuration
210 * @brief Enable Under Drive Mode
211 * @rmtoll CR1 UDEN LL_PWR_EnableUnderDriveMode
212 * @note This mode is enabled only with STOP low power mode.
213 * In this mode, the 1.2V domain is preserved in reduced leakage mode. This
214 * mode is only available when the main Regulator or the low power Regulator
215 * is in low voltage mode.
216 * @note If the Under-drive mode was enabled, it is automatically disabled after
218 * When the voltage Regulator operates in Under-drive mode, an additional
219 * startup delay is induced when waking up from Stop mode.
222 __STATIC_INLINE
void LL_PWR_EnableUnderDriveMode(void)
224 SET_BIT(PWR
->CR1
, PWR_CR1_UDEN
);
228 * @brief Disable Under Drive Mode
229 * @rmtoll CR1 UDEN LL_PWR_DisableUnderDriveMode
232 __STATIC_INLINE
void LL_PWR_DisableUnderDriveMode(void)
234 CLEAR_BIT(PWR
->CR1
, PWR_CR1_UDEN
);
238 * @brief Check if Under Drive Mode is enabled
239 * @rmtoll CR1 UDEN LL_PWR_IsEnabledUnderDriveMode
240 * @retval State of bit (1 or 0).
242 __STATIC_INLINE
uint32_t LL_PWR_IsEnabledUnderDriveMode(void)
244 return (READ_BIT(PWR
->CR1
, PWR_CR1_UDEN
) == (PWR_CR1_UDEN
));
248 * @brief Enable Over drive switching
249 * @rmtoll CR1 ODSWEN LL_PWR_EnableOverDriveSwitching
252 __STATIC_INLINE
void LL_PWR_EnableOverDriveSwitching(void)
254 SET_BIT(PWR
->CR1
, PWR_CR1_ODSWEN
);
258 * @brief Disable Over drive switching
259 * @rmtoll CR1 ODSWEN LL_PWR_DisableOverDriveSwitching
262 __STATIC_INLINE
void LL_PWR_DisableOverDriveSwitching(void)
264 CLEAR_BIT(PWR
->CR1
, PWR_CR1_ODSWEN
);
268 * @brief Check if Over drive switching is enabled
269 * @rmtoll CR1 ODSWEN LL_PWR_IsEnabledOverDriveSwitching
270 * @retval State of bit (1 or 0).
272 __STATIC_INLINE
uint32_t LL_PWR_IsEnabledOverDriveSwitching(void)
274 return (READ_BIT(PWR
->CR1
, PWR_CR1_ODSWEN
) == (PWR_CR1_ODSWEN
));
278 * @brief Enable Over drive Mode
279 * @rmtoll CR1 ODEN LL_PWR_EnableOverDriveMode
282 __STATIC_INLINE
void LL_PWR_EnableOverDriveMode(void)
284 SET_BIT(PWR
->CR1
, PWR_CR1_ODEN
);
288 * @brief Disable Over drive Mode
289 * @rmtoll CR1 ODEN LL_PWR_DisableOverDriveMode
292 __STATIC_INLINE
void LL_PWR_DisableOverDriveMode(void)
294 CLEAR_BIT(PWR
->CR1
, PWR_CR1_ODEN
);
298 * @brief Check if Over drive switching is enabled
299 * @rmtoll CR1 ODEN LL_PWR_IsEnabledOverDriveMode
300 * @retval State of bit (1 or 0).
302 __STATIC_INLINE
uint32_t LL_PWR_IsEnabledOverDriveMode(void)
304 return (READ_BIT(PWR
->CR1
, PWR_CR1_ODEN
) == (PWR_CR1_ODEN
));
308 * @brief Set the main internal Regulator output voltage
309 * @rmtoll CR1 VOS LL_PWR_SetRegulVoltageScaling
310 * @param VoltageScaling This parameter can be one of the following values:
311 * @arg @ref LL_PWR_REGU_VOLTAGE_SCALE1
312 * @arg @ref LL_PWR_REGU_VOLTAGE_SCALE2
313 * @arg @ref LL_PWR_REGU_VOLTAGE_SCALE3
316 __STATIC_INLINE
void LL_PWR_SetRegulVoltageScaling(uint32_t VoltageScaling
)
318 MODIFY_REG(PWR
->CR1
, PWR_CR1_VOS
, VoltageScaling
);
322 * @brief Get the main internal Regulator output voltage
323 * @rmtoll CR1 VOS LL_PWR_GetRegulVoltageScaling
324 * @retval Returned value can be one of the following values:
325 * @arg @ref LL_PWR_REGU_VOLTAGE_SCALE1
326 * @arg @ref LL_PWR_REGU_VOLTAGE_SCALE2
327 * @arg @ref LL_PWR_REGU_VOLTAGE_SCALE3
329 __STATIC_INLINE
uint32_t LL_PWR_GetRegulVoltageScaling(void)
331 return (uint32_t)(READ_BIT(PWR
->CR1
, PWR_CR1_VOS
));
335 * @brief Enable Main Regulator in deepsleep under-drive Mode
336 * @rmtoll CR1 MRUDS LL_PWR_EnableMainRegulatorDeepSleepUDMode
339 __STATIC_INLINE
void LL_PWR_EnableMainRegulatorDeepSleepUDMode(void)
341 SET_BIT(PWR
->CR1
, PWR_CR1_MRUDS
);
345 * @brief Disable Main Regulator in deepsleep under-drive Mode
346 * @rmtoll CR1 MRUDS LL_PWR_DisableMainRegulatorDeepSleepUDMode
349 __STATIC_INLINE
void LL_PWR_DisableMainRegulatorDeepSleepUDMode(void)
351 CLEAR_BIT(PWR
->CR1
, PWR_CR1_MRUDS
);
355 * @brief Check if Main Regulator in deepsleep under-drive Mode is enabled
356 * @rmtoll CR1 MRUDS LL_PWR_IsEnabledMainRegulatorDeepSleepUDMode
357 * @retval State of bit (1 or 0).
359 __STATIC_INLINE
uint32_t LL_PWR_IsEnabledMainRegulatorDeepSleepUDMode(void)
361 return (READ_BIT(PWR
->CR1
, PWR_CR1_MRUDS
) == (PWR_CR1_MRUDS
));
365 * @brief Enable Low Power Regulator in deepsleep under-drive Mode
366 * @rmtoll CR1 LPUDS LL_PWR_EnableLowPowerRegulatorDeepSleepUDMode
369 __STATIC_INLINE
void LL_PWR_EnableLowPowerRegulatorDeepSleepUDMode(void)
371 SET_BIT(PWR
->CR1
, PWR_CR1_LPUDS
);
375 * @brief Disable Low Power Regulator in deepsleep under-drive Mode
376 * @rmtoll CR1 LPUDS LL_PWR_DisableLowPowerRegulatorDeepSleepUDMode
379 __STATIC_INLINE
void LL_PWR_DisableLowPowerRegulatorDeepSleepUDMode(void)
381 CLEAR_BIT(PWR
->CR1
, PWR_CR1_LPUDS
);
385 * @brief Check if Low Power Regulator in deepsleep under-drive Mode is enabled
386 * @rmtoll CR1 LPUDS LL_PWR_IsEnabledLowPowerRegulatorDeepSleepUDMode
387 * @retval State of bit (1 or 0).
389 __STATIC_INLINE
uint32_t LL_PWR_IsEnabledLowPowerRegulatorDeepSleepUDMode(void)
391 return (READ_BIT(PWR
->CR1
, PWR_CR1_LPUDS
) == (PWR_CR1_LPUDS
));
395 * @brief Enable the Flash Power Down in Stop Mode
396 * @rmtoll CR1 FPDS LL_PWR_EnableFlashPowerDown
399 __STATIC_INLINE
void LL_PWR_EnableFlashPowerDown(void)
401 SET_BIT(PWR
->CR1
, PWR_CR1_FPDS
);
405 * @brief Disable the Flash Power Down in Stop Mode
406 * @rmtoll CR1 FPDS LL_PWR_DisableFlashPowerDown
409 __STATIC_INLINE
void LL_PWR_DisableFlashPowerDown(void)
411 CLEAR_BIT(PWR
->CR1
, PWR_CR1_FPDS
);
415 * @brief Check if the Flash Power Down in Stop Mode is enabled
416 * @rmtoll CR1 FPDS LL_PWR_IsEnabledFlashPowerDown
417 * @retval State of bit (1 or 0).
419 __STATIC_INLINE
uint32_t LL_PWR_IsEnabledFlashPowerDown(void)
421 return (READ_BIT(PWR
->CR1
, PWR_CR1_FPDS
) == (PWR_CR1_FPDS
));
425 * @brief Enable access to the backup domain
426 * @rmtoll CR1 DBP LL_PWR_EnableBkUpAccess
429 __STATIC_INLINE
void LL_PWR_EnableBkUpAccess(void)
431 SET_BIT(PWR
->CR1
, PWR_CR1_DBP
);
435 * @brief Disable access to the backup domain
436 * @rmtoll CR1 DBP LL_PWR_DisableBkUpAccess
439 __STATIC_INLINE
void LL_PWR_DisableBkUpAccess(void)
441 CLEAR_BIT(PWR
->CR1
, PWR_CR1_DBP
);
445 * @brief Check if the backup domain is enabled
446 * @rmtoll CR1 DBP LL_PWR_IsEnabledBkUpAccess
447 * @retval State of bit (1 or 0).
449 __STATIC_INLINE
uint32_t LL_PWR_IsEnabledBkUpAccess(void)
451 return (READ_BIT(PWR
->CR1
, PWR_CR1_DBP
) == (PWR_CR1_DBP
));
455 * @brief Enable Backup Regulator
456 * @rmtoll CSR1 BRE LL_PWR_EnableBkUpRegulator
457 * @note When set, the Backup Regulator (used to maintain backup SRAM content in Standby and
458 * VBAT modes) is enabled. If BRE is reset, the backup Regulator is switched off. The backup
459 * SRAM can still be used but its content will be lost in the Standby and VBAT modes. Once set,
460 * the application must wait that the Backup Regulator Ready flag (BRR) is set to indicate that
461 * the data written into the RAM will be maintained in the Standby and VBAT modes.
464 __STATIC_INLINE
void LL_PWR_EnableBkUpRegulator(void)
466 SET_BIT(PWR
->CSR1
, PWR_CSR1_BRE
);
470 * @brief Disable Backup Regulator
471 * @rmtoll CSR1 BRE LL_PWR_DisableBkUpRegulator
474 __STATIC_INLINE
void LL_PWR_DisableBkUpRegulator(void)
476 CLEAR_BIT(PWR
->CSR1
, PWR_CSR1_BRE
);
480 * @brief Check if the backup Regulator is enabled
481 * @rmtoll CSR1 BRE LL_PWR_IsEnabledBkUpRegulator
482 * @retval State of bit (1 or 0).
484 __STATIC_INLINE
uint32_t LL_PWR_IsEnabledBkUpRegulator(void)
486 return (READ_BIT(PWR
->CSR1
, PWR_CSR1_BRE
) == (PWR_CSR1_BRE
));
490 * @brief Set voltage Regulator mode during deep sleep mode
491 * @rmtoll CR1 LPDS LL_PWR_SetRegulModeDS
492 * @param RegulMode This parameter can be one of the following values:
493 * @arg @ref LL_PWR_REGU_DSMODE_MAIN
494 * @arg @ref LL_PWR_REGU_DSMODE_LOW_POWER
497 __STATIC_INLINE
void LL_PWR_SetRegulModeDS(uint32_t RegulMode
)
499 MODIFY_REG(PWR
->CR1
, PWR_CR1_LPDS
, RegulMode
);
503 * @brief Get voltage Regulator mode during deep sleep mode
504 * @rmtoll CR1 LPDS LL_PWR_GetRegulModeDS
505 * @retval Returned value can be one of the following values:
506 * @arg @ref LL_PWR_REGU_DSMODE_MAIN
507 * @arg @ref LL_PWR_REGU_DSMODE_LOW_POWER
509 __STATIC_INLINE
uint32_t LL_PWR_GetRegulModeDS(void)
511 return (uint32_t)(READ_BIT(PWR
->CR1
, PWR_CR1_LPDS
));
515 * @brief Set Power Down mode when CPU enters deepsleep
516 * @rmtoll CR1 PDDS LL_PWR_SetPowerMode\n
517 * CR1 LPDS LL_PWR_SetPowerMode\n
518 * CR1 FPDS LL_PWR_SetPowerMode\n
519 * CR1 LPUDS LL_PWR_SetPowerMode\n
520 * CR1 MRUDS LL_PWR_SetPowerMode
521 * @param PDMode This parameter can be one of the following values:
522 * @arg @ref LL_PWR_MODE_STOP_MAINREGU
523 * @arg @ref LL_PWR_MODE_STOP_MAINREGU_UNDERDRIVE
524 * @arg @ref LL_PWR_MODE_STOP_LPREGU
525 * @arg @ref LL_PWR_MODE_STOP_LPREGU_UNDERDRIVE
526 * @arg @ref LL_PWR_MODE_STANDBY
529 __STATIC_INLINE
void LL_PWR_SetPowerMode(uint32_t PDMode
)
531 MODIFY_REG(PWR
->CR1
, (PWR_CR1_PDDS
| PWR_CR1_LPDS
| PWR_CR1_FPDS
| PWR_CR1_LPUDS
| PWR_CR1_MRUDS
), PDMode
);
535 * @brief Get Power Down mode when CPU enters deepsleep
536 * @rmtoll CR1 PDDS LL_PWR_GetPowerMode\n
537 * CR1 LPDS LL_PWR_GetPowerMode\n
538 * CR1 FPDS LL_PWR_GetPowerMode\n
539 * CR1 LPUDS LL_PWR_GetPowerMode\n
540 * CR1 MRUDS LL_PWR_GetPowerMode
541 * @retval Returned value can be one of the following values:
542 * @arg @ref LL_PWR_MODE_STOP_MAINREGU
543 * @arg @ref LL_PWR_MODE_STOP_MAINREGU_UNDERDRIVE
544 * @arg @ref LL_PWR_MODE_STOP_LPREGU
545 * @arg @ref LL_PWR_MODE_STOP_LPREGU_UNDERDRIVE
546 * @arg @ref LL_PWR_MODE_STANDBY
548 __STATIC_INLINE
uint32_t LL_PWR_GetPowerMode(void)
550 return (uint32_t)(READ_BIT(PWR
->CR1
, (PWR_CR1_PDDS
| PWR_CR1_LPDS
| PWR_CR1_FPDS
| PWR_CR1_LPUDS
| PWR_CR1_MRUDS
)));
554 * @brief Configure the voltage threshold detected by the Power Voltage Detector
555 * @rmtoll CR1 PLS LL_PWR_SetPVDLevel
556 * @param PVDLevel This parameter can be one of the following values:
557 * @arg @ref LL_PWR_PVDLEVEL_0
558 * @arg @ref LL_PWR_PVDLEVEL_1
559 * @arg @ref LL_PWR_PVDLEVEL_2
560 * @arg @ref LL_PWR_PVDLEVEL_3
561 * @arg @ref LL_PWR_PVDLEVEL_4
562 * @arg @ref LL_PWR_PVDLEVEL_5
563 * @arg @ref LL_PWR_PVDLEVEL_6
564 * @arg @ref LL_PWR_PVDLEVEL_7
567 __STATIC_INLINE
void LL_PWR_SetPVDLevel(uint32_t PVDLevel
)
569 MODIFY_REG(PWR
->CR1
, PWR_CR1_PLS
, PVDLevel
);
573 * @brief Get the voltage threshold detection
574 * @rmtoll CR1 PLS LL_PWR_GetPVDLevel
575 * @retval Returned value can be one of the following values:
576 * @arg @ref LL_PWR_PVDLEVEL_0
577 * @arg @ref LL_PWR_PVDLEVEL_1
578 * @arg @ref LL_PWR_PVDLEVEL_2
579 * @arg @ref LL_PWR_PVDLEVEL_3
580 * @arg @ref LL_PWR_PVDLEVEL_4
581 * @arg @ref LL_PWR_PVDLEVEL_5
582 * @arg @ref LL_PWR_PVDLEVEL_6
583 * @arg @ref LL_PWR_PVDLEVEL_7
585 __STATIC_INLINE
uint32_t LL_PWR_GetPVDLevel(void)
587 return (uint32_t)(READ_BIT(PWR
->CR1
, PWR_CR1_PLS
));
591 * @brief Enable Power Voltage Detector
592 * @rmtoll CR1 PVDE LL_PWR_EnablePVD
595 __STATIC_INLINE
void LL_PWR_EnablePVD(void)
597 SET_BIT(PWR
->CR1
, PWR_CR1_PVDE
);
601 * @brief Disable Power Voltage Detector
602 * @rmtoll CR1 PVDE LL_PWR_DisablePVD
605 __STATIC_INLINE
void LL_PWR_DisablePVD(void)
607 CLEAR_BIT(PWR
->CR1
, PWR_CR1_PVDE
);
611 * @brief Check if Power Voltage Detector is enabled
612 * @rmtoll CR1 PVDE LL_PWR_IsEnabledPVD
613 * @retval State of bit (1 or 0).
615 __STATIC_INLINE
uint32_t LL_PWR_IsEnabledPVD(void)
617 return (READ_BIT(PWR
->CR1
, PWR_CR1_PVDE
) == (PWR_CR1_PVDE
));
621 * @brief Enable the WakeUp PINx functionality
622 * @rmtoll CSR2 EWUP1 LL_PWR_EnableWakeUpPin\n
623 * CSR2 EWUP2 LL_PWR_EnableWakeUpPin\n
624 * CSR2 EWUP3 LL_PWR_EnableWakeUpPin\n
625 * CSR2 EWUP4 LL_PWR_EnableWakeUpPin\n
626 * CSR2 EWUP5 LL_PWR_EnableWakeUpPin\n
627 * CSR2 EWUP6 LL_PWR_EnableWakeUpPin
628 * @param WakeUpPin This parameter can be one of the following values:
629 * @arg @ref LL_PWR_WAKEUP_PIN1
630 * @arg @ref LL_PWR_WAKEUP_PIN2
631 * @arg @ref LL_PWR_WAKEUP_PIN3
632 * @arg @ref LL_PWR_WAKEUP_PIN4
633 * @arg @ref LL_PWR_WAKEUP_PIN5
634 * @arg @ref LL_PWR_WAKEUP_PIN6
637 __STATIC_INLINE
void LL_PWR_EnableWakeUpPin(uint32_t WakeUpPin
)
639 SET_BIT(PWR
->CSR2
, WakeUpPin
);
643 * @brief Disable the WakeUp PINx functionality
644 * @rmtoll CSR2 EWUP1 LL_PWR_DisableWakeUpPin\n
645 * CSR2 EWUP2 LL_PWR_DisableWakeUpPin\n
646 * CSR2 EWUP3 LL_PWR_DisableWakeUpPin\n
647 * CSR2 EWUP4 LL_PWR_DisableWakeUpPin\n
648 * CSR2 EWUP5 LL_PWR_DisableWakeUpPin\n
649 * CSR2 EWUP6 LL_PWR_DisableWakeUpPin
650 * @param WakeUpPin This parameter can be one of the following values:
651 * @arg @ref LL_PWR_WAKEUP_PIN1
652 * @arg @ref LL_PWR_WAKEUP_PIN2
653 * @arg @ref LL_PWR_WAKEUP_PIN3
654 * @arg @ref LL_PWR_WAKEUP_PIN4
655 * @arg @ref LL_PWR_WAKEUP_PIN5
656 * @arg @ref LL_PWR_WAKEUP_PIN6
659 __STATIC_INLINE
void LL_PWR_DisableWakeUpPin(uint32_t WakeUpPin
)
661 CLEAR_BIT(PWR
->CSR2
, WakeUpPin
);
665 * @brief Check if the WakeUp PINx functionality is enabled
666 * @rmtoll CSR2 EWUP1 LL_PWR_IsEnabledWakeUpPin\n
667 * CSR2 EWUP2 LL_PWR_IsEnabledWakeUpPin\n
668 * CSR2 EWUP3 LL_PWR_IsEnabledWakeUpPin\n
669 * CSR2 EWUP4 LL_PWR_IsEnabledWakeUpPin\n
670 * CSR2 EWUP5 LL_PWR_IsEnabledWakeUpPin\n
671 * CSR2 EWUP6 LL_PWR_IsEnabledWakeUpPin
672 * @param WakeUpPin This parameter can be one of the following values:
673 * @arg @ref LL_PWR_WAKEUP_PIN1
674 * @arg @ref LL_PWR_WAKEUP_PIN2
675 * @arg @ref LL_PWR_WAKEUP_PIN3
676 * @arg @ref LL_PWR_WAKEUP_PIN4
677 * @arg @ref LL_PWR_WAKEUP_PIN5
678 * @arg @ref LL_PWR_WAKEUP_PIN6
679 * @retval State of bit (1 or 0).
681 __STATIC_INLINE
uint32_t LL_PWR_IsEnabledWakeUpPin(uint32_t WakeUpPin
)
683 return (READ_BIT(PWR
->CSR2
, WakeUpPin
) == (WakeUpPin
));
687 * @brief Set the Wake-Up pin polarity low for the event detection
688 * @rmtoll CR2 WUPP1 LL_PWR_SetWakeUpPinPolarityLow\n
689 * CR2 WUPP2 LL_PWR_SetWakeUpPinPolarityLow\n
690 * CR2 WUPP3 LL_PWR_SetWakeUpPinPolarityLow\n
691 * CR2 WUPP4 LL_PWR_SetWakeUpPinPolarityLow\n
692 * CR2 WUPP5 LL_PWR_SetWakeUpPinPolarityLow\n
693 * CR2 WUPP6 LL_PWR_SetWakeUpPinPolarityLow
694 * @param WakeUpPin This parameter can be one of the following values:
695 * @arg @ref LL_PWR_WAKEUP_PIN1
696 * @arg @ref LL_PWR_WAKEUP_PIN2
697 * @arg @ref LL_PWR_WAKEUP_PIN3
698 * @arg @ref LL_PWR_WAKEUP_PIN4
699 * @arg @ref LL_PWR_WAKEUP_PIN5
700 * @arg @ref LL_PWR_WAKEUP_PIN6
703 __STATIC_INLINE
void LL_PWR_SetWakeUpPinPolarityLow(uint32_t WakeUpPin
)
705 SET_BIT(PWR
->CR2
, WakeUpPin
);
709 * @brief Set the Wake-Up pin polarity high for the event detection
710 * @rmtoll CR2 WUPP1 LL_PWR_SetWakeUpPinPolarityHigh\n
711 * CR2 WUPP2 LL_PWR_SetWakeUpPinPolarityHigh\n
712 * CR2 WUPP3 LL_PWR_SetWakeUpPinPolarityHigh\n
713 * CR2 WUPP4 LL_PWR_SetWakeUpPinPolarityHigh\n
714 * CR2 WUPP5 LL_PWR_SetWakeUpPinPolarityHigh\n
715 * CR2 WUPP6 LL_PWR_SetWakeUpPinPolarityHigh
716 * @param WakeUpPin This parameter can be one of the following values:
717 * @arg @ref LL_PWR_WAKEUP_PIN1
718 * @arg @ref LL_PWR_WAKEUP_PIN2
719 * @arg @ref LL_PWR_WAKEUP_PIN3
720 * @arg @ref LL_PWR_WAKEUP_PIN4
721 * @arg @ref LL_PWR_WAKEUP_PIN5
722 * @arg @ref LL_PWR_WAKEUP_PIN6
725 __STATIC_INLINE
void LL_PWR_SetWakeUpPinPolarityHigh(uint32_t WakeUpPin
)
727 CLEAR_BIT(PWR
->CR2
, WakeUpPin
);
731 * @brief Get the Wake-Up pin polarity for the event detection
732 * @rmtoll CR2 WUPP1 LL_PWR_IsWakeUpPinPolarityLow\n
733 * CR2 WUPP2 LL_PWR_IsWakeUpPinPolarityLow\n
734 * CR2 WUPP3 LL_PWR_IsWakeUpPinPolarityLow\n
735 * CR2 WUPP4 LL_PWR_IsWakeUpPinPolarityLow\n
736 * CR2 WUPP5 LL_PWR_IsWakeUpPinPolarityLow\n
737 * CR2 WUPP6 LL_PWR_IsWakeUpPinPolarityLow
738 * @param WakeUpPin This parameter can be one of the following values:
739 * @arg @ref LL_PWR_WAKEUP_PIN1
740 * @arg @ref LL_PWR_WAKEUP_PIN2
741 * @arg @ref LL_PWR_WAKEUP_PIN3
742 * @arg @ref LL_PWR_WAKEUP_PIN4
743 * @arg @ref LL_PWR_WAKEUP_PIN5
744 * @arg @ref LL_PWR_WAKEUP_PIN6
745 * @retval State of bit (1 or 0).
747 __STATIC_INLINE
uint32_t LL_PWR_IsWakeUpPinPolarityLow(uint32_t WakeUpPin
)
749 return (READ_BIT(PWR
->CR2
, WakeUpPin
) == (WakeUpPin
));
753 * @brief Enable Internal WakeUp
754 * @rmtoll CSR1 EIWUP LL_PWR_EnableInternalWakeUp
755 * @note This API must be used when RTC events (Alarm A or Alarm B, RTC Tamper, RTC TimeStamp
756 * or RTC Wakeup time) are used to wake up the system from Standby mode.
759 __STATIC_INLINE
void LL_PWR_EnableInternalWakeUp(void)
761 SET_BIT(PWR
->CSR1
, PWR_CSR1_EIWUP
);
765 * @brief Disable Internal WakeUp
766 * @rmtoll CSR1 EIWUP LL_PWR_DisableInternalWakeUp
769 __STATIC_INLINE
void LL_PWR_DisableInternalWakeUp(void)
771 CLEAR_BIT(PWR
->CSR1
, PWR_CSR1_EIWUP
);
775 * @brief Check if the Internal WakeUp functionality is enabled
776 * @rmtoll CSR1 EIWUP LL_PWR_IsEnabledInternalWakeUp
777 * @retval State of bit (1 or 0).
779 __STATIC_INLINE
uint32_t LL_PWR_IsEnabledInternalWakeUp(void)
781 return (READ_BIT(PWR
->CSR1
, PWR_CSR1_EIWUP
) == (PWR_CSR1_EIWUP
));
788 /** @defgroup PWR_LL_EF_FLAG_Management FLAG_Management
793 * @brief Get Wake-up Flag 6
794 * @rmtoll CSR2 WUPF6 LL_PWR_IsActiveFlag_WU6
795 * @retval State of bit (1 or 0).
797 __STATIC_INLINE
uint32_t LL_PWR_IsActiveFlag_WU6(void)
799 return (READ_BIT(PWR
->CSR2
, PWR_CSR2_WUPF6
) == (PWR_CSR2_WUPF6
));
803 * @brief Get Wake-up Flag 5
804 * @rmtoll CSR2 WUPF5 LL_PWR_IsActiveFlag_WU5
805 * @retval State of bit (1 or 0).
807 __STATIC_INLINE
uint32_t LL_PWR_IsActiveFlag_WU5(void)
809 return (READ_BIT(PWR
->CSR2
, PWR_CSR2_WUPF5
) == (PWR_CSR2_WUPF5
));
813 * @brief Get Wake-up Flag 4
814 * @rmtoll CSR2 WUPF4 LL_PWR_IsActiveFlag_WU4
815 * @retval State of bit (1 or 0).
817 __STATIC_INLINE
uint32_t LL_PWR_IsActiveFlag_WU4(void)
819 return (READ_BIT(PWR
->CSR2
, PWR_CSR2_WUPF4
) == (PWR_CSR2_WUPF4
));
823 * @brief Get Wake-up Flag 3
824 * @rmtoll CSR2 WUPF3 LL_PWR_IsActiveFlag_WU3
825 * @retval State of bit (1 or 0).
827 __STATIC_INLINE
uint32_t LL_PWR_IsActiveFlag_WU3(void)
829 return (READ_BIT(PWR
->CSR2
, PWR_CSR2_WUPF3
) == (PWR_CSR2_WUPF3
));
833 * @brief Get Wake-up Flag 2
834 * @rmtoll CSR2 WUPF2 LL_PWR_IsActiveFlag_WU2
835 * @retval State of bit (1 or 0).
837 __STATIC_INLINE
uint32_t LL_PWR_IsActiveFlag_WU2(void)
839 return (READ_BIT(PWR
->CSR2
, PWR_CSR2_WUPF2
) == (PWR_CSR2_WUPF2
));
843 * @brief Get Wake-up Flag 1
844 * @rmtoll CSR2 WUPF1 LL_PWR_IsActiveFlag_WU1
845 * @retval State of bit (1 or 0).
847 __STATIC_INLINE
uint32_t LL_PWR_IsActiveFlag_WU1(void)
849 return (READ_BIT(PWR
->CSR2
, PWR_CSR2_WUPF1
) == (PWR_CSR2_WUPF1
));
853 * @brief Get Standby Flag
854 * @rmtoll CSR1 SBF LL_PWR_IsActiveFlag_SB
855 * @retval State of bit (1 or 0).
857 __STATIC_INLINE
uint32_t LL_PWR_IsActiveFlag_SB(void)
859 return (READ_BIT(PWR
->CSR1
, PWR_CSR1_SBF
) == (PWR_CSR1_SBF
));
863 * @brief Indicate whether VDD voltage is below the selected PVD threshold
864 * @rmtoll CSR1 PVDO LL_PWR_IsActiveFlag_PVDO
865 * @retval State of bit (1 or 0).
867 __STATIC_INLINE
uint32_t LL_PWR_IsActiveFlag_PVDO(void)
869 return (READ_BIT(PWR
->CSR1
, PWR_CSR1_PVDO
) == (PWR_CSR1_PVDO
));
873 * @brief Get Backup Regulator ready Flag
874 * @rmtoll CSR1 BRR LL_PWR_IsActiveFlag_BRR
875 * @retval State of bit (1 or 0).
877 __STATIC_INLINE
uint32_t LL_PWR_IsActiveFlag_BRR(void)
879 return (READ_BIT(PWR
->CSR1
, PWR_CSR1_BRR
) == (PWR_CSR1_BRR
));
883 * @brief Indicate whether the Regulator is ready in the selected voltage range or if its output voltage is still changing to the required voltage level
884 * @rmtoll CSR1 VOSRDY LL_PWR_IsActiveFlag_VOS
885 * @retval State of bit (1 or 0).
887 __STATIC_INLINE
uint32_t LL_PWR_IsActiveFlag_VOS(void)
889 return (READ_BIT(PWR
->CSR1
, PWR_CSR1_VOSRDY
) == (PWR_CSR1_VOSRDY
));
893 * @brief Indicate whether the Over-Drive mode is ready or not
894 * @rmtoll CSR1 ODRDY LL_PWR_IsActiveFlag_OD
895 * @retval State of bit (1 or 0).
897 __STATIC_INLINE
uint32_t LL_PWR_IsActiveFlag_OD(void)
899 return (READ_BIT(PWR
->CSR1
, PWR_CSR1_ODRDY
) == (PWR_CSR1_ODRDY
));
903 * @brief Indicate whether the Over-Drive mode switching is ready or not
904 * @rmtoll CSR1 ODSWRDY LL_PWR_IsActiveFlag_ODSW
905 * @retval State of bit (1 or 0).
907 __STATIC_INLINE
uint32_t LL_PWR_IsActiveFlag_ODSW(void)
909 return (READ_BIT(PWR
->CSR1
, PWR_CSR1_ODSWRDY
) == (PWR_CSR1_ODSWRDY
));
913 * @brief Indicate whether the Under-Drive mode is ready or not
914 * @rmtoll CSR1 UDRDY LL_PWR_IsActiveFlag_UD
915 * @retval State of bit (1 or 0).
917 __STATIC_INLINE
uint32_t LL_PWR_IsActiveFlag_UD(void)
919 return (READ_BIT(PWR
->CSR1
, PWR_CSR1_UDRDY
) == (PWR_CSR1_UDRDY
));
923 * @brief Clear Standby Flag
924 * @rmtoll CR1 CSBF LL_PWR_ClearFlag_SB
927 __STATIC_INLINE
void LL_PWR_ClearFlag_SB(void)
929 SET_BIT(PWR
->CR1
, PWR_CR1_CSBF
);
933 * @brief Clear Wake-up Flag 6
934 * @rmtoll CR2 CWUF6 LL_PWR_ClearFlag_WU6
937 __STATIC_INLINE
void LL_PWR_ClearFlag_WU6(void)
939 WRITE_REG(PWR
->CR2
, PWR_CR2_CWUPF6
);
943 * @brief Clear Wake-up Flag 5
944 * @rmtoll CR2 CWUF5 LL_PWR_ClearFlag_WU5
947 __STATIC_INLINE
void LL_PWR_ClearFlag_WU5(void)
949 WRITE_REG(PWR
->CR2
, PWR_CR2_CWUPF5
);
953 * @brief Clear Wake-up Flag 4
954 * @rmtoll CR2 CWUF4 LL_PWR_ClearFlag_WU4
957 __STATIC_INLINE
void LL_PWR_ClearFlag_WU4(void)
959 WRITE_REG(PWR
->CR2
, PWR_CR2_CWUPF4
);
963 * @brief Clear Wake-up Flag 3
964 * @rmtoll CR2 CWUF3 LL_PWR_ClearFlag_WU3
967 __STATIC_INLINE
void LL_PWR_ClearFlag_WU3(void)
969 WRITE_REG(PWR
->CR2
, PWR_CR2_CWUPF3
);
973 * @brief Clear Wake-up Flag 2
974 * @rmtoll CR2 CWUF2 LL_PWR_ClearFlag_WU2
977 __STATIC_INLINE
void LL_PWR_ClearFlag_WU2(void)
979 WRITE_REG(PWR
->CR2
, PWR_CR2_CWUPF2
);
983 * @brief Clear Wake-up Flag 1
984 * @rmtoll CR2 CWUF1 LL_PWR_ClearFlag_WU1
987 __STATIC_INLINE
void LL_PWR_ClearFlag_WU1(void)
989 WRITE_REG(PWR
->CR2
, PWR_CR2_CWUPF1
);
993 * @brief Clear Under-Drive ready Flag
994 * @rmtoll CSR1 UDRDY LL_PWR_ClearFlag_UD
997 __STATIC_INLINE
void LL_PWR_ClearFlag_UD(void)
999 WRITE_REG(PWR
->CSR1
, PWR_CSR1_UDRDY
);
1002 #if defined(USE_FULL_LL_DRIVER)
1003 /** @defgroup PWR_LL_EF_Init De-initialization function
1006 ErrorStatus
LL_PWR_DeInit(void);
1010 #endif /* USE_FULL_LL_DRIVER */
1024 #endif /* defined(PWR) */
1034 #endif /* __STM32F7xx_LL_PWR_H */
1036 /************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/