2 ******************************************************************************
3 * @file stm32f30x_pwr.c
4 * @author MCD Application Team
7 * @brief This file provides firmware functions to manage the following
8 * functionalities of the Power Controller (PWR) peripheral:
9 * + Backup Domain Access
11 * + WakeUp pins configuration
12 * + Low Power modes configuration
15 ******************************************************************************
18 * <h2><center>© COPYRIGHT 2014 STMicroelectronics</center></h2>
20 * Licensed under MCD-ST Liberty SW License Agreement V2, (the "License");
21 * You may not use this file except in compliance with the License.
22 * You may obtain a copy of the License at:
24 * http://www.st.com/software_license_agreement_liberty_v2
26 * Unless required by applicable law or agreed to in writing, software
27 * distributed under the License is distributed on an "AS IS" BASIS,
28 * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
29 * See the License for the specific language governing permissions and
30 * limitations under the License.
32 ******************************************************************************
35 /* Includes ------------------------------------------------------------------*/
36 #include "stm32f30x_pwr.h"
37 #include "stm32f30x_rcc.h"
39 /** @addtogroup STM32F30x_StdPeriph_Driver
44 * @brief PWR driver modules
48 /* Private typedef -----------------------------------------------------------*/
49 /* Private define ------------------------------------------------------------*/
50 /* --------- PWR registers bit address in the alias region ---------- */
51 #define PWR_OFFSET (PWR_BASE - PERIPH_BASE)
53 /* --- CR Register ---*/
55 /* Alias word address of DBP bit */
56 #define CR_OFFSET (PWR_OFFSET + 0x00)
57 #define DBP_BitNumber 0x08
58 #define CR_DBP_BB (PERIPH_BB_BASE + (CR_OFFSET * 32) + (DBP_BitNumber * 4))
60 /* Alias word address of PVDE bit */
61 #define PVDE_BitNumber 0x04
62 #define CR_PVDE_BB (PERIPH_BB_BASE + (CR_OFFSET * 32) + (PVDE_BitNumber * 4))
64 /* ------------------ PWR registers bit mask ------------------------ */
66 /* CR register bit mask */
67 #define CR_DS_MASK ((uint32_t)0xFFFFFFFC)
68 #define CR_PLS_MASK ((uint32_t)0xFFFFFF1F)
70 /* Private macro -------------------------------------------------------------*/
71 /* Private variables ---------------------------------------------------------*/
72 /* Private function prototypes -----------------------------------------------*/
73 /* Private functions ---------------------------------------------------------*/
75 /** @defgroup PWR_Private_Functions
79 /** @defgroup PWR_Group1 Backup Domain Access function
80 * @brief Backup Domain Access function
83 ==============================================================================
84 ##### Backup Domain Access function #####
85 ==============================================================================
87 [..] After reset, the Backup Domain Registers (RCC BDCR Register, RTC registers
88 and RTC backup registers) are protected against possible stray write accesses.
89 [..] To enable access to Backup domain use the PWR_BackupAccessCmd(ENABLE) function.
96 * @brief Deinitializes the PWR peripheral registers to their default reset values.
100 void PWR_DeInit(void)
102 RCC_APB1PeriphResetCmd(RCC_APB1Periph_PWR
, ENABLE
);
103 RCC_APB1PeriphResetCmd(RCC_APB1Periph_PWR
, DISABLE
);
107 * @brief Enables or disables access to the RTC and backup registers.
108 * @note If the HSE divided by 32 is used as the RTC clock, the
109 * Backup Domain Access should be kept enabled.
110 * @param NewState: new state of the access to the RTC and backup registers.
111 * This parameter can be: ENABLE or DISABLE.
114 void PWR_BackupAccessCmd(FunctionalState NewState
)
116 /* Check the parameters */
117 assert_param(IS_FUNCTIONAL_STATE(NewState
));
118 *(__IO
uint32_t *) CR_DBP_BB
= (uint32_t)NewState
;
125 /** @defgroup PWR_Group2 PVD configuration functions
126 * @brief PVD configuration functions
129 ===============================================================================
130 ##### PVD configuration functions #####
131 ==============================================================================
133 (+) The PVD is used to monitor the VDD power supply by comparing it to a threshold
134 selected by the PVD Level (PLS[2:0] bits in the PWR_CR).
135 (+) A PVDO flag is available to indicate if VDD/VDDA is higher or lower than the
136 PVD threshold. This event is internally connected to the EXTI line16
137 and can generate an interrupt if enabled through the EXTI registers.
138 (+) The PVD is stopped in Standby mode.
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_0: PVD detection level set to 2.18V
149 * @arg PWR_PVDLevel_1: PVD detection level set to 2.28V
150 * @arg PWR_PVDLevel_2: PVD detection level set to 2.38V
151 * @arg PWR_PVDLevel_3: PVD detection level set to 2.48V
152 * @arg PWR_PVDLevel_4: PVD detection level set to 2.58V
153 * @arg PWR_PVDLevel_5: PVD detection level set to 2.68V
154 * @arg PWR_PVDLevel_6: PVD detection level set to 2.78V
155 * @arg PWR_PVDLevel_7: PVD detection level set to 2.88V
158 void PWR_PVDLevelConfig(uint32_t PWR_PVDLevel
)
162 /* Check the parameters */
163 assert_param(IS_PWR_PVD_LEVEL(PWR_PVDLevel
));
167 /* Clear PLS[7:5] bits */
168 tmpreg
&= CR_PLS_MASK
;
170 /* Set PLS[7:5] bits according to PWR_PVDLevel value */
171 tmpreg
|= PWR_PVDLevel
;
173 /* Store the new value */
178 * @brief Enables or disables the Power Voltage Detector(PVD).
179 * @param NewState: new state of the PVD.
180 * This parameter can be: ENABLE or DISABLE.
183 void PWR_PVDCmd(FunctionalState NewState
)
185 /* Check the parameters */
186 assert_param(IS_FUNCTIONAL_STATE(NewState
));
187 *(__IO
uint32_t *) CR_PVDE_BB
= (uint32_t)NewState
;
194 /** @defgroup PWR_Group3 WakeUp pins configuration functions
195 * @brief WakeUp pins configuration functions
198 ===============================================================================
199 ##### WakeUp pins configuration functions #####
200 ===============================================================================
202 (+) WakeUp pins are used to wakeup the system from Standby mode. These pins are
203 forced in input pull down configuration and are active on rising edges.
204 (+) There are three WakeUp pins: WakeUp Pin 1 on PA.00, WakeUp Pin 2 on PC.13 and
205 WakeUp Pin 3 on PE.06.
212 * @brief Enables or disables the WakeUp Pin functionality.
213 * @param PWR_WakeUpPin: specifies the WakeUpPin.
214 * This parameter can be: PWR_WakeUpPin_1, PWR_WakeUpPin_2 or PWR_WakeUpPin_3.
215 * @param NewState: new state of the WakeUp Pin functionality.
216 * This parameter can be: ENABLE or DISABLE.
219 void PWR_WakeUpPinCmd(uint32_t PWR_WakeUpPin
, FunctionalState NewState
)
221 /* Check the parameters */
222 assert_param(IS_PWR_WAKEUP_PIN(PWR_WakeUpPin
));
223 assert_param(IS_FUNCTIONAL_STATE(NewState
));
225 if (NewState
!= DISABLE
)
227 /* Enable the EWUPx pin */
228 PWR
->CSR
|= PWR_WakeUpPin
;
232 /* Disable the EWUPx pin */
233 PWR
->CSR
&= ~PWR_WakeUpPin
;
242 /** @defgroup PWR_Group4 Low Power modes configuration functions
243 * @brief Low Power modes configuration functions
246 ===============================================================================
247 ##### Low Power modes configuration functions #####
248 ==============================================================================
250 [..] The devices feature three low-power modes:
251 (+) Sleep mode: Cortex-M4 core stopped, peripherals kept running.
252 (+) Stop mode: all clocks are stopped, regulator running, regulator in low power mode
253 (+) Standby mode: VCORE domain powered off
259 (++) The Sleep mode is entered by executing the WFE() or WFI() instructions.
261 (++) Any peripheral interrupt acknowledged by the nested vectored interrupt
262 controller (NVIC) can wake up the device from Sleep mode.
266 [..] In Stop mode, all clocks in the VCORE domain are stopped, the PLL, the HSI,
267 and the HSE RC oscillators are disabled. Internal SRAM and register
268 contents are preserved.
269 The voltage regulator can be configured either in normal or low-power mode.
272 (++) The Stop mode is entered using the PWR_EnterSTOPMode(PWR_Regulator_LowPower,)
273 function with regulator in LowPower or with Regulator ON.
275 (++) Any EXTI Line (Internal or External) configured in Interrupt/Event mode
276 or any internal IPs (I2C or UASRT) wakeup event.
280 [..] The Standby mode allows to achieve the lowest power consumption. It is based
281 on the Cortex-M4 deepsleep mode, with the voltage regulator disabled.
282 The VCORE domain is consequently powered off. The PLL, the HSI, and the HSE
283 oscillator are also switched off. SRAM and register
284 contents are lost except for the Backup domain (RTC registers, RTC backup
285 registers and Standby circuitry).
287 [..] The voltage regulator is OFF.
290 (++) The Standby mode is entered using the PWR_EnterSTANDBYMode() function.
292 (++) WKUP pin rising edge, RTC alarm (Alarm A and Alarm B), RTC wakeup,
293 tamper event, time-stamp event, external reset in NRST pin, IWDG reset.
295 *** Auto-wakeup (AWU) from low-power mode ***
296 =============================================
297 [..] The MCU can be woken up from low-power mode by an RTC Alarm event, a tamper
298 event, a time-stamp event, or a comparator event, without depending on an
299 external interrupt (Auto-wakeup mode).
301 (+) RTC auto-wakeup (AWU) from the Stop mode
302 (++) To wake up from the Stop mode with an RTC alarm event, it is necessary to:
303 (+++) Configure the EXTI Line 17 to be sensitive to rising edges (Interrupt
304 or Event modes) using the EXTI_Init() function.
305 (+++) Enable the RTC Alarm Interrupt using the RTC_ITConfig() function
306 (+++) Configure the RTC to generate the RTC alarm using the RTC_SetAlarm()
307 and RTC_AlarmCmd() functions.
308 (++) To wake up from the Stop mode with an RTC Tamper or time stamp event, it
310 (+++) Configure the EXTI Line 19 to be sensitive to rising edges (Interrupt
311 or Event modes) using the EXTI_Init() function.
312 (+++) Enable the RTC Tamper or time stamp Interrupt using the RTC_ITConfig()
314 (+++) Configure the RTC to detect the tamper or time stamp event using the
315 RTC_TimeStampConfig(), RTC_TamperTriggerConfig() and RTC_TamperCmd()
318 (+) RTC auto-wakeup (AWU) from the Standby mode
319 (++) To wake up from the Standby mode with an RTC alarm event, it is necessary to:
320 (+++) Enable the RTC Alarm Interrupt using the RTC_ITConfig() function.
321 (+++) Configure the RTC to generate the RTC alarm using the RTC_SetAlarm()
322 and RTC_AlarmCmd() functions.
323 (++) To wake up from the Standby mode with an RTC Tamper or time stamp event, it
325 (+++) Enable the RTC Tamper or time stamp Interrupt using the RTC_ITConfig()
327 (+++) Configure the RTC to detect the tamper or time stamp event using the
328 RTC_TimeStampConfig(), RTC_TamperTriggerConfig() and RTC_TamperCmd()
331 (+) Comparator auto-wakeup (AWU) from the Stop mode
332 (++) To wake up from the Stop mode with a comparator wakeup event, it is necessary to:
333 (+++) Configure the correspondant comparator EXTI Line to be sensitive to
334 the selected edges (falling, rising or falling and rising)
335 (Interrupt or Event modes) using the EXTI_Init() function.
336 (+++) Configure the comparator to generate the event.
343 * @brief Enters Sleep mode.
344 * @note In Sleep mode, all I/O pins keep the same state as in Run mode.
345 * @param PWR_SLEEPEntry: specifies if SLEEP mode in entered with WFI or WFE instruction.
346 * This parameter can be one of the following values:
347 * @arg PWR_SLEEPEntry_WFI: enter SLEEP mode with WFI instruction
348 * @arg PWR_SLEEPEntry_WFE: enter SLEEP mode with WFE instruction
351 void PWR_EnterSleepMode(uint8_t PWR_SLEEPEntry
)
353 /* Check the parameters */
354 assert_param(IS_PWR_SLEEP_ENTRY(PWR_SLEEPEntry
));
356 /* Clear SLEEPDEEP bit of Cortex System Control Register */
357 SCB
->SCR
&= (uint32_t)~((uint32_t)SCB_SCR_SLEEPDEEP_Msk
);
359 /* Select SLEEP mode entry -------------------------------------------------*/
360 if(PWR_SLEEPEntry
== PWR_SLEEPEntry_WFI
)
362 /* Request Wait For Interrupt */
367 /* Request Wait For Event */
373 * @brief Enters STOP mode.
374 * @note In Stop mode, all I/O pins keep the same state as in Run mode.
375 * @note When exiting Stop mode by issuing an interrupt or a wakeup event,
376 * the HSI RC oscillator is selected as system clock.
377 * @note When the voltage regulator operates in low power mode, an additional
378 * startup delay is incurred when waking up from Stop mode.
379 * By keeping the internal regulator ON during Stop mode, the consumption
380 * is higher although the startup time is reduced.
381 * @param PWR_Regulator: specifies the regulator state in STOP mode.
382 * This parameter can be one of the following values:
383 * @arg PWR_Regulator_ON: STOP mode with regulator ON
384 * @arg PWR_Regulator_LowPower: STOP mode with regulator in low power mode
385 * @param PWR_STOPEntry: specifies if STOP mode in entered with WFI or WFE instruction.
386 * This parameter can be one of the following values:
387 * @arg PWR_STOPEntry_WFI: enter STOP mode with WFI instruction
388 * @arg PWR_STOPEntry_WFE: enter STOP mode with WFE instruction
391 void PWR_EnterSTOPMode(uint32_t PWR_Regulator
, uint8_t PWR_STOPEntry
)
395 /* Check the parameters */
396 assert_param(IS_PWR_REGULATOR(PWR_Regulator
));
397 assert_param(IS_PWR_STOP_ENTRY(PWR_STOPEntry
));
399 /* Select the regulator state in STOP mode ---------------------------------*/
401 /* Clear PDDS and LPDSR bits */
402 tmpreg
&= CR_DS_MASK
;
404 /* Set LPDSR bit according to PWR_Regulator value */
405 tmpreg
|= PWR_Regulator
;
407 /* Store the new value */
410 /* Set SLEEPDEEP bit of Cortex System Control Register */
411 SCB
->SCR
|= SCB_SCR_SLEEPDEEP_Msk
;
413 /* Select STOP mode entry --------------------------------------------------*/
414 if(PWR_STOPEntry
== PWR_STOPEntry_WFI
)
416 /* Request Wait For Interrupt */
421 /* Request Wait For Event */
424 /* Reset SLEEPDEEP bit of Cortex System Control Register */
425 SCB
->SCR
&= (uint32_t)~((uint32_t)SCB_SCR_SLEEPDEEP_Msk
);
429 * @brief Enters STANDBY mode.
430 * @note In Standby mode, all I/O pins are high impedance except for:
431 * @note Reset pad (still available)
432 * @note RTC_AF1 pin (PC13) if configured for Wakeup pin 2 (WKUP2), tamper,
433 * time-stamp, RTC Alarm out, or RTC clock calibration out.
434 * @note WKUP pin 1 (PA0) and WKUP pin 3 (PE6), if enabled.
438 void PWR_EnterSTANDBYMode(void)
440 /* Clear Wakeup flag */
441 PWR
->CR
|= PWR_CR_CWUF
;
443 /* Select STANDBY mode */
444 PWR
->CR
|= PWR_CR_PDDS
;
446 /* Set SLEEPDEEP bit of Cortex System Control Register */
447 SCB
->SCR
|= SCB_SCR_SLEEPDEEP_Msk
;
449 /* This option is used to ensure that store operations are completed */
450 #if defined ( __CC_ARM )
453 /* Request Wait For Interrupt */
461 /** @defgroup PWR_Group5 Flags management functions
462 * @brief Flags management functions
465 ===============================================================================
466 ##### Flags management functions #####
467 ===============================================================================
474 * @brief Checks whether the specified PWR flag is set or not.
475 * @param PWR_FLAG: specifies the flag to check.
476 * This parameter can be one of the following values:
477 * @arg PWR_FLAG_WU: Wake Up flag. This flag indicates that a wakeup event
478 * was received from the WKUP pin or from the RTC alarm (Alarm A or Alarm B),
479 * RTC Tamper event, RTC TimeStamp event or RTC Wakeup.
480 * @arg PWR_FLAG_SB: StandBy flag. This flag indicates that the system was
481 * resumed from StandBy mode.
482 * @arg PWR_FLAG_PVDO: PVD Output. This flag is valid only if PVD is enabled
483 * by the PWR_PVDCmd() function.
484 * @arg PWR_FLAG_VREFINTRDY: Internal Voltage Reference Ready flag. This
485 * flag indicates the state of the internal voltage reference, VREFINT.
486 * @retval The new state of PWR_FLAG (SET or RESET).
488 FlagStatus
PWR_GetFlagStatus(uint32_t PWR_FLAG
)
490 FlagStatus bitstatus
= RESET
;
491 /* Check the parameters */
492 assert_param(IS_PWR_GET_FLAG(PWR_FLAG
));
494 if ((PWR
->CSR
& PWR_FLAG
) != (uint32_t)RESET
)
502 /* Return the flag status */
507 * @brief Clears the PWR's pending flags.
508 * @param PWR_FLAG: specifies the flag to clear.
509 * This parameter can be one of the following values:
510 * @arg PWR_FLAG_WU: Wake Up flag
511 * @arg PWR_FLAG_SB: StandBy flag
514 void PWR_ClearFlag(uint32_t PWR_FLAG
)
516 /* Check the parameters */
517 assert_param(IS_PWR_CLEAR_FLAG(PWR_FLAG
));
519 PWR
->CR
|= PWR_FLAG
<< 2;
538 /************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/