2 ******************************************************************************
3 * @file stm32f7xx_ll_lptim.h
4 * @author MCD Application Team
5 * @brief Header file of LPTIM LL module.
6 ******************************************************************************
9 * <h2><center>© Copyright (c) 2017 STMicroelectronics.
10 * All rights reserved.</center></h2>
12 * This software component is licensed by ST under BSD 3-Clause license,
13 * the "License"; You may not use this file except in compliance with the
14 * License. You may obtain a copy of the License at:
15 * opensource.org/licenses/BSD-3-Clause
17 ******************************************************************************
20 /* Define to prevent recursive inclusion -------------------------------------*/
21 #ifndef __STM32F7xx_LL_LPTIM_H
22 #define __STM32F7xx_LL_LPTIM_H
28 /* Includes ------------------------------------------------------------------*/
29 #include "stm32f7xx.h"
31 /** @addtogroup STM32F7xx_LL_Driver
36 /** @defgroup LPTIM_LL LPTIM
40 /* Private types -------------------------------------------------------------*/
41 /* Private variables ---------------------------------------------------------*/
43 /* Private constants ---------------------------------------------------------*/
45 /* Private macros ------------------------------------------------------------*/
46 #if defined(USE_FULL_LL_DRIVER)
47 /** @defgroup LPTIM_LL_Private_Macros LPTIM Private Macros
53 #endif /*USE_FULL_LL_DRIVER*/
55 /* Exported types ------------------------------------------------------------*/
56 #if defined(USE_FULL_LL_DRIVER)
57 /** @defgroup LPTIM_LL_ES_INIT LPTIM Exported Init structure
62 * @brief LPTIM Init structure definition
66 uint32_t ClockSource
; /*!< Specifies the source of the clock used by the LPTIM instance.
67 This parameter can be a value of @ref LPTIM_LL_EC_CLK_SOURCE.
69 This feature can be modified afterwards using unitary function @ref LL_LPTIM_SetClockSource().*/
71 uint32_t Prescaler
; /*!< Specifies the prescaler division ratio.
72 This parameter can be a value of @ref LPTIM_LL_EC_PRESCALER.
74 This feature can be modified afterwards using using unitary function @ref LL_LPTIM_SetPrescaler().*/
76 uint32_t Waveform
; /*!< Specifies the waveform shape.
77 This parameter can be a value of @ref LPTIM_LL_EC_OUTPUT_WAVEFORM.
79 This feature can be modified afterwards using unitary function @ref LL_LPTIM_ConfigOutput().*/
81 uint32_t Polarity
; /*!< Specifies waveform polarity.
82 This parameter can be a value of @ref LPTIM_LL_EC_OUTPUT_POLARITY.
84 This feature can be modified afterwards using unitary function @ref LL_LPTIM_ConfigOutput().*/
85 } LL_LPTIM_InitTypeDef
;
90 #endif /* USE_FULL_LL_DRIVER */
92 /* Exported constants --------------------------------------------------------*/
93 /** @defgroup LPTIM_LL_Exported_Constants LPTIM Exported Constants
97 /** @defgroup LPTIM_LL_EC_GET_FLAG Get Flags Defines
98 * @brief Flags defines which can be used with LL_LPTIM_ReadReg function
101 #define LL_LPTIM_ISR_CMPM LPTIM_ISR_CMPM /*!< Compare match */
102 #define LL_LPTIM_ISR_ARRM LPTIM_ISR_ARRM /*!< Autoreload match */
103 #define LL_LPTIM_ISR_EXTTRIG LPTIM_ISR_EXTTRIG /*!< External trigger edge event */
104 #define LL_LPTIM_ISR_CMPOK LPTIM_ISR_CMPOK /*!< Compare register update OK */
105 #define LL_LPTIM_ISR_ARROK LPTIM_ISR_ARROK /*!< Autoreload register update OK */
106 #define LL_LPTIM_ISR_UP LPTIM_ISR_UP /*!< Counter direction change down to up */
107 #define LL_LPTIM_ISR_DOWN LPTIM_ISR_DOWN /*!< Counter direction change up to down */
112 /** @defgroup LPTIM_LL_EC_IT IT Defines
113 * @brief IT defines which can be used with LL_LPTIM_ReadReg and LL_LPTIM_WriteReg functions
116 #define LL_LPTIM_IER_CMPMIE LPTIM_IER_CMPMIE /*!< Compare match Interrupt Enable */
117 #define LL_LPTIM_IER_ARRMIE LPTIM_IER_ARRMIE /*!< Autoreload match Interrupt Enable */
118 #define LL_LPTIM_IER_EXTTRIGIE LPTIM_IER_EXTTRIGIE /*!< External trigger valid edge Interrupt Enable */
119 #define LL_LPTIM_IER_CMPOKIE LPTIM_IER_CMPOKIE /*!< Compare register update OK Interrupt Enable */
120 #define LL_LPTIM_IER_ARROKIE LPTIM_IER_ARROKIE /*!< Autoreload register update OK Interrupt Enable */
121 #define LL_LPTIM_IER_UPIE LPTIM_IER_UPIE /*!< Direction change to UP Interrupt Enable */
122 #define LL_LPTIM_IER_DOWNIE LPTIM_IER_DOWNIE /*!< Direction change to down Interrupt Enable */
127 /** @defgroup LPTIM_LL_EC_OPERATING_MODE Operating Mode
130 #define LL_LPTIM_OPERATING_MODE_CONTINUOUS LPTIM_CR_CNTSTRT /*!<LP Timer starts in continuous mode*/
131 #define LL_LPTIM_OPERATING_MODE_ONESHOT LPTIM_CR_SNGSTRT /*!<LP Tilmer starts in single mode*/
136 /** @defgroup LPTIM_LL_EC_UPDATE_MODE Update Mode
139 #define LL_LPTIM_UPDATE_MODE_IMMEDIATE 0x00000000U /*!<Preload is disabled: registers are updated after each APB bus write access*/
140 #define LL_LPTIM_UPDATE_MODE_ENDOFPERIOD LPTIM_CFGR_PRELOAD /*!<preload is enabled: registers are updated at the end of the current LPTIM period*/
145 /** @defgroup LPTIM_LL_EC_COUNTER_MODE Counter Mode
148 #define LL_LPTIM_COUNTER_MODE_INTERNAL 0x00000000U /*!<The counter is incremented following each internal clock pulse*/
149 #define LL_LPTIM_COUNTER_MODE_EXTERNAL LPTIM_CFGR_COUNTMODE /*!<The counter is incremented following each valid clock pulse on the LPTIM external Input1*/
154 /** @defgroup LPTIM_LL_EC_OUTPUT_WAVEFORM Output Waveform Type
157 #define LL_LPTIM_OUTPUT_WAVEFORM_PWM 0x00000000U /*!<LPTIM generates either a PWM waveform or a One pulse waveform depending on chosen operating mode CONTINOUS or SINGLE*/
158 #define LL_LPTIM_OUTPUT_WAVEFORM_SETONCE LPTIM_CFGR_WAVE /*!<LPTIM generates a Set Once waveform*/
163 /** @defgroup LPTIM_LL_EC_OUTPUT_POLARITY Output Polarity
166 #define LL_LPTIM_OUTPUT_POLARITY_REGULAR 0x00000000U /*!<The LPTIM output reflects the compare results between LPTIMx_ARR and LPTIMx_CMP registers*/
167 #define LL_LPTIM_OUTPUT_POLARITY_INVERSE LPTIM_CFGR_WAVPOL /*!<The LPTIM output reflects the inverse of the compare results between LPTIMx_ARR and LPTIMx_CMP registers*/
172 /** @defgroup LPTIM_LL_EC_PRESCALER Prescaler Value
175 #define LL_LPTIM_PRESCALER_DIV1 0x00000000U /*!<Prescaler division factor is set to 1*/
176 #define LL_LPTIM_PRESCALER_DIV2 LPTIM_CFGR_PRESC_0 /*!<Prescaler division factor is set to 2*/
177 #define LL_LPTIM_PRESCALER_DIV4 LPTIM_CFGR_PRESC_1 /*!<Prescaler division factor is set to 4*/
178 #define LL_LPTIM_PRESCALER_DIV8 (LPTIM_CFGR_PRESC_1 | LPTIM_CFGR_PRESC_0) /*!<Prescaler division factor is set to 8*/
179 #define LL_LPTIM_PRESCALER_DIV16 LPTIM_CFGR_PRESC_2 /*!<Prescaler division factor is set to 16*/
180 #define LL_LPTIM_PRESCALER_DIV32 (LPTIM_CFGR_PRESC_2 | LPTIM_CFGR_PRESC_0) /*!<Prescaler division factor is set to 32*/
181 #define LL_LPTIM_PRESCALER_DIV64 (LPTIM_CFGR_PRESC_2 | LPTIM_CFGR_PRESC_1) /*!<Prescaler division factor is set to 64*/
182 #define LL_LPTIM_PRESCALER_DIV128 LPTIM_CFGR_PRESC /*!<Prescaler division factor is set to 128*/
187 /** @defgroup LPTIM_LL_EC_TRIG_SOURCE Trigger Source
190 #define LL_LPTIM_TRIG_SOURCE_GPIO 0x00000000U /*!<External input trigger is connected to TIMx_ETR input*/
191 #define LL_LPTIM_TRIG_SOURCE_RTCALARMA LPTIM_CFGR_TRIGSEL_0 /*!<External input trigger is connected to RTC Alarm A*/
192 #define LL_LPTIM_TRIG_SOURCE_RTCALARMB LPTIM_CFGR_TRIGSEL_1 /*!<External input trigger is connected to RTC Alarm B*/
193 #define LL_LPTIM_TRIG_SOURCE_RTCTAMP1 (LPTIM_CFGR_TRIGSEL_1 | LPTIM_CFGR_TRIGSEL_0) /*!<External input trigger is connected to RTC Tamper 1*/
194 #define LL_LPTIM_TRIG_SOURCE_RTCTAMP2 LPTIM_CFGR_TRIGSEL_2 /*!<External input trigger is connected to RTC Tamper 2*/
195 #define LL_LPTIM_TRIG_SOURCE_RTCTAMP3 (LPTIM_CFGR_TRIGSEL_2 | LPTIM_CFGR_TRIGSEL_0) /*!<External input trigger is connected to RTC Tamper 3*/
196 #define LL_LPTIM_TRIG_SOURCE_COMP1 (LPTIM_CFGR_TRIGSEL_2 | LPTIM_CFGR_TRIGSEL_1) /*!<External input trigger is connected to COMP1 output*/
197 #define LL_LPTIM_TRIG_SOURCE_COMP2 LPTIM_CFGR_TRIGSEL /*!<External input trigger is connected to COMP2 output*/
202 /** @defgroup LPTIM_LL_EC_TRIG_FILTER Trigger Filter
205 #define LL_LPTIM_TRIG_FILTER_NONE 0x00000000U /*!<Any trigger active level change is considered as a valid trigger*/
206 #define LL_LPTIM_TRIG_FILTER_2 LPTIM_CFGR_TRGFLT_0 /*!<Trigger active level change must be stable for at least 2 clock periods before it is considered as valid trigger*/
207 #define LL_LPTIM_TRIG_FILTER_4 LPTIM_CFGR_TRGFLT_1 /*!<Trigger active level change must be stable for at least 4 clock periods before it is considered as valid trigger*/
208 #define LL_LPTIM_TRIG_FILTER_8 LPTIM_CFGR_TRGFLT /*!<Trigger active level change must be stable for at least 8 clock periods before it is considered as valid trigger*/
213 /** @defgroup LPTIM_LL_EC_TRIG_POLARITY Trigger Polarity
216 #define LL_LPTIM_TRIG_POLARITY_RISING LPTIM_CFGR_TRIGEN_0 /*!<LPTIM counter starts when a rising edge is detected*/
217 #define LL_LPTIM_TRIG_POLARITY_FALLING LPTIM_CFGR_TRIGEN_1 /*!<LPTIM counter starts when a falling edge is detected*/
218 #define LL_LPTIM_TRIG_POLARITY_RISING_FALLING LPTIM_CFGR_TRIGEN /*!<LPTIM counter starts when a rising or a falling edge is detected*/
223 /** @defgroup LPTIM_LL_EC_CLK_SOURCE Clock Source
226 #define LL_LPTIM_CLK_SOURCE_INTERNAL 0x00000000U /*!<LPTIM is clocked by internal clock source (APB clock or any of the embedded oscillators)*/
227 #define LL_LPTIM_CLK_SOURCE_EXTERNAL LPTIM_CFGR_CKSEL /*!<LPTIM is clocked by an external clock source through the LPTIM external Input1*/
232 /** @defgroup LPTIM_LL_EC_CLK_FILTER Clock Filter
235 #define LL_LPTIM_CLK_FILTER_NONE 0x00000000U /*!<Any external clock signal level change is considered as a valid transition*/
236 #define LL_LPTIM_CLK_FILTER_2 LPTIM_CFGR_CKFLT_0 /*!<External clock signal level change must be stable for at least 2 clock periods before it is considered as valid transition*/
237 #define LL_LPTIM_CLK_FILTER_4 LPTIM_CFGR_CKFLT_1 /*!<External clock signal level change must be stable for at least 4 clock periods before it is considered as valid transition*/
238 #define LL_LPTIM_CLK_FILTER_8 LPTIM_CFGR_CKFLT /*!<External clock signal level change must be stable for at least 8 clock periods before it is considered as valid transition*/
243 /** @defgroup LPTIM_LL_EC_CLK_POLARITY Clock Polarity
246 #define LL_LPTIM_CLK_POLARITY_RISING 0x00000000U /*!< The rising edge is the active edge used for counting*/
247 #define LL_LPTIM_CLK_POLARITY_FALLING LPTIM_CFGR_CKPOL_0 /*!< The falling edge is the active edge used for counting*/
248 #define LL_LPTIM_CLK_POLARITY_RISING_FALLING LPTIM_CFGR_CKPOL_1 /*!< Both edges are active edges*/
253 /** @defgroup LPTIM_LL_EC_ENCODER_MODE Encoder Mode
256 #define LL_LPTIM_ENCODER_MODE_RISING 0x00000000U /*!< The rising edge is the active edge used for counting*/
257 #define LL_LPTIM_ENCODER_MODE_FALLING LPTIM_CFGR_CKPOL_0 /*!< The falling edge is the active edge used for counting*/
258 #define LL_LPTIM_ENCODER_MODE_RISING_FALLING LPTIM_CFGR_CKPOL_1 /*!< Both edges are active edges*/
268 /* Exported macro ------------------------------------------------------------*/
269 /** @defgroup LPTIM_LL_Exported_Macros LPTIM Exported Macros
273 /** @defgroup LPTIM_LL_EM_WRITE_READ Common Write and read registers Macros
278 * @brief Write a value in LPTIM register
279 * @param __INSTANCE__ LPTIM Instance
280 * @param __REG__ Register to be written
281 * @param __VALUE__ Value to be written in the register
284 #define LL_LPTIM_WriteReg(__INSTANCE__, __REG__, __VALUE__) WRITE_REG(__INSTANCE__->__REG__, (__VALUE__))
287 * @brief Read a value in LPTIM register
288 * @param __INSTANCE__ LPTIM Instance
289 * @param __REG__ Register to be read
290 * @retval Register value
292 #define LL_LPTIM_ReadReg(__INSTANCE__, __REG__) READ_REG(__INSTANCE__->__REG__)
302 /* Exported functions --------------------------------------------------------*/
303 /** @defgroup LPTIM_LL_Exported_Functions LPTIM Exported Functions
307 /** @defgroup LPTIM_LL_EF_LPTIM_Configuration LPTIM Configuration
312 * @brief Enable the LPTIM instance
313 * @note After setting the ENABLE bit, a delay of two counter clock is needed
314 * before the LPTIM instance is actually enabled.
315 * @rmtoll CR ENABLE LL_LPTIM_Enable
316 * @param LPTIMx Low-Power Timer instance
319 __STATIC_INLINE
void LL_LPTIM_Enable(LPTIM_TypeDef
*LPTIMx
)
321 SET_BIT(LPTIMx
->CR
, LPTIM_CR_ENABLE
);
325 * @brief Disable the LPTIM instance
326 * @rmtoll CR ENABLE LL_LPTIM_Disable
327 * @param LPTIMx Low-Power Timer instance
330 __STATIC_INLINE
void LL_LPTIM_Disable(LPTIM_TypeDef
*LPTIMx
)
332 CLEAR_BIT(LPTIMx
->CR
, LPTIM_CR_ENABLE
);
336 * @brief Indicates whether the LPTIM instance is enabled.
337 * @rmtoll CR ENABLE LL_LPTIM_IsEnabled
338 * @param LPTIMx Low-Power Timer instance
339 * @retval State of bit (1 or 0).
341 __STATIC_INLINE
uint32_t LL_LPTIM_IsEnabled(LPTIM_TypeDef
*LPTIMx
)
343 return (READ_BIT(LPTIMx
->CR
, LPTIM_CR_ENABLE
) == (LPTIM_CR_ENABLE
));
347 * @brief Starts the LPTIM counter in the desired mode.
348 * @note LPTIM instance must be enabled before starting the counter.
349 * @note It is possible to change on the fly from One Shot mode to
351 * @rmtoll CR CNTSTRT LL_LPTIM_StartCounter\n
352 * CR SNGSTRT LL_LPTIM_StartCounter
353 * @param LPTIMx Low-Power Timer instance
354 * @param OperatingMode This parameter can be one of the following values:
355 * @arg @ref LL_LPTIM_OPERATING_MODE_CONTINUOUS
356 * @arg @ref LL_LPTIM_OPERATING_MODE_ONESHOT
359 __STATIC_INLINE
void LL_LPTIM_StartCounter(LPTIM_TypeDef
*LPTIMx
, uint32_t OperatingMode
)
361 MODIFY_REG(LPTIMx
->CR
, LPTIM_CR_CNTSTRT
| LPTIM_CR_SNGSTRT
, OperatingMode
);
366 * @brief Set the LPTIM registers update mode (enable/disable register preload)
367 * @note This function must be called when the LPTIM instance is disabled.
368 * @rmtoll CFGR PRELOAD LL_LPTIM_SetUpdateMode
369 * @param LPTIMx Low-Power Timer instance
370 * @param UpdateMode This parameter can be one of the following values:
371 * @arg @ref LL_LPTIM_UPDATE_MODE_IMMEDIATE
372 * @arg @ref LL_LPTIM_UPDATE_MODE_ENDOFPERIOD
375 __STATIC_INLINE
void LL_LPTIM_SetUpdateMode(LPTIM_TypeDef
*LPTIMx
, uint32_t UpdateMode
)
377 MODIFY_REG(LPTIMx
->CFGR
, LPTIM_CFGR_PRELOAD
, UpdateMode
);
381 * @brief Get the LPTIM registers update mode
382 * @rmtoll CFGR PRELOAD LL_LPTIM_GetUpdateMode
383 * @param LPTIMx Low-Power Timer instance
384 * @retval Returned value can be one of the following values:
385 * @arg @ref LL_LPTIM_UPDATE_MODE_IMMEDIATE
386 * @arg @ref LL_LPTIM_UPDATE_MODE_ENDOFPERIOD
388 __STATIC_INLINE
uint32_t LL_LPTIM_GetUpdateMode(LPTIM_TypeDef
*LPTIMx
)
390 return (uint32_t)(READ_BIT(LPTIMx
->CFGR
, LPTIM_CFGR_PRELOAD
));
394 * @brief Set the auto reload value
395 * @note The LPTIMx_ARR register content must only be modified when the LPTIM is enabled
396 * @note After a write to the LPTIMx_ARR register a new write operation to the
397 * same register can only be performed when the previous write operation
398 * is completed. Any successive write before the ARROK flag be set, will
399 * lead to unpredictable results.
400 * @note autoreload value be strictly greater than the compare value.
401 * @rmtoll ARR ARR LL_LPTIM_SetAutoReload
402 * @param LPTIMx Low-Power Timer instance
403 * @param AutoReload Value between Min_Data=0x00 and Max_Data=0xFFFF
406 __STATIC_INLINE
void LL_LPTIM_SetAutoReload(LPTIM_TypeDef
*LPTIMx
, uint32_t AutoReload
)
408 MODIFY_REG(LPTIMx
->ARR
, LPTIM_ARR_ARR
, AutoReload
);
412 * @brief Get actual auto reload value
413 * @rmtoll ARR ARR LL_LPTIM_GetAutoReload
414 * @param LPTIMx Low-Power Timer instance
415 * @retval AutoReload Value between Min_Data=0x00 and Max_Data=0xFFFF
417 __STATIC_INLINE
uint32_t LL_LPTIM_GetAutoReload(LPTIM_TypeDef
*LPTIMx
)
419 return (uint32_t)(READ_BIT(LPTIMx
->ARR
, LPTIM_ARR_ARR
));
423 * @brief Set the compare value
424 * @note After a write to the LPTIMx_CMP register a new write operation to the
425 * same register can only be performed when the previous write operation
426 * is completed. Any successive write before the CMPOK flag be set, will
427 * lead to unpredictable results.
428 * @rmtoll CMP CMP LL_LPTIM_SetCompare
429 * @param LPTIMx Low-Power Timer instance
430 * @param CompareValue Value between Min_Data=0x00 and Max_Data=0xFFFF
433 __STATIC_INLINE
void LL_LPTIM_SetCompare(LPTIM_TypeDef
*LPTIMx
, uint32_t CompareValue
)
435 MODIFY_REG(LPTIMx
->CMP
, LPTIM_CMP_CMP
, CompareValue
);
439 * @brief Get actual compare value
440 * @rmtoll CMP CMP LL_LPTIM_GetCompare
441 * @param LPTIMx Low-Power Timer instance
442 * @retval CompareValue Value between Min_Data=0x00 and Max_Data=0xFFFF
444 __STATIC_INLINE
uint32_t LL_LPTIM_GetCompare(LPTIM_TypeDef
*LPTIMx
)
446 return (uint32_t)(READ_BIT(LPTIMx
->CMP
, LPTIM_CMP_CMP
));
450 * @brief Get actual counter value
451 * @note When the LPTIM instance is running with an asynchronous clock, reading
452 * the LPTIMx_CNT register may return unreliable values. So in this case
453 * it is necessary to perform two consecutive read accesses and verify
454 * that the two returned values are identical.
455 * @rmtoll CNT CNT LL_LPTIM_GetCounter
456 * @param LPTIMx Low-Power Timer instance
457 * @retval Counter value
459 __STATIC_INLINE
uint32_t LL_LPTIM_GetCounter(LPTIM_TypeDef
*LPTIMx
)
461 return (uint32_t)(READ_BIT(LPTIMx
->CNT
, LPTIM_CNT_CNT
));
465 * @brief Set the counter mode (selection of the LPTIM counter clock source).
466 * @note The counter mode can be set only when the LPTIM instance is disabled.
467 * @rmtoll CFGR COUNTMODE LL_LPTIM_SetCounterMode
468 * @param LPTIMx Low-Power Timer instance
469 * @param CounterMode This parameter can be one of the following values:
470 * @arg @ref LL_LPTIM_COUNTER_MODE_INTERNAL
471 * @arg @ref LL_LPTIM_COUNTER_MODE_EXTERNAL
474 __STATIC_INLINE
void LL_LPTIM_SetCounterMode(LPTIM_TypeDef
*LPTIMx
, uint32_t CounterMode
)
476 MODIFY_REG(LPTIMx
->CFGR
, LPTIM_CFGR_COUNTMODE
, CounterMode
);
480 * @brief Get the counter mode
481 * @rmtoll CFGR COUNTMODE LL_LPTIM_GetCounterMode
482 * @param LPTIMx Low-Power Timer instance
483 * @retval Returned value can be one of the following values:
484 * @arg @ref LL_LPTIM_COUNTER_MODE_INTERNAL
485 * @arg @ref LL_LPTIM_COUNTER_MODE_EXTERNAL
487 __STATIC_INLINE
uint32_t LL_LPTIM_GetCounterMode(LPTIM_TypeDef
*LPTIMx
)
489 return (uint32_t)(READ_BIT(LPTIMx
->CFGR
, LPTIM_CFGR_COUNTMODE
));
493 * @brief Configure the LPTIM instance output (LPTIMx_OUT)
494 * @note This function must be called when the LPTIM instance is disabled.
495 * @note Regarding the LPTIM output polarity the change takes effect
496 * immediately, so the output default value will change immediately after
497 * the polarity is re-configured, even before the timer is enabled.
498 * @rmtoll CFGR WAVE LL_LPTIM_ConfigOutput\n
499 * CFGR WAVPOL LL_LPTIM_ConfigOutput
500 * @param LPTIMx Low-Power Timer instance
501 * @param Waveform This parameter can be one of the following values:
502 * @arg @ref LL_LPTIM_OUTPUT_WAVEFORM_PWM
503 * @arg @ref LL_LPTIM_OUTPUT_WAVEFORM_SETONCE
504 * @param Polarity This parameter can be one of the following values:
505 * @arg @ref LL_LPTIM_OUTPUT_POLARITY_REGULAR
506 * @arg @ref LL_LPTIM_OUTPUT_POLARITY_INVERSE
509 __STATIC_INLINE
void LL_LPTIM_ConfigOutput(LPTIM_TypeDef
*LPTIMx
, uint32_t Waveform
, uint32_t Polarity
)
511 MODIFY_REG(LPTIMx
->CFGR
, LPTIM_CFGR_WAVE
| LPTIM_CFGR_WAVPOL
, Waveform
| Polarity
);
515 * @brief Set waveform shape
516 * @rmtoll CFGR WAVE LL_LPTIM_SetWaveform
517 * @param LPTIMx Low-Power Timer instance
518 * @param Waveform This parameter can be one of the following values:
519 * @arg @ref LL_LPTIM_OUTPUT_WAVEFORM_PWM
520 * @arg @ref LL_LPTIM_OUTPUT_WAVEFORM_SETONCE
523 __STATIC_INLINE
void LL_LPTIM_SetWaveform(LPTIM_TypeDef
*LPTIMx
, uint32_t Waveform
)
525 MODIFY_REG(LPTIMx
->CFGR
, LPTIM_CFGR_WAVE
, Waveform
);
529 * @brief Get actual waveform shape
530 * @rmtoll CFGR WAVE LL_LPTIM_GetWaveform
531 * @param LPTIMx Low-Power Timer instance
532 * @retval Returned value can be one of the following values:
533 * @arg @ref LL_LPTIM_OUTPUT_WAVEFORM_PWM
534 * @arg @ref LL_LPTIM_OUTPUT_WAVEFORM_SETONCE
536 __STATIC_INLINE
uint32_t LL_LPTIM_GetWaveform(LPTIM_TypeDef
*LPTIMx
)
538 return (uint32_t)(READ_BIT(LPTIMx
->CFGR
, LPTIM_CFGR_WAVE
));
542 * @brief Set output polarity
543 * @rmtoll CFGR WAVPOL LL_LPTIM_SetPolarity
544 * @param LPTIMx Low-Power Timer instance
545 * @param Polarity This parameter can be one of the following values:
546 * @arg @ref LL_LPTIM_OUTPUT_POLARITY_REGULAR
547 * @arg @ref LL_LPTIM_OUTPUT_POLARITY_INVERSE
550 __STATIC_INLINE
void LL_LPTIM_SetPolarity(LPTIM_TypeDef
*LPTIMx
, uint32_t Polarity
)
552 MODIFY_REG(LPTIMx
->CFGR
, LPTIM_CFGR_WAVPOL
, Polarity
);
556 * @brief Get actual output polarity
557 * @rmtoll CFGR WAVPOL LL_LPTIM_GetPolarity
558 * @param LPTIMx Low-Power Timer instance
559 * @retval Returned value can be one of the following values:
560 * @arg @ref LL_LPTIM_OUTPUT_POLARITY_REGULAR
561 * @arg @ref LL_LPTIM_OUTPUT_POLARITY_INVERSE
563 __STATIC_INLINE
uint32_t LL_LPTIM_GetPolarity(LPTIM_TypeDef
*LPTIMx
)
565 return (uint32_t)(READ_BIT(LPTIMx
->CFGR
, LPTIM_CFGR_WAVPOL
));
569 * @brief Set actual prescaler division ratio.
570 * @note This function must be called when the LPTIM instance is disabled.
571 * @note When the LPTIM is configured to be clocked by an internal clock source
572 * and the LPTIM counter is configured to be updated by active edges
573 * detected on the LPTIM external Input1, the internal clock provided to
574 * the LPTIM must be not be prescaled.
575 * @rmtoll CFGR PRESC LL_LPTIM_SetPrescaler
576 * @param LPTIMx Low-Power Timer instance
577 * @param Prescaler This parameter can be one of the following values:
578 * @arg @ref LL_LPTIM_PRESCALER_DIV1
579 * @arg @ref LL_LPTIM_PRESCALER_DIV2
580 * @arg @ref LL_LPTIM_PRESCALER_DIV4
581 * @arg @ref LL_LPTIM_PRESCALER_DIV8
582 * @arg @ref LL_LPTIM_PRESCALER_DIV16
583 * @arg @ref LL_LPTIM_PRESCALER_DIV32
584 * @arg @ref LL_LPTIM_PRESCALER_DIV64
585 * @arg @ref LL_LPTIM_PRESCALER_DIV128
588 __STATIC_INLINE
void LL_LPTIM_SetPrescaler(LPTIM_TypeDef
*LPTIMx
, uint32_t Prescaler
)
590 MODIFY_REG(LPTIMx
->CFGR
, LPTIM_CFGR_PRESC
, Prescaler
);
594 * @brief Get actual prescaler division ratio.
595 * @rmtoll CFGR PRESC LL_LPTIM_GetPrescaler
596 * @param LPTIMx Low-Power Timer instance
597 * @retval Returned value can be one of the following values:
598 * @arg @ref LL_LPTIM_PRESCALER_DIV1
599 * @arg @ref LL_LPTIM_PRESCALER_DIV2
600 * @arg @ref LL_LPTIM_PRESCALER_DIV4
601 * @arg @ref LL_LPTIM_PRESCALER_DIV8
602 * @arg @ref LL_LPTIM_PRESCALER_DIV16
603 * @arg @ref LL_LPTIM_PRESCALER_DIV32
604 * @arg @ref LL_LPTIM_PRESCALER_DIV64
605 * @arg @ref LL_LPTIM_PRESCALER_DIV128
607 __STATIC_INLINE
uint32_t LL_LPTIM_GetPrescaler(LPTIM_TypeDef
*LPTIMx
)
609 return (uint32_t)(READ_BIT(LPTIMx
->CFGR
, LPTIM_CFGR_PRESC
));
617 /** @defgroup LPTIM_LL_EF_Trigger_Configuration Trigger Configuration
622 * @brief Enable the timeout function
623 * @note This function must be called when the LPTIM instance is disabled.
624 * @note The first trigger event will start the timer, any successive trigger
625 * event will reset the counter and the timer will restart.
626 * @note The timeout value corresponds to the compare value; if no trigger
627 * occurs within the expected time frame, the MCU is waked-up by the
628 * compare match event.
629 * @rmtoll CFGR TIMOUT LL_LPTIM_EnableTimeout
630 * @param LPTIMx Low-Power Timer instance
633 __STATIC_INLINE
void LL_LPTIM_EnableTimeout(LPTIM_TypeDef
*LPTIMx
)
635 SET_BIT(LPTIMx
->CFGR
, LPTIM_CFGR_TIMOUT
);
639 * @brief Disable the timeout function
640 * @note This function must be called when the LPTIM instance is disabled.
641 * @note A trigger event arriving when the timer is already started will be
643 * @rmtoll CFGR TIMOUT LL_LPTIM_DisableTimeout
644 * @param LPTIMx Low-Power Timer instance
647 __STATIC_INLINE
void LL_LPTIM_DisableTimeout(LPTIM_TypeDef
*LPTIMx
)
649 CLEAR_BIT(LPTIMx
->CFGR
, LPTIM_CFGR_TIMOUT
);
653 * @brief Indicate whether the timeout function is enabled.
654 * @rmtoll CFGR TIMOUT LL_LPTIM_IsEnabledTimeout
655 * @param LPTIMx Low-Power Timer instance
656 * @retval State of bit (1 or 0).
658 __STATIC_INLINE
uint32_t LL_LPTIM_IsEnabledTimeout(LPTIM_TypeDef
*LPTIMx
)
660 return (READ_BIT(LPTIMx
->CFGR
, LPTIM_CFGR_TIMOUT
) == (LPTIM_CFGR_TIMOUT
));
664 * @brief Start the LPTIM counter
665 * @note This function must be called when the LPTIM instance is disabled.
666 * @rmtoll CFGR TRIGEN LL_LPTIM_TrigSw
667 * @param LPTIMx Low-Power Timer instance
670 __STATIC_INLINE
void LL_LPTIM_TrigSw(LPTIM_TypeDef
*LPTIMx
)
672 CLEAR_BIT(LPTIMx
->CFGR
, LPTIM_CFGR_TRIGEN
);
676 * @brief Configure the external trigger used as a trigger event for the LPTIM.
677 * @note This function must be called when the LPTIM instance is disabled.
678 * @note An internal clock source must be present when a digital filter is
679 * required for the trigger.
680 * @rmtoll CFGR TRIGSEL LL_LPTIM_ConfigTrigger\n
681 * CFGR TRGFLT LL_LPTIM_ConfigTrigger\n
682 * CFGR TRIGEN LL_LPTIM_ConfigTrigger
683 * @param LPTIMx Low-Power Timer instance
684 * @param Source This parameter can be one of the following values:
685 * @arg @ref LL_LPTIM_TRIG_SOURCE_GPIO
686 * @arg @ref LL_LPTIM_TRIG_SOURCE_RTCALARMA
687 * @arg @ref LL_LPTIM_TRIG_SOURCE_RTCALARMB
688 * @arg @ref LL_LPTIM_TRIG_SOURCE_RTCTAMP1
689 * @arg @ref LL_LPTIM_TRIG_SOURCE_RTCTAMP2
690 * @arg @ref LL_LPTIM_TRIG_SOURCE_RTCTAMP3
691 * @arg @ref LL_LPTIM_TRIG_SOURCE_COMP1
692 * @arg @ref LL_LPTIM_TRIG_SOURCE_COMP2
693 * @param Filter This parameter can be one of the following values:
694 * @arg @ref LL_LPTIM_TRIG_FILTER_NONE
695 * @arg @ref LL_LPTIM_TRIG_FILTER_2
696 * @arg @ref LL_LPTIM_TRIG_FILTER_4
697 * @arg @ref LL_LPTIM_TRIG_FILTER_8
698 * @param Polarity This parameter can be one of the following values:
699 * @arg @ref LL_LPTIM_TRIG_POLARITY_RISING
700 * @arg @ref LL_LPTIM_TRIG_POLARITY_FALLING
701 * @arg @ref LL_LPTIM_TRIG_POLARITY_RISING_FALLING
704 __STATIC_INLINE
void LL_LPTIM_ConfigTrigger(LPTIM_TypeDef
*LPTIMx
, uint32_t Source
, uint32_t Filter
, uint32_t Polarity
)
706 MODIFY_REG(LPTIMx
->CFGR
, LPTIM_CFGR_TRIGSEL
| LPTIM_CFGR_TRGFLT
| LPTIM_CFGR_TRIGEN
, Source
| Filter
| Polarity
);
710 * @brief Get actual external trigger source.
711 * @rmtoll CFGR TRIGSEL LL_LPTIM_GetTriggerSource
712 * @param LPTIMx Low-Power Timer instance
713 * @retval Returned value can be one of the following values:
714 * @arg @ref LL_LPTIM_TRIG_SOURCE_GPIO
715 * @arg @ref LL_LPTIM_TRIG_SOURCE_RTCALARMA
716 * @arg @ref LL_LPTIM_TRIG_SOURCE_RTCALARMB
717 * @arg @ref LL_LPTIM_TRIG_SOURCE_RTCTAMP1
718 * @arg @ref LL_LPTIM_TRIG_SOURCE_RTCTAMP2
719 * @arg @ref LL_LPTIM_TRIG_SOURCE_RTCTAMP3
720 * @arg @ref LL_LPTIM_TRIG_SOURCE_COMP1
721 * @arg @ref LL_LPTIM_TRIG_SOURCE_COMP2
723 __STATIC_INLINE
uint32_t LL_LPTIM_GetTriggerSource(LPTIM_TypeDef
*LPTIMx
)
725 return (uint32_t)(READ_BIT(LPTIMx
->CFGR
, LPTIM_CFGR_TRIGSEL
));
729 * @brief Get actual external trigger filter.
730 * @rmtoll CFGR TRGFLT LL_LPTIM_GetTriggerFilter
731 * @param LPTIMx Low-Power Timer instance
732 * @retval Returned value can be one of the following values:
733 * @arg @ref LL_LPTIM_TRIG_FILTER_NONE
734 * @arg @ref LL_LPTIM_TRIG_FILTER_2
735 * @arg @ref LL_LPTIM_TRIG_FILTER_4
736 * @arg @ref LL_LPTIM_TRIG_FILTER_8
738 __STATIC_INLINE
uint32_t LL_LPTIM_GetTriggerFilter(LPTIM_TypeDef
*LPTIMx
)
740 return (uint32_t)(READ_BIT(LPTIMx
->CFGR
, LPTIM_CFGR_TRGFLT
));
744 * @brief Get actual external trigger polarity.
745 * @rmtoll CFGR TRIGEN LL_LPTIM_GetTriggerPolarity
746 * @param LPTIMx Low-Power Timer instance
747 * @retval Returned value can be one of the following values:
748 * @arg @ref LL_LPTIM_TRIG_POLARITY_RISING
749 * @arg @ref LL_LPTIM_TRIG_POLARITY_FALLING
750 * @arg @ref LL_LPTIM_TRIG_POLARITY_RISING_FALLING
752 __STATIC_INLINE
uint32_t LL_LPTIM_GetTriggerPolarity(LPTIM_TypeDef
*LPTIMx
)
754 return (uint32_t)(READ_BIT(LPTIMx
->CFGR
, LPTIM_CFGR_TRIGEN
));
761 /** @defgroup LPTIM_LL_EF_Clock_Configuration Clock Configuration
766 * @brief Set the source of the clock used by the LPTIM instance.
767 * @note This function must be called when the LPTIM instance is disabled.
768 * @rmtoll CFGR CKSEL LL_LPTIM_SetClockSource
769 * @param LPTIMx Low-Power Timer instance
770 * @param ClockSource This parameter can be one of the following values:
771 * @arg @ref LL_LPTIM_CLK_SOURCE_INTERNAL
772 * @arg @ref LL_LPTIM_CLK_SOURCE_EXTERNAL
775 __STATIC_INLINE
void LL_LPTIM_SetClockSource(LPTIM_TypeDef
*LPTIMx
, uint32_t ClockSource
)
777 MODIFY_REG(LPTIMx
->CFGR
, LPTIM_CFGR_CKSEL
, ClockSource
);
781 * @brief Get actual LPTIM instance clock source.
782 * @rmtoll CFGR CKSEL LL_LPTIM_GetClockSource
783 * @param LPTIMx Low-Power Timer instance
784 * @retval Returned value can be one of the following values:
785 * @arg @ref LL_LPTIM_CLK_SOURCE_INTERNAL
786 * @arg @ref LL_LPTIM_CLK_SOURCE_EXTERNAL
788 __STATIC_INLINE
uint32_t LL_LPTIM_GetClockSource(LPTIM_TypeDef
*LPTIMx
)
790 return (uint32_t)(READ_BIT(LPTIMx
->CFGR
, LPTIM_CFGR_CKSEL
));
794 * @brief Configure the active edge or edges used by the counter when the LPTIM is clocked by an external clock source.
795 * @note This function must be called when the LPTIM instance is disabled.
796 * @note When both external clock signal edges are considered active ones,
797 * the LPTIM must also be clocked by an internal clock source with a
798 * frequency equal to at least four times the external clock frequency.
799 * @note An internal clock source must be present when a digital filter is
800 * required for external clock.
801 * @rmtoll CFGR CKFLT LL_LPTIM_ConfigClock\n
802 * CFGR CKPOL LL_LPTIM_ConfigClock
803 * @param LPTIMx Low-Power Timer instance
804 * @param ClockFilter This parameter can be one of the following values:
805 * @arg @ref LL_LPTIM_CLK_FILTER_NONE
806 * @arg @ref LL_LPTIM_CLK_FILTER_2
807 * @arg @ref LL_LPTIM_CLK_FILTER_4
808 * @arg @ref LL_LPTIM_CLK_FILTER_8
809 * @param ClockPolarity This parameter can be one of the following values:
810 * @arg @ref LL_LPTIM_CLK_POLARITY_RISING
811 * @arg @ref LL_LPTIM_CLK_POLARITY_FALLING
812 * @arg @ref LL_LPTIM_CLK_POLARITY_RISING_FALLING
815 __STATIC_INLINE
void LL_LPTIM_ConfigClock(LPTIM_TypeDef
*LPTIMx
, uint32_t ClockFilter
, uint32_t ClockPolarity
)
817 MODIFY_REG(LPTIMx
->CFGR
, LPTIM_CFGR_CKFLT
| LPTIM_CFGR_CKPOL
, ClockFilter
| ClockPolarity
);
821 * @brief Get actual clock polarity
822 * @rmtoll CFGR CKPOL LL_LPTIM_GetClockPolarity
823 * @param LPTIMx Low-Power Timer instance
824 * @retval Returned value can be one of the following values:
825 * @arg @ref LL_LPTIM_CLK_POLARITY_RISING
826 * @arg @ref LL_LPTIM_CLK_POLARITY_FALLING
827 * @arg @ref LL_LPTIM_CLK_POLARITY_RISING_FALLING
829 __STATIC_INLINE
uint32_t LL_LPTIM_GetClockPolarity(LPTIM_TypeDef
*LPTIMx
)
831 return (uint32_t)(READ_BIT(LPTIMx
->CFGR
, LPTIM_CFGR_CKPOL
));
835 * @brief Get actual clock digital filter
836 * @rmtoll CFGR CKFLT LL_LPTIM_GetClockFilter
837 * @param LPTIMx Low-Power Timer instance
838 * @retval Returned value can be one of the following values:
839 * @arg @ref LL_LPTIM_CLK_FILTER_NONE
840 * @arg @ref LL_LPTIM_CLK_FILTER_2
841 * @arg @ref LL_LPTIM_CLK_FILTER_4
842 * @arg @ref LL_LPTIM_CLK_FILTER_8
844 __STATIC_INLINE
uint32_t LL_LPTIM_GetClockFilter(LPTIM_TypeDef
*LPTIMx
)
846 return (uint32_t)(READ_BIT(LPTIMx
->CFGR
, LPTIM_CFGR_CKFLT
));
853 /** @defgroup LPTIM_LL_EF_Encoder_Mode Encoder Mode
858 * @brief Configure the encoder mode.
859 * @note This function must be called when the LPTIM instance is disabled.
860 * @rmtoll CFGR CKPOL LL_LPTIM_SetEncoderMode
861 * @param LPTIMx Low-Power Timer instance
862 * @param EncoderMode This parameter can be one of the following values:
863 * @arg @ref LL_LPTIM_ENCODER_MODE_RISING
864 * @arg @ref LL_LPTIM_ENCODER_MODE_FALLING
865 * @arg @ref LL_LPTIM_ENCODER_MODE_RISING_FALLING
868 __STATIC_INLINE
void LL_LPTIM_SetEncoderMode(LPTIM_TypeDef
*LPTIMx
, uint32_t EncoderMode
)
870 MODIFY_REG(LPTIMx
->CFGR
, LPTIM_CFGR_CKPOL
, EncoderMode
);
874 * @brief Get actual encoder mode.
875 * @rmtoll CFGR CKPOL LL_LPTIM_GetEncoderMode
876 * @param LPTIMx Low-Power Timer instance
877 * @retval Returned value can be one of the following values:
878 * @arg @ref LL_LPTIM_ENCODER_MODE_RISING
879 * @arg @ref LL_LPTIM_ENCODER_MODE_FALLING
880 * @arg @ref LL_LPTIM_ENCODER_MODE_RISING_FALLING
882 __STATIC_INLINE
uint32_t LL_LPTIM_GetEncoderMode(LPTIM_TypeDef
*LPTIMx
)
884 return (uint32_t)(READ_BIT(LPTIMx
->CFGR
, LPTIM_CFGR_CKPOL
));
888 * @brief Enable the encoder mode
889 * @note This function must be called when the LPTIM instance is disabled.
890 * @note In this mode the LPTIM instance must be clocked by an internal clock
891 * source. Also, the prescaler division ratio must be equal to 1.
892 * @note LPTIM instance must be configured in continuous mode prior enabling
894 * @rmtoll CFGR ENC LL_LPTIM_EnableEncoderMode
895 * @param LPTIMx Low-Power Timer instance
898 __STATIC_INLINE
void LL_LPTIM_EnableEncoderMode(LPTIM_TypeDef
*LPTIMx
)
900 SET_BIT(LPTIMx
->CFGR
, LPTIM_CFGR_ENC
);
904 * @brief Disable the encoder mode
905 * @note This function must be called when the LPTIM instance is disabled.
906 * @rmtoll CFGR ENC LL_LPTIM_DisableEncoderMode
907 * @param LPTIMx Low-Power Timer instance
910 __STATIC_INLINE
void LL_LPTIM_DisableEncoderMode(LPTIM_TypeDef
*LPTIMx
)
912 CLEAR_BIT(LPTIMx
->CFGR
, LPTIM_CFGR_ENC
);
916 * @brief Indicates whether the LPTIM operates in encoder mode.
917 * @rmtoll CFGR ENC LL_LPTIM_IsEnabledEncoderMode
918 * @param LPTIMx Low-Power Timer instance
919 * @retval State of bit (1 or 0).
921 __STATIC_INLINE
uint32_t LL_LPTIM_IsEnabledEncoderMode(LPTIM_TypeDef
*LPTIMx
)
923 return (READ_BIT(LPTIMx
->CFGR
, LPTIM_CFGR_ENC
) == (LPTIM_CFGR_ENC
));
930 /** @defgroup LPTIM_LL_EF_FLAG_Management FLAG Management
935 * @brief Clear the compare match flag (CMPMCF)
936 * @rmtoll ICR CMPMCF LL_LPTIM_ClearFLAG_CMPM
937 * @param LPTIMx Low-Power Timer instance
940 __STATIC_INLINE
void LL_LPTIM_ClearFLAG_CMPM(LPTIM_TypeDef
*LPTIMx
)
942 SET_BIT(LPTIMx
->ICR
, LPTIM_ICR_CMPMCF
);
946 * @brief Inform application whether a compare match interrupt has occurred.
947 * @rmtoll ISR CMPM LL_LPTIM_IsActiveFlag_CMPM
948 * @param LPTIMx Low-Power Timer instance
949 * @retval State of bit (1 or 0).
951 __STATIC_INLINE
uint32_t LL_LPTIM_IsActiveFlag_CMPM(LPTIM_TypeDef
*LPTIMx
)
953 return (READ_BIT(LPTIMx
->ISR
, LPTIM_ISR_CMPM
) == (LPTIM_ISR_CMPM
));
957 * @brief Clear the autoreload match flag (ARRMCF)
958 * @rmtoll ICR ARRMCF LL_LPTIM_ClearFLAG_ARRM
959 * @param LPTIMx Low-Power Timer instance
962 __STATIC_INLINE
void LL_LPTIM_ClearFLAG_ARRM(LPTIM_TypeDef
*LPTIMx
)
964 SET_BIT(LPTIMx
->ICR
, LPTIM_ICR_ARRMCF
);
968 * @brief Inform application whether a autoreload match interrupt has occurred.
969 * @rmtoll ISR ARRM LL_LPTIM_IsActiveFlag_ARRM
970 * @param LPTIMx Low-Power Timer instance
971 * @retval State of bit (1 or 0).
973 __STATIC_INLINE
uint32_t LL_LPTIM_IsActiveFlag_ARRM(LPTIM_TypeDef
*LPTIMx
)
975 return (READ_BIT(LPTIMx
->ISR
, LPTIM_ISR_ARRM
) == (LPTIM_ISR_ARRM
));
979 * @brief Clear the external trigger valid edge flag(EXTTRIGCF).
980 * @rmtoll ICR EXTTRIGCF LL_LPTIM_ClearFlag_EXTTRIG
981 * @param LPTIMx Low-Power Timer instance
984 __STATIC_INLINE
void LL_LPTIM_ClearFlag_EXTTRIG(LPTIM_TypeDef
*LPTIMx
)
986 SET_BIT(LPTIMx
->ICR
, LPTIM_ICR_EXTTRIGCF
);
990 * @brief Inform application whether a valid edge on the selected external trigger input has occurred.
991 * @rmtoll ISR EXTTRIG LL_LPTIM_IsActiveFlag_EXTTRIG
992 * @param LPTIMx Low-Power Timer instance
993 * @retval State of bit (1 or 0).
995 __STATIC_INLINE
uint32_t LL_LPTIM_IsActiveFlag_EXTTRIG(LPTIM_TypeDef
*LPTIMx
)
997 return (READ_BIT(LPTIMx
->ISR
, LPTIM_ISR_EXTTRIG
) == (LPTIM_ISR_EXTTRIG
));
1001 * @brief Clear the compare register update interrupt flag (CMPOKCF).
1002 * @rmtoll ICR CMPOKCF LL_LPTIM_ClearFlag_CMPOK
1003 * @param LPTIMx Low-Power Timer instance
1006 __STATIC_INLINE
void LL_LPTIM_ClearFlag_CMPOK(LPTIM_TypeDef
*LPTIMx
)
1008 SET_BIT(LPTIMx
->ICR
, LPTIM_ICR_CMPOKCF
);
1012 * @brief Informs application whether the APB bus write operation to the LPTIMx_CMP register has been successfully completed; If so, a new one can be initiated.
1013 * @rmtoll ISR CMPOK LL_LPTIM_IsActiveFlag_CMPOK
1014 * @param LPTIMx Low-Power Timer instance
1015 * @retval State of bit (1 or 0).
1017 __STATIC_INLINE
uint32_t LL_LPTIM_IsActiveFlag_CMPOK(LPTIM_TypeDef
*LPTIMx
)
1019 return (READ_BIT(LPTIMx
->ISR
, LPTIM_ISR_CMPOK
) == (LPTIM_ISR_CMPOK
));
1023 * @brief Clear the autoreload register update interrupt flag (ARROKCF).
1024 * @rmtoll ICR ARROKCF LL_LPTIM_ClearFlag_ARROK
1025 * @param LPTIMx Low-Power Timer instance
1028 __STATIC_INLINE
void LL_LPTIM_ClearFlag_ARROK(LPTIM_TypeDef
*LPTIMx
)
1030 SET_BIT(LPTIMx
->ICR
, LPTIM_ICR_ARROKCF
);
1034 * @brief Informs application whether the APB bus write operation to the LPTIMx_ARR register has been successfully completed; If so, a new one can be initiated.
1035 * @rmtoll ISR ARROK LL_LPTIM_IsActiveFlag_ARROK
1036 * @param LPTIMx Low-Power Timer instance
1037 * @retval State of bit (1 or 0).
1039 __STATIC_INLINE
uint32_t LL_LPTIM_IsActiveFlag_ARROK(LPTIM_TypeDef
*LPTIMx
)
1041 return (READ_BIT(LPTIMx
->ISR
, LPTIM_ISR_ARROK
) == (LPTIM_ISR_ARROK
));
1045 * @brief Clear the counter direction change to up interrupt flag (UPCF).
1046 * @rmtoll ICR UPCF LL_LPTIM_ClearFlag_UP
1047 * @param LPTIMx Low-Power Timer instance
1050 __STATIC_INLINE
void LL_LPTIM_ClearFlag_UP(LPTIM_TypeDef
*LPTIMx
)
1052 SET_BIT(LPTIMx
->ICR
, LPTIM_ICR_UPCF
);
1056 * @brief Informs the application whether the counter direction has changed from down to up (when the LPTIM instance operates in encoder mode).
1057 * @rmtoll ISR UP LL_LPTIM_IsActiveFlag_UP
1058 * @param LPTIMx Low-Power Timer instance
1059 * @retval State of bit (1 or 0).
1061 __STATIC_INLINE
uint32_t LL_LPTIM_IsActiveFlag_UP(LPTIM_TypeDef
*LPTIMx
)
1063 return (READ_BIT(LPTIMx
->ISR
, LPTIM_ISR_UP
) == (LPTIM_ISR_UP
));
1067 * @brief Clear the counter direction change to down interrupt flag (DOWNCF).
1068 * @rmtoll ICR DOWNCF LL_LPTIM_ClearFlag_DOWN
1069 * @param LPTIMx Low-Power Timer instance
1072 __STATIC_INLINE
void LL_LPTIM_ClearFlag_DOWN(LPTIM_TypeDef
*LPTIMx
)
1074 SET_BIT(LPTIMx
->ICR
, LPTIM_ICR_DOWNCF
);
1078 * @brief Informs the application whether the counter direction has changed from up to down (when the LPTIM instance operates in encoder mode).
1079 * @rmtoll ISR DOWN LL_LPTIM_IsActiveFlag_DOWN
1080 * @param LPTIMx Low-Power Timer instance
1081 * @retval State of bit (1 or 0).
1083 __STATIC_INLINE
uint32_t LL_LPTIM_IsActiveFlag_DOWN(LPTIM_TypeDef
*LPTIMx
)
1085 return (READ_BIT(LPTIMx
->ISR
, LPTIM_ISR_DOWN
) == (LPTIM_ISR_DOWN
));
1092 /** @defgroup LPTIM_LL_EF_IT_Management Interrupt Management
1097 * @brief Enable compare match interrupt (CMPMIE).
1098 * @rmtoll IER CMPMIE LL_LPTIM_EnableIT_CMPM
1099 * @param LPTIMx Low-Power Timer instance
1102 __STATIC_INLINE
void LL_LPTIM_EnableIT_CMPM(LPTIM_TypeDef
*LPTIMx
)
1104 SET_BIT(LPTIMx
->IER
, LPTIM_IER_CMPMIE
);
1108 * @brief Disable compare match interrupt (CMPMIE).
1109 * @rmtoll IER CMPMIE LL_LPTIM_DisableIT_CMPM
1110 * @param LPTIMx Low-Power Timer instance
1113 __STATIC_INLINE
void LL_LPTIM_DisableIT_CMPM(LPTIM_TypeDef
*LPTIMx
)
1115 CLEAR_BIT(LPTIMx
->IER
, LPTIM_IER_CMPMIE
);
1119 * @brief Indicates whether the compare match interrupt (CMPMIE) is enabled.
1120 * @rmtoll IER CMPMIE LL_LPTIM_IsEnabledIT_CMPM
1121 * @param LPTIMx Low-Power Timer instance
1122 * @retval State of bit (1 or 0).
1124 __STATIC_INLINE
uint32_t LL_LPTIM_IsEnabledIT_CMPM(LPTIM_TypeDef
*LPTIMx
)
1126 return (READ_BIT(LPTIMx
->IER
, LPTIM_IER_CMPMIE
) == (LPTIM_IER_CMPMIE
));
1130 * @brief Enable autoreload match interrupt (ARRMIE).
1131 * @rmtoll IER ARRMIE LL_LPTIM_EnableIT_ARRM
1132 * @param LPTIMx Low-Power Timer instance
1135 __STATIC_INLINE
void LL_LPTIM_EnableIT_ARRM(LPTIM_TypeDef
*LPTIMx
)
1137 SET_BIT(LPTIMx
->IER
, LPTIM_IER_ARRMIE
);
1141 * @brief Disable autoreload match interrupt (ARRMIE).
1142 * @rmtoll IER ARRMIE LL_LPTIM_DisableIT_ARRM
1143 * @param LPTIMx Low-Power Timer instance
1146 __STATIC_INLINE
void LL_LPTIM_DisableIT_ARRM(LPTIM_TypeDef
*LPTIMx
)
1148 CLEAR_BIT(LPTIMx
->IER
, LPTIM_IER_ARRMIE
);
1152 * @brief Indicates whether the autoreload match interrupt (ARRMIE) is enabled.
1153 * @rmtoll IER ARRMIE LL_LPTIM_IsEnabledIT_ARRM
1154 * @param LPTIMx Low-Power Timer instance
1155 * @retval State of bit (1 or 0).
1157 __STATIC_INLINE
uint32_t LL_LPTIM_IsEnabledIT_ARRM(LPTIM_TypeDef
*LPTIMx
)
1159 return (READ_BIT(LPTIMx
->IER
, LPTIM_IER_ARRMIE
) == (LPTIM_IER_ARRMIE
));
1163 * @brief Enable external trigger valid edge interrupt (EXTTRIGIE).
1164 * @rmtoll IER EXTTRIGIE LL_LPTIM_EnableIT_EXTTRIG
1165 * @param LPTIMx Low-Power Timer instance
1168 __STATIC_INLINE
void LL_LPTIM_EnableIT_EXTTRIG(LPTIM_TypeDef
*LPTIMx
)
1170 SET_BIT(LPTIMx
->IER
, LPTIM_IER_EXTTRIGIE
);
1174 * @brief Disable external trigger valid edge interrupt (EXTTRIGIE).
1175 * @rmtoll IER EXTTRIGIE LL_LPTIM_DisableIT_EXTTRIG
1176 * @param LPTIMx Low-Power Timer instance
1179 __STATIC_INLINE
void LL_LPTIM_DisableIT_EXTTRIG(LPTIM_TypeDef
*LPTIMx
)
1181 CLEAR_BIT(LPTIMx
->IER
, LPTIM_IER_EXTTRIGIE
);
1185 * @brief Indicates external trigger valid edge interrupt (EXTTRIGIE) is enabled.
1186 * @rmtoll IER EXTTRIGIE LL_LPTIM_IsEnabledIT_EXTTRIG
1187 * @param LPTIMx Low-Power Timer instance
1188 * @retval State of bit (1 or 0).
1190 __STATIC_INLINE
uint32_t LL_LPTIM_IsEnabledIT_EXTTRIG(LPTIM_TypeDef
*LPTIMx
)
1192 return (READ_BIT(LPTIMx
->IER
, LPTIM_IER_EXTTRIGIE
) == (LPTIM_IER_EXTTRIGIE
));
1196 * @brief Enable compare register write completed interrupt (CMPOKIE).
1197 * @rmtoll IER CMPOKIE LL_LPTIM_EnableIT_CMPOK
1198 * @param LPTIMx Low-Power Timer instance
1201 __STATIC_INLINE
void LL_LPTIM_EnableIT_CMPOK(LPTIM_TypeDef
*LPTIMx
)
1203 SET_BIT(LPTIMx
->IER
, LPTIM_IER_CMPOKIE
);
1207 * @brief Disable compare register write completed interrupt (CMPOKIE).
1208 * @rmtoll IER CMPOKIE LL_LPTIM_DisableIT_CMPOK
1209 * @param LPTIMx Low-Power Timer instance
1212 __STATIC_INLINE
void LL_LPTIM_DisableIT_CMPOK(LPTIM_TypeDef
*LPTIMx
)
1214 CLEAR_BIT(LPTIMx
->IER
, LPTIM_IER_CMPOKIE
);
1218 * @brief Indicates whether the compare register write completed interrupt (CMPOKIE) is enabled.
1219 * @rmtoll IER CMPOKIE LL_LPTIM_IsEnabledIT_CMPOK
1220 * @param LPTIMx Low-Power Timer instance
1221 * @retval State of bit (1 or 0).
1223 __STATIC_INLINE
uint32_t LL_LPTIM_IsEnabledIT_CMPOK(LPTIM_TypeDef
*LPTIMx
)
1225 return (READ_BIT(LPTIMx
->IER
, LPTIM_IER_CMPOKIE
) == (LPTIM_IER_CMPOKIE
));
1229 * @brief Enable autoreload register write completed interrupt (ARROKIE).
1230 * @rmtoll IER ARROKIE LL_LPTIM_EnableIT_ARROK
1231 * @param LPTIMx Low-Power Timer instance
1234 __STATIC_INLINE
void LL_LPTIM_EnableIT_ARROK(LPTIM_TypeDef
*LPTIMx
)
1236 SET_BIT(LPTIMx
->IER
, LPTIM_IER_ARROKIE
);
1240 * @brief Disable autoreload register write completed interrupt (ARROKIE).
1241 * @rmtoll IER ARROKIE LL_LPTIM_DisableIT_ARROK
1242 * @param LPTIMx Low-Power Timer instance
1245 __STATIC_INLINE
void LL_LPTIM_DisableIT_ARROK(LPTIM_TypeDef
*LPTIMx
)
1247 CLEAR_BIT(LPTIMx
->IER
, LPTIM_IER_ARROKIE
);
1251 * @brief Indicates whether the autoreload register write completed interrupt (ARROKIE) is enabled.
1252 * @rmtoll IER ARROKIE LL_LPTIM_IsEnabledIT_ARROK
1253 * @param LPTIMx Low-Power Timer instance
1254 * @retval State of bit (1 or 0).
1256 __STATIC_INLINE
uint32_t LL_LPTIM_IsEnabledIT_ARROK(LPTIM_TypeDef
*LPTIMx
)
1258 return (READ_BIT(LPTIMx
->IER
, LPTIM_IER_ARROKIE
) == (LPTIM_IER_ARROKIE
));
1262 * @brief Enable direction change to up interrupt (UPIE).
1263 * @rmtoll IER UPIE LL_LPTIM_EnableIT_UP
1264 * @param LPTIMx Low-Power Timer instance
1267 __STATIC_INLINE
void LL_LPTIM_EnableIT_UP(LPTIM_TypeDef
*LPTIMx
)
1269 SET_BIT(LPTIMx
->IER
, LPTIM_IER_UPIE
);
1273 * @brief Disable direction change to up interrupt (UPIE).
1274 * @rmtoll IER UPIE LL_LPTIM_DisableIT_UP
1275 * @param LPTIMx Low-Power Timer instance
1278 __STATIC_INLINE
void LL_LPTIM_DisableIT_UP(LPTIM_TypeDef
*LPTIMx
)
1280 CLEAR_BIT(LPTIMx
->IER
, LPTIM_IER_UPIE
);
1284 * @brief Indicates whether the direction change to up interrupt (UPIE) is enabled.
1285 * @rmtoll IER UPIE LL_LPTIM_IsEnabledIT_UP
1286 * @param LPTIMx Low-Power Timer instance
1287 * @retval State of bit (1 or 0).
1289 __STATIC_INLINE
uint32_t LL_LPTIM_IsEnabledIT_UP(LPTIM_TypeDef
*LPTIMx
)
1291 return (READ_BIT(LPTIMx
->IER
, LPTIM_IER_UPIE
) == (LPTIM_IER_UPIE
));
1295 * @brief Enable direction change to down interrupt (DOWNIE).
1296 * @rmtoll IER DOWNIE LL_LPTIM_EnableIT_DOWN
1297 * @param LPTIMx Low-Power Timer instance
1300 __STATIC_INLINE
void LL_LPTIM_EnableIT_DOWN(LPTIM_TypeDef
*LPTIMx
)
1302 SET_BIT(LPTIMx
->IER
, LPTIM_IER_DOWNIE
);
1306 * @brief Disable direction change to down interrupt (DOWNIE).
1307 * @rmtoll IER DOWNIE LL_LPTIM_DisableIT_DOWN
1308 * @param LPTIMx Low-Power Timer instance
1311 __STATIC_INLINE
void LL_LPTIM_DisableIT_DOWN(LPTIM_TypeDef
*LPTIMx
)
1313 CLEAR_BIT(LPTIMx
->IER
, LPTIM_IER_DOWNIE
);
1317 * @brief Indicates whether the direction change to down interrupt (DOWNIE) is enabled.
1318 * @rmtoll IER DOWNIE LL_LPTIM_IsEnabledIT_DOWN
1319 * @param LPTIMx Low-Power Timer instance
1320 * @retval State of bit (1 or 0).
1322 __STATIC_INLINE
uint32_t LL_LPTIM_IsEnabledIT_DOWN(LPTIM_TypeDef
*LPTIMx
)
1324 return (READ_BIT(LPTIMx
->IER
, LPTIM_IER_DOWNIE
) == (LPTIM_IER_DOWNIE
));
1331 #if defined(USE_FULL_LL_DRIVER)
1332 /** @defgroup LPTIM_LL_EF_Init Initialisation and deinitialisation functions
1336 ErrorStatus
LL_LPTIM_DeInit(LPTIM_TypeDef
*LPTIMx
);
1337 void LL_LPTIM_StructInit(LL_LPTIM_InitTypeDef
*LPTIM_InitStruct
);
1338 ErrorStatus
LL_LPTIM_Init(LPTIM_TypeDef
*LPTIMx
, LL_LPTIM_InitTypeDef
*LPTIM_InitStruct
);
1342 #endif /* USE_FULL_LL_DRIVER */
1362 #endif /* __STM32F7xx_LL_LPTIM_H */
1364 /************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/