stm32f10x_bkp.c
Go to the documentation of this file.
1 
22 /* Includes ------------------------------------------------------------------*/
23 #include "stm32f10x_bkp.h"
24 #include "stm32f10x_rcc.h"
25 
47 /* ------------ BKP registers bit address in the alias region --------------- */
48 #define BKP_OFFSET (BKP_BASE - PERIPH_BASE)
49 
50 /* --- CR Register ----*/
51 
52 /* Alias word address of TPAL bit */
53 #define CR_OFFSET (BKP_OFFSET + 0x30)
54 #define TPAL_BitNumber 0x01
55 #define CR_TPAL_BB (PERIPH_BB_BASE + (CR_OFFSET * 32) + (TPAL_BitNumber * 4))
56 
57 /* Alias word address of TPE bit */
58 #define TPE_BitNumber 0x00
59 #define CR_TPE_BB (PERIPH_BB_BASE + (CR_OFFSET * 32) + (TPE_BitNumber * 4))
60 
61 /* --- CSR Register ---*/
62 
63 /* Alias word address of TPIE bit */
64 #define CSR_OFFSET (BKP_OFFSET + 0x34)
65 #define TPIE_BitNumber 0x02
66 #define CSR_TPIE_BB (PERIPH_BB_BASE + (CSR_OFFSET * 32) + (TPIE_BitNumber * 4))
67 
68 /* Alias word address of TIF bit */
69 #define TIF_BitNumber 0x09
70 #define CSR_TIF_BB (PERIPH_BB_BASE + (CSR_OFFSET * 32) + (TIF_BitNumber * 4))
71 
72 /* Alias word address of TEF bit */
73 #define TEF_BitNumber 0x08
74 #define CSR_TEF_BB (PERIPH_BB_BASE + (CSR_OFFSET * 32) + (TEF_BitNumber * 4))
75 
76 /* ---------------------- BKP registers bit mask ------------------------ */
77 
78 /* RTCCR register bit mask */
79 #define RTCCR_CAL_MASK ((uint16_t)0xFF80)
80 #define RTCCR_MASK ((uint16_t)0xFC7F)
81 
120 void BKP_DeInit(void)
121 {
124 }
125 
134 void BKP_TamperPinLevelConfig(uint16_t BKP_TamperPinLevel)
135 {
136  /* Check the parameters */
137  assert_param(IS_BKP_TAMPER_PIN_LEVEL(BKP_TamperPinLevel));
138  *(__IO uint32_t *) CR_TPAL_BB = BKP_TamperPinLevel;
139 }
140 
148 {
149  /* Check the parameters */
151  *(__IO uint32_t *) CR_TPE_BB = (uint32_t)NewState;
152 }
153 
161 {
162  /* Check the parameters */
164  *(__IO uint32_t *) CSR_TPIE_BB = (uint32_t)NewState;
165 }
166 
180 void BKP_RTCOutputConfig(uint16_t BKP_RTCOutputSource)
181 {
182  uint16_t tmpreg = 0;
183  /* Check the parameters */
184  assert_param(IS_BKP_RTC_OUTPUT_SOURCE(BKP_RTCOutputSource));
185  tmpreg = BKP->RTCCR;
186  /* Clear CCO, ASOE and ASOS bits */
187  tmpreg &= RTCCR_MASK;
188 
189  /* Set CCO, ASOE and ASOS bits according to BKP_RTCOutputSource value */
190  tmpreg |= BKP_RTCOutputSource;
191  /* Store the new value */
192  BKP->RTCCR = tmpreg;
193 }
194 
201 void BKP_SetRTCCalibrationValue(uint8_t CalibrationValue)
202 {
203  uint16_t tmpreg = 0;
204  /* Check the parameters */
205  assert_param(IS_BKP_CALIBRATION_VALUE(CalibrationValue));
206  tmpreg = BKP->RTCCR;
207  /* Clear CAL[6:0] bits */
208  tmpreg &= RTCCR_CAL_MASK;
209  /* Set CAL[6:0] bits according to CalibrationValue value */
210  tmpreg |= CalibrationValue;
211  /* Store the new value */
212  BKP->RTCCR = tmpreg;
213 }
214 
222 void BKP_WriteBackupRegister(uint16_t BKP_DR, uint16_t Data)
223 {
224  __IO uint32_t tmp = 0;
225 
226  /* Check the parameters */
227  assert_param(IS_BKP_DR(BKP_DR));
228 
229  tmp = (uint32_t)BKP_BASE;
230  tmp += BKP_DR;
231 
232  *(__IO uint32_t *) tmp = Data;
233 }
234 
241 uint16_t BKP_ReadBackupRegister(uint16_t BKP_DR)
242 {
243  __IO uint32_t tmp = 0;
244 
245  /* Check the parameters */
246  assert_param(IS_BKP_DR(BKP_DR));
247 
248  tmp = (uint32_t)BKP_BASE;
249  tmp += BKP_DR;
250 
251  return (*(__IO uint16_t *) tmp);
252 }
253 
260 {
261  return (FlagStatus)(*(__IO uint32_t *) CSR_TEF_BB);
262 }
263 
269 void BKP_ClearFlag(void)
270 {
271  /* Set CTE bit to clear Tamper Pin Event flag */
272  BKP->CSR |= BKP_CSR_CTE;
273 }
274 
281 {
282  return (ITStatus)(*(__IO uint32_t *) CSR_TIF_BB);
283 }
284 
291 {
292  /* Set CTI bit to clear Tamper Pin Interrupt pending bit */
293  BKP->CSR |= BKP_CSR_CTI;
294 }
295 
308 /******************* (C) COPYRIGHT 2011 STMicroelectronics *****END OF FILE****/
FlagStatus
Definition: stm32f4xx.h:706
FunctionalState
Definition: stm32f4xx.h:708
uint16_t BKP_ReadBackupRegister(uint16_t BKP_DR)
Reads data from the specified Data Backup Register.
#define RTCCR_MASK
Definition: stm32f10x_bkp.c:80
void BKP_TamperPinLevelConfig(uint16_t BKP_TamperPinLevel)
Configures the Tamper Pin active level.
#define CSR_TIF_BB
Definition: stm32f10x_bkp.c:70
void BKP_RTCOutputConfig(uint16_t BKP_RTCOutputSource)
Select the RTC output source to output on the Tamper pin.
void BKP_ITConfig(FunctionalState NewState)
Enables or disables the Tamper Pin Interrupt.
void assert_param(int val)
This file contains all the functions prototypes for the BKP firmware library.
#define CR_TPE_BB
Definition: stm32f10x_bkp.c:59
void RCC_BackupResetCmd(FunctionalState NewState)
Forces or releases the Backup domain reset.
#define IS_FUNCTIONAL_STATE(STATE)
Definition: stm32f4xx.h:709
#define CR_TPAL_BB
Definition: stm32f10x_bkp.c:55
void BKP_TamperPinCmd(FunctionalState NewState)
Enables or disables the Tamper Pin activation.
enum FlagStatus ITStatus
#define __IO
Definition: core_cm0.h:198
FlagStatus BKP_GetFlagStatus(void)
Checks whether the Tamper Pin Event flag is set or not.
#define CSR_TEF_BB
Definition: stm32f10x_bkp.c:74
void BKP_DeInit(void)
Deinitializes the BKP peripheral registers to their default reset values.
#define BKP_CSR_CTI
Definition: stm32f10x.h:1669
#define IS_BKP_TAMPER_PIN_LEVEL(LEVEL)
Definition: stm32f10x_bkp.h:60
#define IS_BKP_CALIBRATION_VALUE(VALUE)
#define CSR_TPIE_BB
Definition: stm32f10x_bkp.c:66
This file contains all the functions prototypes for the RCC firmware library.
#define IS_BKP_RTC_OUTPUT_SOURCE(SOURCE)
Definition: stm32f10x_bkp.h:74
void BKP_ClearFlag(void)
Clears Tamper Pin Event pending flag.
ITStatus BKP_GetITStatus(void)
Checks whether the Tamper Pin Interrupt has occurred or not.
#define BKP_CSR_CTE
Definition: stm32f10x.h:1668
#define IS_BKP_DR(DR)
void BKP_SetRTCCalibrationValue(uint8_t CalibrationValue)
Sets RTC Clock Calibration value.
#define BKP
Definition: stm32f10x.h:1402
#define RTCCR_CAL_MASK
Definition: stm32f10x_bkp.c:79
void BKP_ClearITPendingBit(void)
Clears Tamper Pin Interrupt pending bit.
#define BKP_BASE
Definition: stm32f10x.h:1308
void BKP_WriteBackupRegister(uint16_t BKP_DR, uint16_t Data)
Writes user data to the specified Data Backup Register.


rosflight_firmware
Author(s): Daniel Koch , James Jackson
autogenerated on Thu Apr 15 2021 05:07:48