F1 and F3 HAL / LL libraries
[betaflight.git] / lib / main / STM32F1 / Drivers / STM32F1xx_HAL_Driver / Src / stm32f1xx_ll_rtc.c
blobcbe98610c106c988b9e66aa1768533ef14c0b59a
1 /**
2 ******************************************************************************
3 * @file stm32f1xx_ll_rtc.c
4 * @author MCD Application Team
5 * @version V1.1.1
6 * @date 12-May-2017
7 * @brief RTC LL module driver.
8 ******************************************************************************
9 * @attention
11 * <h2><center>&copy; COPYRIGHT(c) 2016 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 ******************************************************************************
37 #if defined(USE_FULL_LL_DRIVER)
39 /* Includes ------------------------------------------------------------------*/
40 #include "stm32f1xx_ll_rtc.h"
41 #include "stm32f1xx_ll_cortex.h"
42 #ifdef USE_FULL_ASSERT
43 #include "stm32_assert.h"
44 #else
45 #define assert_param(expr) ((void)0U)
46 #endif
48 /** @addtogroup STM32F1xx_LL_Driver
49 * @{
52 #if defined(RTC)
54 /** @addtogroup RTC_LL
55 * @{
58 /* Private types -------------------------------------------------------------*/
59 /* Private variables ---------------------------------------------------------*/
60 /* Private constants ---------------------------------------------------------*/
61 /** @addtogroup RTC_LL_Private_Constants
62 * @{
64 /* Default values used for prescaler */
65 #define RTC_ASYNCH_PRESC_DEFAULT 0x00007FFFU
67 /* Values used for timeout */
68 #define RTC_INITMODE_TIMEOUT 1000U /* 1s when tick set to 1ms */
69 #define RTC_SYNCHRO_TIMEOUT 1000U /* 1s when tick set to 1ms */
70 /**
71 * @}
74 /* Private macros ------------------------------------------------------------*/
75 /** @addtogroup RTC_LL_Private_Macros
76 * @{
79 #define IS_LL_RTC_ASYNCH_PREDIV(__VALUE__) ((__VALUE__) <= 0xFFFFFU)
81 #define IS_LL_RTC_FORMAT(__VALUE__) (((__VALUE__) == LL_RTC_FORMAT_BIN) \
82 || ((__VALUE__) == LL_RTC_FORMAT_BCD))
84 #define IS_LL_RTC_HOUR24(__HOUR__) ((__HOUR__) <= 23U)
85 #define IS_LL_RTC_MINUTES(__MINUTES__) ((__MINUTES__) <= 59U)
86 #define IS_LL_RTC_SECONDS(__SECONDS__) ((__SECONDS__) <= 59U)
87 #define IS_LL_RTC_CALIB_OUTPUT(__OUTPUT__) (((__OUTPUT__) == LL_RTC_CALIB_OUTPUT_NONE) || \
88 ((__OUTPUT__) == LL_RTC_CALIB_OUTPUT_RTCCLOCK) || \
89 ((__OUTPUT__) == LL_RTC_CALIB_OUTPUT_ALARM) || \
90 ((__OUTPUT__) == LL_RTC_CALIB_OUTPUT_SECOND))
91 /**
92 * @}
94 /* Private function prototypes -----------------------------------------------*/
95 /* Exported functions --------------------------------------------------------*/
96 /** @addtogroup RTC_LL_Exported_Functions
97 * @{
100 /** @addtogroup RTC_LL_EF_Init
101 * @{
105 * @brief De-Initializes the RTC registers to their default reset values.
106 * @note This function doesn't reset the RTC Clock source and RTC Backup Data
107 * registers.
108 * @param RTCx RTC Instance
109 * @retval An ErrorStatus enumeration value:
110 * - SUCCESS: RTC registers are de-initialized
111 * - ERROR: RTC registers are not de-initialized
113 ErrorStatus LL_RTC_DeInit(RTC_TypeDef *RTCx)
115 ErrorStatus status = ERROR;
117 /* Check the parameter */
118 assert_param(IS_RTC_ALL_INSTANCE(RTCx));
120 /* Disable the write protection for RTC registers */
121 LL_RTC_DisableWriteProtection(RTCx);
123 /* Set Initialization mode */
124 if (LL_RTC_EnterInitMode(RTCx) != ERROR)
126 LL_RTC_WriteReg(RTCx,CNTL, 0x0000);
127 LL_RTC_WriteReg(RTCx,CNTH, 0x0000);
128 LL_RTC_WriteReg(RTCx,PRLH, 0x0000);
129 LL_RTC_WriteReg(RTCx,PRLL, 0x8000);
130 LL_RTC_WriteReg(RTCx,CRH, 0x0000);
131 LL_RTC_WriteReg(RTCx,CRL, 0x0020);
133 /* Reset Tamper and alternate functions configuration register */
134 LL_RTC_WriteReg(BKP,RTCCR, 0x00000000U);
135 LL_RTC_WriteReg(BKP,CR, 0x00000000U);
136 LL_RTC_WriteReg(BKP,CSR, 0x00000000U);
138 /* Exit Initialization Mode */
139 if(LL_RTC_ExitInitMode(RTCx) == ERROR)
141 return ERROR;
144 /* Wait till the RTC RSF flag is set */
145 status = LL_RTC_WaitForSynchro(RTCx);
147 /* Clear RSF Flag */
148 LL_RTC_ClearFlag_RS(RTCx);
151 /* Enable the write protection for RTC registers */
152 LL_RTC_EnableWriteProtection(RTCx);
154 return status;
158 * @brief Initializes the RTC registers according to the specified parameters
159 * in RTC_InitStruct.
160 * @param RTCx RTC Instance
161 * @param RTC_InitStruct pointer to a @ref LL_RTC_InitTypeDef structure that contains
162 * the configuration information for the RTC peripheral.
163 * @note The RTC Prescaler register is write protected and can be written in
164 * initialization mode only.
165 * @note the user should call LL_RTC_StructInit() or the structure of Prescaler
166 * need to be initialized before RTC init()
167 * @retval An ErrorStatus enumeration value:
168 * - SUCCESS: RTC registers are initialized
169 * - ERROR: RTC registers are not initialized
171 ErrorStatus LL_RTC_Init(RTC_TypeDef *RTCx, LL_RTC_InitTypeDef *RTC_InitStruct)
173 ErrorStatus status = ERROR;
175 /* Check the parameters */
176 assert_param(IS_RTC_ALL_INSTANCE(RTCx));
177 assert_param(IS_LL_RTC_ASYNCH_PREDIV(RTC_InitStruct->AsynchPrescaler));
178 assert_param(IS_LL_RTC_CALIB_OUTPUT(RTC_InitStruct->OutPutSource));
179 /* Waiting for synchro */
180 if(LL_RTC_WaitForSynchro(RTCx) != ERROR)
182 /* Set Initialization mode */
183 if (LL_RTC_EnterInitMode(RTCx) != ERROR)
185 /* Clear Flag Bits */
186 LL_RTC_ClearFlag_ALR(RTCx);
187 LL_RTC_ClearFlag_OW(RTCx);
188 LL_RTC_ClearFlag_SEC(RTCx);
190 if(RTC_InitStruct->OutPutSource != LL_RTC_CALIB_OUTPUT_NONE)
192 /* Disable the selected Tamper Pin */
193 LL_RTC_TAMPER_Disable(BKP);
195 /* Set the signal which will be routed to RTC Tamper Pin */
196 LL_RTC_SetOutputSource(BKP, RTC_InitStruct->OutPutSource);
198 /* Configure Synchronous and Asynchronous prescaler factor */
199 LL_RTC_SetAsynchPrescaler(RTCx, RTC_InitStruct->AsynchPrescaler);
201 /* Exit Initialization Mode */
202 LL_RTC_ExitInitMode(RTCx);
204 status = SUCCESS;
207 return status;
211 * @brief Set each @ref LL_RTC_InitTypeDef field to default value.
212 * @param RTC_InitStruct pointer to a @ref LL_RTC_InitTypeDef structure which will be initialized.
213 * @retval None
215 void LL_RTC_StructInit(LL_RTC_InitTypeDef *RTC_InitStruct)
217 /* Set RTC_InitStruct fields to default values */
218 RTC_InitStruct->AsynchPrescaler = RTC_ASYNCH_PRESC_DEFAULT;
219 RTC_InitStruct->OutPutSource = LL_RTC_CALIB_OUTPUT_NONE;
223 * @brief Set the RTC current time.
224 * @param RTCx RTC Instance
225 * @param RTC_Format This parameter can be one of the following values:
226 * @arg @ref LL_RTC_FORMAT_BIN
227 * @arg @ref LL_RTC_FORMAT_BCD
228 * @param RTC_TimeStruct pointer to a RTC_TimeTypeDef structure that contains
229 * the time configuration information for the RTC.
230 * @note The user should call LL_RTC_TIME_StructInit() or the structure
231 * of time need to be initialized before time init()
232 * @retval An ErrorStatus enumeration value:
233 * - SUCCESS: RTC Time register is configured
234 * - ERROR: RTC Time register is not configured
236 ErrorStatus LL_RTC_TIME_Init(RTC_TypeDef *RTCx, uint32_t RTC_Format, LL_RTC_TimeTypeDef *RTC_TimeStruct)
238 ErrorStatus status = ERROR;
239 uint32_t counter_time = 0U;
241 /* Check the parameters */
242 assert_param(IS_RTC_ALL_INSTANCE(RTCx));
243 assert_param(IS_LL_RTC_FORMAT(RTC_Format));
245 if (RTC_Format == LL_RTC_FORMAT_BIN)
247 assert_param(IS_LL_RTC_HOUR24(RTC_TimeStruct->Hours));
248 assert_param(IS_LL_RTC_MINUTES(RTC_TimeStruct->Minutes));
249 assert_param(IS_LL_RTC_SECONDS(RTC_TimeStruct->Seconds));
251 else
253 assert_param(IS_LL_RTC_HOUR24(__LL_RTC_CONVERT_BCD2BIN(RTC_TimeStruct->Hours)));
254 assert_param(IS_LL_RTC_MINUTES(__LL_RTC_CONVERT_BCD2BIN(RTC_TimeStruct->Minutes)));
255 assert_param(IS_LL_RTC_SECONDS(__LL_RTC_CONVERT_BCD2BIN(RTC_TimeStruct->Seconds)));
258 /* Enter Initialization mode */
259 if (LL_RTC_EnterInitMode(RTCx) != ERROR)
261 /* Check the input parameters format */
262 if (RTC_Format != LL_RTC_FORMAT_BIN)
264 counter_time = (uint32_t)(((uint32_t)RTC_TimeStruct->Hours * 3600U) + \
265 ((uint32_t)RTC_TimeStruct->Minutes * 60U) + \
266 ((uint32_t)RTC_TimeStruct->Seconds));
267 LL_RTC_TIME_Set(RTCx, counter_time);
269 else
271 counter_time = (((uint32_t)(__LL_RTC_CONVERT_BCD2BIN(RTC_TimeStruct->Hours)) * 3600U) + \
272 ((uint32_t)(__LL_RTC_CONVERT_BCD2BIN(RTC_TimeStruct->Minutes)) * 60U) + \
273 ((uint32_t)(__LL_RTC_CONVERT_BCD2BIN(RTC_TimeStruct->Seconds))));
274 LL_RTC_TIME_Set(RTCx, counter_time);
276 status = SUCCESS;
278 /* Exit Initialization mode */
279 LL_RTC_ExitInitMode(RTCx);
281 return status;
285 * @brief Set each @ref LL_RTC_TimeTypeDef field to default value (Time = 00h:00min:00sec).
286 * @param RTC_TimeStruct pointer to a @ref LL_RTC_TimeTypeDef structure which will be initialized.
287 * @retval None
289 void LL_RTC_TIME_StructInit(LL_RTC_TimeTypeDef *RTC_TimeStruct)
291 /* Time = 00h:00min:00sec */
292 RTC_TimeStruct->Hours = 0U;
293 RTC_TimeStruct->Minutes = 0U;
294 RTC_TimeStruct->Seconds = 0U;
298 * @brief Set the RTC Alarm.
299 * @param RTCx RTC Instance
300 * @param RTC_Format This parameter can be one of the following values:
301 * @arg @ref LL_RTC_FORMAT_BIN
302 * @arg @ref LL_RTC_FORMAT_BCD
303 * @param RTC_AlarmStruct pointer to a @ref LL_RTC_AlarmTypeDef structure that
304 * contains the alarm configuration parameters.
305 * @note the user should call LL_RTC_ALARM_StructInit() or the structure
306 * of Alarm need to be initialized before Alarm init()
307 * @retval An ErrorStatus enumeration value:
308 * - SUCCESS: ALARM registers are configured
309 * - ERROR: ALARM registers are not configured
311 ErrorStatus LL_RTC_ALARM_Init(RTC_TypeDef *RTCx, uint32_t RTC_Format, LL_RTC_AlarmTypeDef *RTC_AlarmStruct)
313 ErrorStatus status = ERROR;
314 uint32_t counter_alarm = 0U;
315 /* Check the parameters */
316 assert_param(IS_RTC_ALL_INSTANCE(RTCx));
317 assert_param(IS_LL_RTC_FORMAT(RTC_Format));
319 if (RTC_Format == LL_RTC_FORMAT_BIN)
321 assert_param(IS_LL_RTC_HOUR24(RTC_AlarmStruct->AlarmTime.Hours));
322 assert_param(IS_LL_RTC_MINUTES(RTC_AlarmStruct->AlarmTime.Minutes));
323 assert_param(IS_LL_RTC_SECONDS(RTC_AlarmStruct->AlarmTime.Seconds));
325 else
327 assert_param(IS_LL_RTC_HOUR24(__LL_RTC_CONVERT_BCD2BIN(RTC_AlarmStruct->AlarmTime.Hours)));
328 assert_param(IS_LL_RTC_MINUTES(__LL_RTC_CONVERT_BCD2BIN(RTC_AlarmStruct->AlarmTime.Minutes)));
329 assert_param(IS_LL_RTC_SECONDS(__LL_RTC_CONVERT_BCD2BIN(RTC_AlarmStruct->AlarmTime.Seconds)));
332 /* Enter Initialization mode */
333 if (LL_RTC_EnterInitMode(RTCx) != ERROR)
335 /* Check the input parameters format */
336 if (RTC_Format != LL_RTC_FORMAT_BIN)
338 counter_alarm = (uint32_t)(((uint32_t)RTC_AlarmStruct->AlarmTime.Hours * 3600U) + \
339 ((uint32_t)RTC_AlarmStruct->AlarmTime.Minutes * 60U) + \
340 ((uint32_t)RTC_AlarmStruct->AlarmTime.Seconds));
341 LL_RTC_ALARM_Set(RTCx, counter_alarm);
343 else
345 counter_alarm = (((uint32_t)(__LL_RTC_CONVERT_BCD2BIN(RTC_AlarmStruct->AlarmTime.Hours)) * 3600U) + \
346 ((uint32_t)(__LL_RTC_CONVERT_BCD2BIN(RTC_AlarmStruct->AlarmTime.Minutes)) * 60U) + \
347 ((uint32_t)(__LL_RTC_CONVERT_BCD2BIN(RTC_AlarmStruct->AlarmTime.Seconds))));
348 LL_RTC_ALARM_Set(RTCx, counter_alarm);
350 status = SUCCESS;
352 /* Exit Initialization mode */
353 LL_RTC_ExitInitMode(RTCx);
355 return status;
359 * @brief Set each @ref LL_RTC_AlarmTypeDef of ALARM field to default value (Time = 00h:00mn:00sec /
360 * Day = 1st day of the month/Mask = all fields are masked).
361 * @param RTC_AlarmStruct pointer to a @ref LL_RTC_AlarmTypeDef structure which will be initialized.
362 * @retval None
364 void LL_RTC_ALARM_StructInit(LL_RTC_AlarmTypeDef *RTC_AlarmStruct)
366 /* Alarm Time Settings : Time = 00h:00mn:00sec */
367 RTC_AlarmStruct->AlarmTime.Hours = 0U;
368 RTC_AlarmStruct->AlarmTime.Minutes = 0U;
369 RTC_AlarmStruct->AlarmTime.Seconds = 0U;
373 * @brief Enters the RTC Initialization mode.
374 * @param RTCx RTC Instance
375 * @retval An ErrorStatus enumeration value:
376 * - SUCCESS: RTC is in Init mode
377 * - ERROR: RTC is not in Init mode
379 ErrorStatus LL_RTC_EnterInitMode(RTC_TypeDef *RTCx)
381 __IO uint32_t timeout = RTC_INITMODE_TIMEOUT;
382 ErrorStatus status = SUCCESS;
383 uint32_t tmp = 0U;
385 /* Check the parameter */
386 assert_param(IS_RTC_ALL_INSTANCE(RTCx));
388 /* Wait till RTC is in INIT state and if Time out is reached exit */
389 tmp = LL_RTC_IsActiveFlag_RTOF(RTCx);
390 while ((timeout != 0U) && (tmp != 1U))
392 if (LL_SYSTICK_IsActiveCounterFlag() == 1U)
394 timeout --;
396 tmp = LL_RTC_IsActiveFlag_RTOF(RTCx);
397 if (timeout == 0U)
399 status = ERROR;
403 /* Disable the write protection for RTC registers */
404 LL_RTC_DisableWriteProtection(RTCx);
406 return status;
410 * @brief Exit the RTC Initialization mode.
411 * @note When the initialization sequence is complete, the calendar restarts
412 * counting after 4 RTCCLK cycles.
413 * @param RTCx RTC Instance
414 * @retval An ErrorStatus enumeration value:
415 * - SUCCESS: RTC exited from in Init mode
416 * - ERROR: Not applicable
418 ErrorStatus LL_RTC_ExitInitMode(RTC_TypeDef *RTCx)
420 __IO uint32_t timeout = RTC_INITMODE_TIMEOUT;
421 ErrorStatus status = SUCCESS;
422 uint32_t tmp = 0U;
424 /* Check the parameter */
425 assert_param(IS_RTC_ALL_INSTANCE(RTCx));
427 /* Disable initialization mode */
428 LL_RTC_EnableWriteProtection(RTCx);
430 /* Wait till RTC is in INIT state and if Time out is reached exit */
431 tmp = LL_RTC_IsActiveFlag_RTOF(RTCx);
432 while ((timeout != 0U) && (tmp != 1U))
434 if (LL_SYSTICK_IsActiveCounterFlag() == 1U)
436 timeout --;
438 tmp = LL_RTC_IsActiveFlag_RTOF(RTCx);
439 if (timeout == 0U)
441 status = ERROR;
444 return status;
448 * @brief Set the Time Counter
449 * @param RTCx RTC Instance
450 * @param TimeCounter this value can be from 0 to 0xFFFFFFFF
451 * @retval An ErrorStatus enumeration value:
452 * - SUCCESS: RTC Counter register configured
453 * - ERROR: Not applicable
455 ErrorStatus LL_RTC_TIME_SetCounter(RTC_TypeDef *RTCx, uint32_t TimeCounter)
457 ErrorStatus status = ERROR;
458 /* Check the parameter */
459 assert_param(IS_RTC_ALL_INSTANCE(RTCx));
461 /* Enter Initialization mode */
462 if (LL_RTC_EnterInitMode(RTCx) != ERROR)
464 LL_RTC_TIME_Set(RTCx, TimeCounter);
465 status = SUCCESS;
467 /* Exit Initialization mode */
468 LL_RTC_ExitInitMode(RTCx);
470 return status;
474 * @brief Set Alarm Counter.
475 * @param RTCx RTC Instance
476 * @param AlarmCounter this value can be from 0 to 0xFFFFFFFF
477 * @retval An ErrorStatus enumeration value:
478 * - SUCCESS: RTC exited from in Init mode
479 * - ERROR: Not applicable
481 ErrorStatus LL_RTC_ALARM_SetCounter(RTC_TypeDef *RTCx, uint32_t AlarmCounter)
483 ErrorStatus status = ERROR;
484 /* Check the parameter */
485 assert_param(IS_RTC_ALL_INSTANCE(RTCx));
487 /* Enter Initialization mode */
488 if (LL_RTC_EnterInitMode(RTCx) != ERROR)
490 LL_RTC_ALARM_Set(RTCx, AlarmCounter);
491 status = SUCCESS;
493 /* Exit Initialization mode */
494 LL_RTC_ExitInitMode(RTCx);
496 return status;
500 * @brief Waits until the RTC registers are synchronized with RTC APB clock.
501 * @note The RTC Resynchronization mode is write protected, use the
502 * @ref LL_RTC_DisableWriteProtection before calling this function.
503 * @param RTCx RTC Instance
504 * @retval An ErrorStatus enumeration value:
505 * - SUCCESS: RTC registers are synchronised
506 * - ERROR: RTC registers are not synchronised
508 ErrorStatus LL_RTC_WaitForSynchro(RTC_TypeDef *RTCx)
510 __IO uint32_t timeout = RTC_SYNCHRO_TIMEOUT;
511 ErrorStatus status = SUCCESS;
512 uint32_t tmp = 0U;
514 /* Check the parameter */
515 assert_param(IS_RTC_ALL_INSTANCE(RTCx));
517 /* Clear RSF flag */
518 LL_RTC_ClearFlag_RS(RTCx);
520 /* Wait the registers to be synchronised */
521 tmp = LL_RTC_IsActiveFlag_RS(RTCx);
522 while ((timeout != 0U) && (tmp != 0U))
524 if (LL_SYSTICK_IsActiveCounterFlag() == 1U)
526 timeout--;
528 tmp = LL_RTC_IsActiveFlag_RS(RTCx);
529 if (timeout == 0U)
531 status = ERROR;
535 return (status);
539 * @}
543 * @}
547 * @}
550 #endif /* defined(RTC) */
553 * @}
556 #endif /* USE_FULL_LL_DRIVER */
558 /************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/