2 ******************************************************************************
3 * @file stm32f10x_pwr.c
4 * @author MCD Application Team
7 * @brief This file provides all the PWR firmware functions.
8 ******************************************************************************
11 * THE PRESENT FIRMWARE WHICH IS FOR GUIDANCE ONLY AIMS AT PROVIDING CUSTOMERS
12 * WITH CODING INFORMATION REGARDING THEIR PRODUCTS IN ORDER FOR THEM TO SAVE
13 * TIME. AS A RESULT, STMICROELECTRONICS SHALL NOT BE HELD LIABLE FOR ANY
14 * DIRECT, INDIRECT OR CONSEQUENTIAL DAMAGES WITH RESPECT TO ANY CLAIMS ARISING
15 * FROM THE CONTENT OF SUCH FIRMWARE AND/OR THE USE MADE BY CUSTOMERS OF THE
16 * CODING INFORMATION CONTAINED HEREIN IN CONNECTION WITH THEIR PRODUCTS.
18 * <h2><center>© COPYRIGHT 2011 STMicroelectronics</center></h2>
19 ******************************************************************************
22 /* Includes ------------------------------------------------------------------*/
23 #include "stm32f10x_pwr.h"
24 #include "stm32f10x_rcc.h"
26 /** @addtogroup STM32F10x_StdPeriph_Driver
31 * @brief PWR driver modules
35 /** @defgroup PWR_Private_TypesDefinitions
43 /** @defgroup PWR_Private_Defines
47 /* --------- PWR registers bit address in the alias region ---------- */
48 #define PWR_OFFSET (PWR_BASE - PERIPH_BASE)
50 /* --- CR Register ---*/
52 /* Alias word address of DBP bit */
53 #define CR_OFFSET (PWR_OFFSET + 0x00)
54 #define DBP_BitNumber 0x08
55 #define CR_DBP_BB (PERIPH_BB_BASE + (CR_OFFSET * 32) + (DBP_BitNumber * 4))
57 /* Alias word address of PVDE bit */
58 #define PVDE_BitNumber 0x04
59 #define CR_PVDE_BB (PERIPH_BB_BASE + (CR_OFFSET * 32) + (PVDE_BitNumber * 4))
61 /* --- CSR Register ---*/
63 /* Alias word address of EWUP bit */
64 #define CSR_OFFSET (PWR_OFFSET + 0x04)
65 #define EWUP_BitNumber 0x08
66 #define CSR_EWUP_BB (PERIPH_BB_BASE + (CSR_OFFSET * 32) + (EWUP_BitNumber * 4))
68 /* ------------------ PWR registers bit mask ------------------------ */
70 /* CR register bit mask */
71 #define CR_DS_MASK ((uint32_t)0xFFFFFFFC)
72 #define CR_PLS_MASK ((uint32_t)0xFFFFFF1F)
79 /** @defgroup PWR_Private_Macros
87 /** @defgroup PWR_Private_Variables
95 /** @defgroup PWR_Private_FunctionPrototypes
103 /** @defgroup PWR_Private_Functions
108 * @brief Deinitializes the PWR peripheral registers to their default reset values.
112 void PWR_DeInit(void)
114 RCC_APB1PeriphResetCmd(RCC_APB1Periph_PWR
, ENABLE
);
115 RCC_APB1PeriphResetCmd(RCC_APB1Periph_PWR
, DISABLE
);
119 * @brief Enables or disables access to the RTC and backup registers.
120 * @param NewState: new state of the access to the RTC and backup registers.
121 * This parameter can be: ENABLE or DISABLE.
124 void PWR_BackupAccessCmd(FunctionalState NewState
)
126 /* Check the parameters */
127 assert_param(IS_FUNCTIONAL_STATE(NewState
));
128 *(__IO
uint32_t *) CR_DBP_BB
= (uint32_t)NewState
;
132 * @brief Enables or disables the Power Voltage Detector(PVD).
133 * @param NewState: new state of the PVD.
134 * This parameter can be: ENABLE or DISABLE.
137 void PWR_PVDCmd(FunctionalState NewState
)
139 /* Check the parameters */
140 assert_param(IS_FUNCTIONAL_STATE(NewState
));
141 *(__IO
uint32_t *) CR_PVDE_BB
= (uint32_t)NewState
;
145 * @brief Configures the voltage threshold detected by the Power Voltage Detector(PVD).
146 * @param PWR_PVDLevel: specifies the PVD detection level
147 * This parameter can be one of the following values:
148 * @arg PWR_PVDLevel_2V2: PVD detection level set to 2.2V
149 * @arg PWR_PVDLevel_2V3: PVD detection level set to 2.3V
150 * @arg PWR_PVDLevel_2V4: PVD detection level set to 2.4V
151 * @arg PWR_PVDLevel_2V5: PVD detection level set to 2.5V
152 * @arg PWR_PVDLevel_2V6: PVD detection level set to 2.6V
153 * @arg PWR_PVDLevel_2V7: PVD detection level set to 2.7V
154 * @arg PWR_PVDLevel_2V8: PVD detection level set to 2.8V
155 * @arg PWR_PVDLevel_2V9: PVD detection level set to 2.9V
158 void PWR_PVDLevelConfig(uint32_t PWR_PVDLevel
)
161 /* Check the parameters */
162 assert_param(IS_PWR_PVD_LEVEL(PWR_PVDLevel
));
164 /* Clear PLS[7:5] bits */
165 tmpreg
&= CR_PLS_MASK
;
166 /* Set PLS[7:5] bits according to PWR_PVDLevel value */
167 tmpreg
|= PWR_PVDLevel
;
168 /* Store the new value */
173 * @brief Enables or disables the WakeUp Pin functionality.
174 * @param NewState: new state of the WakeUp Pin functionality.
175 * This parameter can be: ENABLE or DISABLE.
178 void PWR_WakeUpPinCmd(FunctionalState NewState
)
180 /* Check the parameters */
181 assert_param(IS_FUNCTIONAL_STATE(NewState
));
182 *(__IO
uint32_t *) CSR_EWUP_BB
= (uint32_t)NewState
;
186 * @brief Enters STOP mode.
187 * @param PWR_Regulator: specifies the regulator state in STOP mode.
188 * This parameter can be one of the following values:
189 * @arg PWR_Regulator_ON: STOP mode with regulator ON
190 * @arg PWR_Regulator_LowPower: STOP mode with regulator in low power mode
191 * @param PWR_STOPEntry: specifies if STOP mode in entered with WFI or WFE instruction.
192 * This parameter can be one of the following values:
193 * @arg PWR_STOPEntry_WFI: enter STOP mode with WFI instruction
194 * @arg PWR_STOPEntry_WFE: enter STOP mode with WFE instruction
197 void PWR_EnterSTOPMode(uint32_t PWR_Regulator
, uint8_t PWR_STOPEntry
)
200 /* Check the parameters */
201 assert_param(IS_PWR_REGULATOR(PWR_Regulator
));
202 assert_param(IS_PWR_STOP_ENTRY(PWR_STOPEntry
));
204 /* Select the regulator state in STOP mode ---------------------------------*/
206 /* Clear PDDS and LPDS bits */
207 tmpreg
&= CR_DS_MASK
;
208 /* Set LPDS bit according to PWR_Regulator value */
209 tmpreg
|= PWR_Regulator
;
210 /* Store the new value */
212 /* Set SLEEPDEEP bit of Cortex System Control Register */
213 SCB
->SCR
|= SCB_SCR_SLEEPDEEP
;
215 /* Select STOP mode entry --------------------------------------------------*/
216 if(PWR_STOPEntry
== PWR_STOPEntry_WFI
)
218 /* Request Wait For Interrupt */
223 /* Request Wait For Event */
227 /* Reset SLEEPDEEP bit of Cortex System Control Register */
228 SCB
->SCR
&= (uint32_t)~((uint32_t)SCB_SCR_SLEEPDEEP
);
232 * @brief Enters STANDBY mode.
236 void PWR_EnterSTANDBYMode(void)
238 /* Clear Wake-up flag */
239 PWR
->CR
|= PWR_CR_CWUF
;
240 /* Select STANDBY mode */
241 PWR
->CR
|= PWR_CR_PDDS
;
242 /* Set SLEEPDEEP bit of Cortex System Control Register */
243 SCB
->SCR
|= SCB_SCR_SLEEPDEEP
;
244 /* This option is used to ensure that store operations are completed */
245 #if defined ( __CC_ARM )
248 /* Request Wait For Interrupt */
253 * @brief Checks whether the specified PWR flag is set or not.
254 * @param PWR_FLAG: specifies the flag to check.
255 * This parameter can be one of the following values:
256 * @arg PWR_FLAG_WU: Wake Up flag
257 * @arg PWR_FLAG_SB: StandBy flag
258 * @arg PWR_FLAG_PVDO: PVD Output
259 * @retval The new state of PWR_FLAG (SET or RESET).
261 FlagStatus
PWR_GetFlagStatus(uint32_t PWR_FLAG
)
263 FlagStatus bitstatus
= RESET
;
264 /* Check the parameters */
265 assert_param(IS_PWR_GET_FLAG(PWR_FLAG
));
267 if ((PWR
->CSR
& PWR_FLAG
) != (uint32_t)RESET
)
275 /* Return the flag status */
280 * @brief Clears the PWR's pending flags.
281 * @param PWR_FLAG: specifies the flag to clear.
282 * This parameter can be one of the following values:
283 * @arg PWR_FLAG_WU: Wake Up flag
284 * @arg PWR_FLAG_SB: StandBy flag
287 void PWR_ClearFlag(uint32_t PWR_FLAG
)
289 /* Check the parameters */
290 assert_param(IS_PWR_CLEAR_FLAG(PWR_FLAG
));
292 PWR
->CR
|= PWR_FLAG
<< 2;
307 /******************* (C) COPYRIGHT 2011 STMicroelectronics *****END OF FILE****/