Merge pull request #10592 from iNavFlight/MrD_Update-parameter-description
[inav.git] / lib / main / STM32F7 / Drivers / STM32F7xx_HAL_Driver / Inc / stm32f7xx_ll_lptim.h
blob11ddd29ffa397675a62e3e68e68b1fa902b711ad
1 /**
2 ******************************************************************************
3 * @file stm32f7xx_ll_lptim.h
4 * @author MCD Application Team
5 * @version V1.2.2
6 * @date 14-April-2017
7 * @brief Header file of LPTIM LL module.
8 ******************************************************************************
9 * @attention
11 * <h2><center>&copy; COPYRIGHT(c) 2017 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 ******************************************************************************
38 /* Define to prevent recursive inclusion -------------------------------------*/
39 #ifndef __STM32F7xx_LL_LPTIM_H
40 #define __STM32F7xx_LL_LPTIM_H
42 #ifdef __cplusplus
43 extern "C" {
44 #endif
46 /* Includes ------------------------------------------------------------------*/
47 #include "stm32f7xx.h"
49 /** @addtogroup STM32F7xx_LL_Driver
50 * @{
52 #if defined (LPTIM1)
54 /** @defgroup LPTIM_LL LPTIM
55 * @{
58 /* Private types -------------------------------------------------------------*/
59 /* Private variables ---------------------------------------------------------*/
61 /* Private constants ---------------------------------------------------------*/
63 /* Private macros ------------------------------------------------------------*/
64 #if defined(USE_FULL_LL_DRIVER)
65 /** @defgroup LPTIM_LL_Private_Macros LPTIM Private Macros
66 * @{
68 /**
69 * @}
71 #endif /*USE_FULL_LL_DRIVER*/
73 /* Exported types ------------------------------------------------------------*/
74 #if defined(USE_FULL_LL_DRIVER)
75 /** @defgroup LPTIM_LL_ES_INIT LPTIM Exported Init structure
76 * @{
79 /**
80 * @brief LPTIM Init structure definition
82 typedef struct
84 uint32_t ClockSource; /*!< Specifies the source of the clock used by the LPTIM instance.
85 This parameter can be a value of @ref LPTIM_LL_EC_CLK_SOURCE.
87 This feature can be modified afterwards using unitary function @ref LL_LPTIM_SetClockSource().*/
89 uint32_t Prescaler; /*!< Specifies the prescaler division ratio.
90 This parameter can be a value of @ref LPTIM_LL_EC_PRESCALER.
92 This feature can be modified afterwards using using unitary function @ref LL_LPTIM_SetPrescaler().*/
94 uint32_t Waveform; /*!< Specifies the waveform shape.
95 This parameter can be a value of @ref LPTIM_LL_EC_OUTPUT_WAVEFORM.
97 This feature can be modified afterwards using unitary function @ref LL_LPTIM_ConfigOutput().*/
99 uint32_t Polarity; /*!< Specifies waveform polarity.
100 This parameter can be a value of @ref LPTIM_LL_EC_OUTPUT_POLARITY.
102 This feature can be modified afterwards using unitary function @ref LL_LPTIM_ConfigOutput().*/
103 } LL_LPTIM_InitTypeDef;
106 * @}
108 #endif /* USE_FULL_LL_DRIVER */
110 /* Exported constants --------------------------------------------------------*/
111 /** @defgroup LPTIM_LL_Exported_Constants LPTIM Exported Constants
112 * @{
115 /** @defgroup LPTIM_LL_EC_GET_FLAG Get Flags Defines
116 * @brief Flags defines which can be used with LL_LPTIM_ReadReg function
117 * @{
119 #define LL_LPTIM_ISR_CMPM LPTIM_ISR_CMPM /*!< Compare match */
120 #define LL_LPTIM_ISR_ARRM LPTIM_ISR_ARRM /*!< Autoreload match */
121 #define LL_LPTIM_ISR_EXTTRIG LPTIM_ISR_EXTTRIG /*!< External trigger edge event */
122 #define LL_LPTIM_ISR_CMPOK LPTIM_ISR_CMPOK /*!< Compare register update OK */
123 #define LL_LPTIM_ISR_ARROK LPTIM_ISR_ARROK /*!< Autoreload register update OK */
124 #define LL_LPTIM_ISR_UP LPTIM_ISR_UP /*!< Counter direction change down to up */
125 #define LL_LPTIM_ISR_DOWN LPTIM_ISR_DOWN /*!< Counter direction change up to down */
127 * @}
130 /** @defgroup LPTIM_LL_EC_IT IT Defines
131 * @brief IT defines which can be used with LL_LPTIM_ReadReg and LL_LPTIM_WriteReg functions
132 * @{
134 #define LL_LPTIM_IER_CMPMIE LPTIM_IER_CMPMIE /*!< Compare match Interrupt Enable */
135 #define LL_LPTIM_IER_ARRMIE LPTIM_IER_ARRMIE /*!< Autoreload match Interrupt Enable */
136 #define LL_LPTIM_IER_EXTTRIGIE LPTIM_IER_EXTTRIGIE /*!< External trigger valid edge Interrupt Enable */
137 #define LL_LPTIM_IER_CMPOKIE LPTIM_IER_CMPOKIE /*!< Compare register update OK Interrupt Enable */
138 #define LL_LPTIM_IER_ARROKIE LPTIM_IER_ARROKIE /*!< Autoreload register update OK Interrupt Enable */
139 #define LL_LPTIM_IER_UPIE LPTIM_IER_UPIE /*!< Direction change to UP Interrupt Enable */
140 #define LL_LPTIM_IER_DOWNIE LPTIM_IER_DOWNIE /*!< Direction change to down Interrupt Enable */
142 * @}
145 /** @defgroup LPTIM_LL_EC_OPERATING_MODE Operating Mode
146 * @{
148 #define LL_LPTIM_OPERATING_MODE_CONTINUOUS LPTIM_CR_CNTSTRT /*!<LP Timer starts in continuous mode*/
149 #define LL_LPTIM_OPERATING_MODE_ONESHOT LPTIM_CR_SNGSTRT /*!<LP Tilmer starts in single mode*/
151 * @}
154 /** @defgroup LPTIM_LL_EC_UPDATE_MODE Update Mode
155 * @{
157 #define LL_LPTIM_UPDATE_MODE_IMMEDIATE 0x00000000U /*!<Preload is disabled: registers are updated after each APB bus write access*/
158 #define LL_LPTIM_UPDATE_MODE_ENDOFPERIOD LPTIM_CFGR_PRELOAD /*!<preload is enabled: registers are updated at the end of the current LPTIM period*/
160 * @}
163 /** @defgroup LPTIM_LL_EC_COUNTER_MODE Counter Mode
164 * @{
166 #define LL_LPTIM_COUNTER_MODE_INTERNAL 0x00000000U /*!<The counter is incremented following each internal clock pulse*/
167 #define LL_LPTIM_COUNTER_MODE_EXTERNAL LPTIM_CFGR_COUNTMODE /*!<The counter is incremented following each valid clock pulse on the LPTIM external Input1*/
169 * @}
172 /** @defgroup LPTIM_LL_EC_OUTPUT_WAVEFORM Output Waveform Type
173 * @{
175 #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*/
176 #define LL_LPTIM_OUTPUT_WAVEFORM_SETONCE LPTIM_CFGR_WAVE /*!<LPTIM generates a Set Once waveform*/
178 * @}
181 /** @defgroup LPTIM_LL_EC_OUTPUT_POLARITY Output Polarity
182 * @{
184 #define LL_LPTIM_OUTPUT_POLARITY_REGULAR 0x00000000U /*!<The LPTIM output reflects the compare results between LPTIMx_ARR and LPTIMx_CMP registers*/
185 #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*/
187 * @}
190 /** @defgroup LPTIM_LL_EC_PRESCALER Prescaler Value
191 * @{
193 #define LL_LPTIM_PRESCALER_DIV1 0x00000000U /*!<Prescaler division factor is set to 1*/
194 #define LL_LPTIM_PRESCALER_DIV2 LPTIM_CFGR_PRESC_0 /*!<Prescaler division factor is set to 2*/
195 #define LL_LPTIM_PRESCALER_DIV4 LPTIM_CFGR_PRESC_1 /*!<Prescaler division factor is set to 4*/
196 #define LL_LPTIM_PRESCALER_DIV8 (LPTIM_CFGR_PRESC_1 | LPTIM_CFGR_PRESC_0) /*!<Prescaler division factor is set to 8*/
197 #define LL_LPTIM_PRESCALER_DIV16 LPTIM_CFGR_PRESC_2 /*!<Prescaler division factor is set to 16*/
198 #define LL_LPTIM_PRESCALER_DIV32 (LPTIM_CFGR_PRESC_2 | LPTIM_CFGR_PRESC_0) /*!<Prescaler division factor is set to 32*/
199 #define LL_LPTIM_PRESCALER_DIV64 (LPTIM_CFGR_PRESC_2 | LPTIM_CFGR_PRESC_1) /*!<Prescaler division factor is set to 64*/
200 #define LL_LPTIM_PRESCALER_DIV128 LPTIM_CFGR_PRESC /*!<Prescaler division factor is set to 128*/
202 * @}
205 /** @defgroup LPTIM_LL_EC_TRIG_SOURCE Trigger Source
206 * @{
208 #define LL_LPTIM_TRIG_SOURCE_GPIO 0x00000000U /*!<External input trigger is connected to TIMx_ETR input*/
209 #define LL_LPTIM_TRIG_SOURCE_RTCALARMA LPTIM_CFGR_TRIGSEL_0 /*!<External input trigger is connected to RTC Alarm A*/
210 #define LL_LPTIM_TRIG_SOURCE_RTCALARMB LPTIM_CFGR_TRIGSEL_1 /*!<External input trigger is connected to RTC Alarm B*/
211 #define LL_LPTIM_TRIG_SOURCE_RTCTAMP1 (LPTIM_CFGR_TRIGSEL_1 | LPTIM_CFGR_TRIGSEL_0) /*!<External input trigger is connected to RTC Tamper 1*/
212 #define LL_LPTIM_TRIG_SOURCE_RTCTAMP2 LPTIM_CFGR_TRIGSEL_2 /*!<External input trigger is connected to RTC Tamper 2*/
213 #define LL_LPTIM_TRIG_SOURCE_RTCTAMP3 (LPTIM_CFGR_TRIGSEL_2 | LPTIM_CFGR_TRIGSEL_0) /*!<External input trigger is connected to RTC Tamper 3*/
214 #define LL_LPTIM_TRIG_SOURCE_COMP1 (LPTIM_CFGR_TRIGSEL_2 | LPTIM_CFGR_TRIGSEL_1) /*!<External input trigger is connected to COMP1 output*/
215 #define LL_LPTIM_TRIG_SOURCE_COMP2 LPTIM_CFGR_TRIGSEL /*!<External input trigger is connected to COMP2 output*/
217 * @}
220 /** @defgroup LPTIM_LL_EC_TRIG_FILTER Trigger Filter
221 * @{
223 #define LL_LPTIM_TRIG_FILTER_NONE 0x00000000U /*!<Any trigger active level change is considered as a valid trigger*/
224 #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*/
225 #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*/
226 #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*/
228 * @}
231 /** @defgroup LPTIM_LL_EC_TRIG_POLARITY Trigger Polarity
232 * @{
234 #define LL_LPTIM_TRIG_POLARITY_RISING LPTIM_CFGR_TRIGEN_0 /*!<LPTIM counter starts when a rising edge is detected*/
235 #define LL_LPTIM_TRIG_POLARITY_FALLING LPTIM_CFGR_TRIGEN_1 /*!<LPTIM counter starts when a falling edge is detected*/
236 #define LL_LPTIM_TRIG_POLARITY_RISING_FALLING LPTIM_CFGR_TRIGEN /*!<LPTIM counter starts when a rising or a falling edge is detected*/
238 * @}
241 /** @defgroup LPTIM_LL_EC_CLK_SOURCE Clock Source
242 * @{
244 #define LL_LPTIM_CLK_SOURCE_INTERNAL 0x00000000U /*!<LPTIM is clocked by internal clock source (APB clock or any of the embedded oscillators)*/
245 #define LL_LPTIM_CLK_SOURCE_EXTERNAL LPTIM_CFGR_CKSEL /*!<LPTIM is clocked by an external clock source through the LPTIM external Input1*/
247 * @}
250 /** @defgroup LPTIM_LL_EC_CLK_FILTER Clock Filter
251 * @{
253 #define LL_LPTIM_CLK_FILTER_NONE 0x00000000U /*!<Any external clock signal level change is considered as a valid transition*/
254 #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*/
255 #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*/
256 #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*/
258 * @}
261 /** @defgroup LPTIM_LL_EC_CLK_POLARITY Clock Polarity
262 * @{
264 #define LL_LPTIM_CLK_POLARITY_RISING 0x00000000U /*!< The rising edge is the active edge used for counting*/
265 #define LL_LPTIM_CLK_POLARITY_FALLING LPTIM_CFGR_CKPOL_0 /*!< The falling edge is the active edge used for counting*/
266 #define LL_LPTIM_CLK_POLARITY_RISING_FALLING LPTIM_CFGR_CKPOL_1 /*!< Both edges are active edges*/
268 * @}
271 /** @defgroup LPTIM_LL_EC_ENCODER_MODE Encoder Mode
272 * @{
274 #define LL_LPTIM_ENCODER_MODE_RISING 0x00000000U /*!< The rising edge is the active edge used for counting*/
275 #define LL_LPTIM_ENCODER_MODE_FALLING LPTIM_CFGR_CKPOL_0 /*!< The falling edge is the active edge used for counting*/
276 #define LL_LPTIM_ENCODER_MODE_RISING_FALLING LPTIM_CFGR_CKPOL_1 /*!< Both edges are active edges*/
278 * @}
283 * @}
286 /* Exported macro ------------------------------------------------------------*/
287 /** @defgroup LPTIM_LL_Exported_Macros LPTIM Exported Macros
288 * @{
291 /** @defgroup LPTIM_LL_EM_WRITE_READ Common Write and read registers Macros
292 * @{
296 * @brief Write a value in LPTIM register
297 * @param __INSTANCE__ LPTIM Instance
298 * @param __REG__ Register to be written
299 * @param __VALUE__ Value to be written in the register
300 * @retval None
302 #define LL_LPTIM_WriteReg(__INSTANCE__, __REG__, __VALUE__) WRITE_REG(__INSTANCE__->__REG__, (__VALUE__))
305 * @brief Read a value in LPTIM register
306 * @param __INSTANCE__ LPTIM Instance
307 * @param __REG__ Register to be read
308 * @retval Register value
310 #define LL_LPTIM_ReadReg(__INSTANCE__, __REG__) READ_REG(__INSTANCE__->__REG__)
312 * @}
316 * @}
320 /* Exported functions --------------------------------------------------------*/
321 /** @defgroup LPTIM_LL_Exported_Functions LPTIM Exported Functions
322 * @{
325 /** @defgroup LPTIM_LL_EF_LPTIM_Configuration LPTIM Configuration
326 * @{
330 * @brief Enable the LPTIM instance
331 * @note After setting the ENABLE bit, a delay of two counter clock is needed
332 * before the LPTIM instance is actually enabled.
333 * @rmtoll CR ENABLE LL_LPTIM_Enable
334 * @param LPTIMx Low-Power Timer instance
335 * @retval None
337 __STATIC_INLINE void LL_LPTIM_Enable(LPTIM_TypeDef *LPTIMx)
339 SET_BIT(LPTIMx->CR, LPTIM_CR_ENABLE);
343 * @brief Disable the LPTIM instance
344 * @rmtoll CR ENABLE LL_LPTIM_Disable
345 * @param LPTIMx Low-Power Timer instance
346 * @retval None
348 __STATIC_INLINE void LL_LPTIM_Disable(LPTIM_TypeDef *LPTIMx)
350 CLEAR_BIT(LPTIMx->CR, LPTIM_CR_ENABLE);
354 * @brief Indicates whether the LPTIM instance is enabled.
355 * @rmtoll CR ENABLE LL_LPTIM_IsEnabled
356 * @param LPTIMx Low-Power Timer instance
357 * @retval State of bit (1 or 0).
359 __STATIC_INLINE uint32_t LL_LPTIM_IsEnabled(LPTIM_TypeDef *LPTIMx)
361 return (READ_BIT(LPTIMx->CR, LPTIM_CR_ENABLE) == (LPTIM_CR_ENABLE));
365 * @brief Starts the LPTIM counter in the desired mode.
366 * @note LPTIM instance must be enabled before starting the counter.
367 * @note It is possible to change on the fly from One Shot mode to
368 * Continuous mode.
369 * @rmtoll CR CNTSTRT LL_LPTIM_StartCounter\n
370 * CR SNGSTRT LL_LPTIM_StartCounter
371 * @param LPTIMx Low-Power Timer instance
372 * @param OperatingMode This parameter can be one of the following values:
373 * @arg @ref LL_LPTIM_OPERATING_MODE_CONTINUOUS
374 * @arg @ref LL_LPTIM_OPERATING_MODE_ONESHOT
375 * @retval None
377 __STATIC_INLINE void LL_LPTIM_StartCounter(LPTIM_TypeDef *LPTIMx, uint32_t OperatingMode)
379 MODIFY_REG(LPTIMx->CR, LPTIM_CR_CNTSTRT | LPTIM_CR_SNGSTRT, OperatingMode);
384 * @brief Set the LPTIM registers update mode (enable/disable register preload)
385 * @note This function must be called when the LPTIM instance is disabled.
386 * @rmtoll CFGR PRELOAD LL_LPTIM_SetUpdateMode
387 * @param LPTIMx Low-Power Timer instance
388 * @param UpdateMode This parameter can be one of the following values:
389 * @arg @ref LL_LPTIM_UPDATE_MODE_IMMEDIATE
390 * @arg @ref LL_LPTIM_UPDATE_MODE_ENDOFPERIOD
391 * @retval None
393 __STATIC_INLINE void LL_LPTIM_SetUpdateMode(LPTIM_TypeDef *LPTIMx, uint32_t UpdateMode)
395 MODIFY_REG(LPTIMx->CFGR, LPTIM_CFGR_PRELOAD, UpdateMode);
399 * @brief Get the LPTIM registers update mode
400 * @rmtoll CFGR PRELOAD LL_LPTIM_GetUpdateMode
401 * @param LPTIMx Low-Power Timer instance
402 * @retval Returned value can be one of the following values:
403 * @arg @ref LL_LPTIM_UPDATE_MODE_IMMEDIATE
404 * @arg @ref LL_LPTIM_UPDATE_MODE_ENDOFPERIOD
406 __STATIC_INLINE uint32_t LL_LPTIM_GetUpdateMode(LPTIM_TypeDef *LPTIMx)
408 return (uint32_t)(READ_BIT(LPTIMx->CFGR, LPTIM_CFGR_PRELOAD));
412 * @brief Set the auto reload value
413 * @note The LPTIMx_ARR register content must only be modified when the LPTIM is enabled
414 * @note After a write to the LPTIMx_ARR register a new write operation to the
415 * same register can only be performed when the previous write operation
416 * is completed. Any successive write before the ARROK flag be set, will
417 * lead to unpredictable results.
418 * @note autoreload value be strictly greater than the compare value.
419 * @rmtoll ARR ARR LL_LPTIM_SetAutoReload
420 * @param LPTIMx Low-Power Timer instance
421 * @param AutoReload Value between Min_Data=0x00 and Max_Data=0xFFFF
422 * @retval None
424 __STATIC_INLINE void LL_LPTIM_SetAutoReload(LPTIM_TypeDef *LPTIMx, uint32_t AutoReload)
426 MODIFY_REG(LPTIMx->ARR, LPTIM_ARR_ARR, AutoReload);
430 * @brief Get actual auto reload value
431 * @rmtoll ARR ARR LL_LPTIM_GetAutoReload
432 * @param LPTIMx Low-Power Timer instance
433 * @retval AutoReload Value between Min_Data=0x00 and Max_Data=0xFFFF
435 __STATIC_INLINE uint32_t LL_LPTIM_GetAutoReload(LPTIM_TypeDef *LPTIMx)
437 return (uint32_t)(READ_BIT(LPTIMx->ARR, LPTIM_ARR_ARR));
441 * @brief Set the compare value
442 * @note After a write to the LPTIMx_CMP register a new write operation to the
443 * same register can only be performed when the previous write operation
444 * is completed. Any successive write before the CMPOK flag be set, will
445 * lead to unpredictable results.
446 * @rmtoll CMP CMP LL_LPTIM_SetCompare
447 * @param LPTIMx Low-Power Timer instance
448 * @param CompareValue Value between Min_Data=0x00 and Max_Data=0xFFFF
449 * @retval None
451 __STATIC_INLINE void LL_LPTIM_SetCompare(LPTIM_TypeDef *LPTIMx, uint32_t CompareValue)
453 MODIFY_REG(LPTIMx->CMP, LPTIM_CMP_CMP, CompareValue);
457 * @brief Get actual compare value
458 * @rmtoll CMP CMP LL_LPTIM_GetCompare
459 * @param LPTIMx Low-Power Timer instance
460 * @retval CompareValue Value between Min_Data=0x00 and Max_Data=0xFFFF
462 __STATIC_INLINE uint32_t LL_LPTIM_GetCompare(LPTIM_TypeDef *LPTIMx)
464 return (uint32_t)(READ_BIT(LPTIMx->CMP, LPTIM_CMP_CMP));
468 * @brief Get actual counter value
469 * @note When the LPTIM instance is running with an asynchronous clock, reading
470 * the LPTIMx_CNT register may return unreliable values. So in this case
471 * it is necessary to perform two consecutive read accesses and verify
472 * that the two returned values are identical.
473 * @rmtoll CNT CNT LL_LPTIM_GetCounter
474 * @param LPTIMx Low-Power Timer instance
475 * @retval Counter value
477 __STATIC_INLINE uint32_t LL_LPTIM_GetCounter(LPTIM_TypeDef *LPTIMx)
479 return (uint32_t)(READ_BIT(LPTIMx->CNT, LPTIM_CNT_CNT));
483 * @brief Set the counter mode (selection of the LPTIM counter clock source).
484 * @note The counter mode can be set only when the LPTIM instance is disabled.
485 * @rmtoll CFGR COUNTMODE LL_LPTIM_SetCounterMode
486 * @param LPTIMx Low-Power Timer instance
487 * @param CounterMode This parameter can be one of the following values:
488 * @arg @ref LL_LPTIM_COUNTER_MODE_INTERNAL
489 * @arg @ref LL_LPTIM_COUNTER_MODE_EXTERNAL
490 * @retval None
492 __STATIC_INLINE void LL_LPTIM_SetCounterMode(LPTIM_TypeDef *LPTIMx, uint32_t CounterMode)
494 MODIFY_REG(LPTIMx->CFGR, LPTIM_CFGR_COUNTMODE, CounterMode);
498 * @brief Get the counter mode
499 * @rmtoll CFGR COUNTMODE LL_LPTIM_GetCounterMode
500 * @param LPTIMx Low-Power Timer instance
501 * @retval Returned value can be one of the following values:
502 * @arg @ref LL_LPTIM_COUNTER_MODE_INTERNAL
503 * @arg @ref LL_LPTIM_COUNTER_MODE_EXTERNAL
505 __STATIC_INLINE uint32_t LL_LPTIM_GetCounterMode(LPTIM_TypeDef *LPTIMx)
507 return (uint32_t)(READ_BIT(LPTIMx->CFGR, LPTIM_CFGR_COUNTMODE));
511 * @brief Configure the LPTIM instance output (LPTIMx_OUT)
512 * @note This function must be called when the LPTIM instance is disabled.
513 * @note Regarding the LPTIM output polarity the change takes effect
514 * immediately, so the output default value will change immediately after
515 * the polarity is re-configured, even before the timer is enabled.
516 * @rmtoll CFGR WAVE LL_LPTIM_ConfigOutput\n
517 * CFGR WAVPOL LL_LPTIM_ConfigOutput
518 * @param LPTIMx Low-Power Timer instance
519 * @param Waveform This parameter can be one of the following values:
520 * @arg @ref LL_LPTIM_OUTPUT_WAVEFORM_PWM
521 * @arg @ref LL_LPTIM_OUTPUT_WAVEFORM_SETONCE
522 * @param Polarity This parameter can be one of the following values:
523 * @arg @ref LL_LPTIM_OUTPUT_POLARITY_REGULAR
524 * @arg @ref LL_LPTIM_OUTPUT_POLARITY_INVERSE
525 * @retval None
527 __STATIC_INLINE void LL_LPTIM_ConfigOutput(LPTIM_TypeDef *LPTIMx, uint32_t Waveform, uint32_t Polarity)
529 MODIFY_REG(LPTIMx->CFGR, LPTIM_CFGR_WAVE | LPTIM_CFGR_WAVPOL, Waveform | Polarity);
533 * @brief Set waveform shape
534 * @rmtoll CFGR WAVE LL_LPTIM_SetWaveform
535 * @param LPTIMx Low-Power Timer instance
536 * @param Waveform This parameter can be one of the following values:
537 * @arg @ref LL_LPTIM_OUTPUT_WAVEFORM_PWM
538 * @arg @ref LL_LPTIM_OUTPUT_WAVEFORM_SETONCE
539 * @retval None
541 __STATIC_INLINE void LL_LPTIM_SetWaveform(LPTIM_TypeDef *LPTIMx, uint32_t Waveform)
543 MODIFY_REG(LPTIMx->CFGR, LPTIM_CFGR_WAVE, Waveform);
547 * @brief Get actual waveform shape
548 * @rmtoll CFGR WAVE LL_LPTIM_GetWaveform
549 * @param LPTIMx Low-Power Timer instance
550 * @retval Returned value can be one of the following values:
551 * @arg @ref LL_LPTIM_OUTPUT_WAVEFORM_PWM
552 * @arg @ref LL_LPTIM_OUTPUT_WAVEFORM_SETONCE
554 __STATIC_INLINE uint32_t LL_LPTIM_GetWaveform(LPTIM_TypeDef *LPTIMx)
556 return (uint32_t)(READ_BIT(LPTIMx->CFGR, LPTIM_CFGR_WAVE));
560 * @brief Set output polarity
561 * @rmtoll CFGR WAVPOL LL_LPTIM_SetPolarity
562 * @param LPTIMx Low-Power Timer instance
563 * @param Polarity This parameter can be one of the following values:
564 * @arg @ref LL_LPTIM_OUTPUT_POLARITY_REGULAR
565 * @arg @ref LL_LPTIM_OUTPUT_POLARITY_INVERSE
566 * @retval None
568 __STATIC_INLINE void LL_LPTIM_SetPolarity(LPTIM_TypeDef *LPTIMx, uint32_t Polarity)
570 MODIFY_REG(LPTIMx->CFGR, LPTIM_CFGR_WAVPOL, Polarity);
574 * @brief Get actual output polarity
575 * @rmtoll CFGR WAVPOL LL_LPTIM_GetPolarity
576 * @param LPTIMx Low-Power Timer instance
577 * @retval Returned value can be one of the following values:
578 * @arg @ref LL_LPTIM_OUTPUT_POLARITY_REGULAR
579 * @arg @ref LL_LPTIM_OUTPUT_POLARITY_INVERSE
581 __STATIC_INLINE uint32_t LL_LPTIM_GetPolarity(LPTIM_TypeDef *LPTIMx)
583 return (uint32_t)(READ_BIT(LPTIMx->CFGR, LPTIM_CFGR_WAVPOL));
587 * @brief Set actual prescaler division ratio.
588 * @note This function must be called when the LPTIM instance is disabled.
589 * @note When the LPTIM is configured to be clocked by an internal clock source
590 * and the LPTIM counter is configured to be updated by active edges
591 * detected on the LPTIM external Input1, the internal clock provided to
592 * the LPTIM must be not be prescaled.
593 * @rmtoll CFGR PRESC LL_LPTIM_SetPrescaler
594 * @param LPTIMx Low-Power Timer instance
595 * @param Prescaler This parameter can be one of the following values:
596 * @arg @ref LL_LPTIM_PRESCALER_DIV1
597 * @arg @ref LL_LPTIM_PRESCALER_DIV2
598 * @arg @ref LL_LPTIM_PRESCALER_DIV4
599 * @arg @ref LL_LPTIM_PRESCALER_DIV8
600 * @arg @ref LL_LPTIM_PRESCALER_DIV16
601 * @arg @ref LL_LPTIM_PRESCALER_DIV32
602 * @arg @ref LL_LPTIM_PRESCALER_DIV64
603 * @arg @ref LL_LPTIM_PRESCALER_DIV128
604 * @retval None
606 __STATIC_INLINE void LL_LPTIM_SetPrescaler(LPTIM_TypeDef *LPTIMx, uint32_t Prescaler)
608 MODIFY_REG(LPTIMx->CFGR, LPTIM_CFGR_PRESC, Prescaler);
612 * @brief Get actual prescaler division ratio.
613 * @rmtoll CFGR PRESC LL_LPTIM_GetPrescaler
614 * @param LPTIMx Low-Power Timer instance
615 * @retval Returned value can be one of the following values:
616 * @arg @ref LL_LPTIM_PRESCALER_DIV1
617 * @arg @ref LL_LPTIM_PRESCALER_DIV2
618 * @arg @ref LL_LPTIM_PRESCALER_DIV4
619 * @arg @ref LL_LPTIM_PRESCALER_DIV8
620 * @arg @ref LL_LPTIM_PRESCALER_DIV16
621 * @arg @ref LL_LPTIM_PRESCALER_DIV32
622 * @arg @ref LL_LPTIM_PRESCALER_DIV64
623 * @arg @ref LL_LPTIM_PRESCALER_DIV128
625 __STATIC_INLINE uint32_t LL_LPTIM_GetPrescaler(LPTIM_TypeDef *LPTIMx)
627 return (uint32_t)(READ_BIT(LPTIMx->CFGR, LPTIM_CFGR_PRESC));
632 * @}
635 /** @defgroup LPTIM_LL_EF_Trigger_Configuration Trigger Configuration
636 * @{
640 * @brief Enable the timeout function
641 * @note This function must be called when the LPTIM instance is disabled.
642 * @note The first trigger event will start the timer, any successive trigger
643 * event will reset the counter and the timer will restart.
644 * @note The timeout value corresponds to the compare value; if no trigger
645 * occurs within the expected time frame, the MCU is waked-up by the
646 * compare match event.
647 * @rmtoll CFGR TIMOUT LL_LPTIM_EnableTimeout
648 * @param LPTIMx Low-Power Timer instance
649 * @retval None
651 __STATIC_INLINE void LL_LPTIM_EnableTimeout(LPTIM_TypeDef *LPTIMx)
653 SET_BIT(LPTIMx->CFGR, LPTIM_CFGR_TIMOUT);
657 * @brief Disable the timeout function
658 * @note This function must be called when the LPTIM instance is disabled.
659 * @note A trigger event arriving when the timer is already started will be
660 * ignored.
661 * @rmtoll CFGR TIMOUT LL_LPTIM_DisableTimeout
662 * @param LPTIMx Low-Power Timer instance
663 * @retval None
665 __STATIC_INLINE void LL_LPTIM_DisableTimeout(LPTIM_TypeDef *LPTIMx)
667 CLEAR_BIT(LPTIMx->CFGR, LPTIM_CFGR_TIMOUT);
671 * @brief Indicate whether the timeout function is enabled.
672 * @rmtoll CFGR TIMOUT LL_LPTIM_IsEnabledTimeout
673 * @param LPTIMx Low-Power Timer instance
674 * @retval State of bit (1 or 0).
676 __STATIC_INLINE uint32_t LL_LPTIM_IsEnabledTimeout(LPTIM_TypeDef *LPTIMx)
678 return (READ_BIT(LPTIMx->CFGR, LPTIM_CFGR_TIMOUT) == (LPTIM_CFGR_TIMOUT));
682 * @brief Start the LPTIM counter
683 * @note This function must be called when the LPTIM instance is disabled.
684 * @rmtoll CFGR TRIGEN LL_LPTIM_TrigSw
685 * @param LPTIMx Low-Power Timer instance
686 * @retval None
688 __STATIC_INLINE void LL_LPTIM_TrigSw(LPTIM_TypeDef *LPTIMx)
690 CLEAR_BIT(LPTIMx->CFGR, LPTIM_CFGR_TRIGEN);
694 * @brief Configure the external trigger used as a trigger event for the LPTIM.
695 * @note This function must be called when the LPTIM instance is disabled.
696 * @note An internal clock source must be present when a digital filter is
697 * required for the trigger.
698 * @rmtoll CFGR TRIGSEL LL_LPTIM_ConfigTrigger\n
699 * CFGR TRGFLT LL_LPTIM_ConfigTrigger\n
700 * CFGR TRIGEN LL_LPTIM_ConfigTrigger
701 * @param LPTIMx Low-Power Timer instance
702 * @param Source This parameter can be one of the following values:
703 * @arg @ref LL_LPTIM_TRIG_SOURCE_GPIO
704 * @arg @ref LL_LPTIM_TRIG_SOURCE_RTCALARMA
705 * @arg @ref LL_LPTIM_TRIG_SOURCE_RTCALARMB
706 * @arg @ref LL_LPTIM_TRIG_SOURCE_RTCTAMP1
707 * @arg @ref LL_LPTIM_TRIG_SOURCE_RTCTAMP2
708 * @arg @ref LL_LPTIM_TRIG_SOURCE_RTCTAMP3
709 * @arg @ref LL_LPTIM_TRIG_SOURCE_COMP1
710 * @arg @ref LL_LPTIM_TRIG_SOURCE_COMP2
711 * @param Filter This parameter can be one of the following values:
712 * @arg @ref LL_LPTIM_TRIG_FILTER_NONE
713 * @arg @ref LL_LPTIM_TRIG_FILTER_2
714 * @arg @ref LL_LPTIM_TRIG_FILTER_4
715 * @arg @ref LL_LPTIM_TRIG_FILTER_8
716 * @param Polarity This parameter can be one of the following values:
717 * @arg @ref LL_LPTIM_TRIG_POLARITY_RISING
718 * @arg @ref LL_LPTIM_TRIG_POLARITY_FALLING
719 * @arg @ref LL_LPTIM_TRIG_POLARITY_RISING_FALLING
720 * @retval None
722 __STATIC_INLINE void LL_LPTIM_ConfigTrigger(LPTIM_TypeDef *LPTIMx, uint32_t Source, uint32_t Filter, uint32_t Polarity)
724 MODIFY_REG(LPTIMx->CFGR, LPTIM_CFGR_TRIGSEL | LPTIM_CFGR_TRGFLT | LPTIM_CFGR_TRIGEN, Source | Filter | Polarity);
728 * @brief Get actual external trigger source.
729 * @rmtoll CFGR TRIGSEL LL_LPTIM_GetTriggerSource
730 * @param LPTIMx Low-Power Timer instance
731 * @retval Returned value can be one of the following values:
732 * @arg @ref LL_LPTIM_TRIG_SOURCE_GPIO
733 * @arg @ref LL_LPTIM_TRIG_SOURCE_RTCALARMA
734 * @arg @ref LL_LPTIM_TRIG_SOURCE_RTCALARMB
735 * @arg @ref LL_LPTIM_TRIG_SOURCE_RTCTAMP1
736 * @arg @ref LL_LPTIM_TRIG_SOURCE_RTCTAMP2
737 * @arg @ref LL_LPTIM_TRIG_SOURCE_RTCTAMP3
738 * @arg @ref LL_LPTIM_TRIG_SOURCE_COMP1
739 * @arg @ref LL_LPTIM_TRIG_SOURCE_COMP2
741 __STATIC_INLINE uint32_t LL_LPTIM_GetTriggerSource(LPTIM_TypeDef *LPTIMx)
743 return (uint32_t)(READ_BIT(LPTIMx->CFGR, LPTIM_CFGR_TRIGSEL));
747 * @brief Get actual external trigger filter.
748 * @rmtoll CFGR TRGFLT LL_LPTIM_GetTriggerFilter
749 * @param LPTIMx Low-Power Timer instance
750 * @retval Returned value can be one of the following values:
751 * @arg @ref LL_LPTIM_TRIG_FILTER_NONE
752 * @arg @ref LL_LPTIM_TRIG_FILTER_2
753 * @arg @ref LL_LPTIM_TRIG_FILTER_4
754 * @arg @ref LL_LPTIM_TRIG_FILTER_8
756 __STATIC_INLINE uint32_t LL_LPTIM_GetTriggerFilter(LPTIM_TypeDef *LPTIMx)
758 return (uint32_t)(READ_BIT(LPTIMx->CFGR, LPTIM_CFGR_TRGFLT));
762 * @brief Get actual external trigger polarity.
763 * @rmtoll CFGR TRIGEN LL_LPTIM_GetTriggerPolarity
764 * @param LPTIMx Low-Power Timer instance
765 * @retval Returned value can be one of the following values:
766 * @arg @ref LL_LPTIM_TRIG_POLARITY_RISING
767 * @arg @ref LL_LPTIM_TRIG_POLARITY_FALLING
768 * @arg @ref LL_LPTIM_TRIG_POLARITY_RISING_FALLING
770 __STATIC_INLINE uint32_t LL_LPTIM_GetTriggerPolarity(LPTIM_TypeDef *LPTIMx)
772 return (uint32_t)(READ_BIT(LPTIMx->CFGR, LPTIM_CFGR_TRIGEN));
776 * @}
779 /** @defgroup LPTIM_LL_EF_Clock_Configuration Clock Configuration
780 * @{
784 * @brief Set the source of the clock used by the LPTIM instance.
785 * @note This function must be called when the LPTIM instance is disabled.
786 * @rmtoll CFGR CKSEL LL_LPTIM_SetClockSource
787 * @param LPTIMx Low-Power Timer instance
788 * @param ClockSource This parameter can be one of the following values:
789 * @arg @ref LL_LPTIM_CLK_SOURCE_INTERNAL
790 * @arg @ref LL_LPTIM_CLK_SOURCE_EXTERNAL
791 * @retval None
793 __STATIC_INLINE void LL_LPTIM_SetClockSource(LPTIM_TypeDef *LPTIMx, uint32_t ClockSource)
795 MODIFY_REG(LPTIMx->CFGR, LPTIM_CFGR_CKSEL, ClockSource);
799 * @brief Get actual LPTIM instance clock source.
800 * @rmtoll CFGR CKSEL LL_LPTIM_GetClockSource
801 * @param LPTIMx Low-Power Timer instance
802 * @retval Returned value can be one of the following values:
803 * @arg @ref LL_LPTIM_CLK_SOURCE_INTERNAL
804 * @arg @ref LL_LPTIM_CLK_SOURCE_EXTERNAL
806 __STATIC_INLINE uint32_t LL_LPTIM_GetClockSource(LPTIM_TypeDef *LPTIMx)
808 return (uint32_t)(READ_BIT(LPTIMx->CFGR, LPTIM_CFGR_CKSEL));
812 * @brief Configure the active edge or edges used by the counter when the LPTIM is clocked by an external clock source.
813 * @note This function must be called when the LPTIM instance is disabled.
814 * @note When both external clock signal edges are considered active ones,
815 * the LPTIM must also be clocked by an internal clock source with a
816 * frequency equal to at least four times the external clock frequency.
817 * @note An internal clock source must be present when a digital filter is
818 * required for external clock.
819 * @rmtoll CFGR CKFLT LL_LPTIM_ConfigClock\n
820 * CFGR CKPOL LL_LPTIM_ConfigClock
821 * @param LPTIMx Low-Power Timer instance
822 * @param ClockFilter This parameter can be one of the following values:
823 * @arg @ref LL_LPTIM_CLK_FILTER_NONE
824 * @arg @ref LL_LPTIM_CLK_FILTER_2
825 * @arg @ref LL_LPTIM_CLK_FILTER_4
826 * @arg @ref LL_LPTIM_CLK_FILTER_8
827 * @param ClockPolarity This parameter can be one of the following values:
828 * @arg @ref LL_LPTIM_CLK_POLARITY_RISING
829 * @arg @ref LL_LPTIM_CLK_POLARITY_FALLING
830 * @arg @ref LL_LPTIM_CLK_POLARITY_RISING_FALLING
831 * @retval None
833 __STATIC_INLINE void LL_LPTIM_ConfigClock(LPTIM_TypeDef *LPTIMx, uint32_t ClockFilter, uint32_t ClockPolarity)
835 MODIFY_REG(LPTIMx->CFGR, LPTIM_CFGR_CKFLT | LPTIM_CFGR_CKPOL, ClockFilter | ClockPolarity);
839 * @brief Get actual clock polarity
840 * @rmtoll CFGR CKPOL LL_LPTIM_GetClockPolarity
841 * @param LPTIMx Low-Power Timer instance
842 * @retval Returned value can be one of the following values:
843 * @arg @ref LL_LPTIM_CLK_POLARITY_RISING
844 * @arg @ref LL_LPTIM_CLK_POLARITY_FALLING
845 * @arg @ref LL_LPTIM_CLK_POLARITY_RISING_FALLING
847 __STATIC_INLINE uint32_t LL_LPTIM_GetClockPolarity(LPTIM_TypeDef *LPTIMx)
849 return (uint32_t)(READ_BIT(LPTIMx->CFGR, LPTIM_CFGR_CKPOL));
853 * @brief Get actual clock digital filter
854 * @rmtoll CFGR CKFLT LL_LPTIM_GetClockFilter
855 * @param LPTIMx Low-Power Timer instance
856 * @retval Returned value can be one of the following values:
857 * @arg @ref LL_LPTIM_CLK_FILTER_NONE
858 * @arg @ref LL_LPTIM_CLK_FILTER_2
859 * @arg @ref LL_LPTIM_CLK_FILTER_4
860 * @arg @ref LL_LPTIM_CLK_FILTER_8
862 __STATIC_INLINE uint32_t LL_LPTIM_GetClockFilter(LPTIM_TypeDef *LPTIMx)
864 return (uint32_t)(READ_BIT(LPTIMx->CFGR, LPTIM_CFGR_CKFLT));
868 * @}
871 /** @defgroup LPTIM_LL_EF_Encoder_Mode Encoder Mode
872 * @{
876 * @brief Configure the encoder mode.
877 * @note This function must be called when the LPTIM instance is disabled.
878 * @rmtoll CFGR CKPOL LL_LPTIM_SetEncoderMode
879 * @param LPTIMx Low-Power Timer instance
880 * @param EncoderMode This parameter can be one of the following values:
881 * @arg @ref LL_LPTIM_ENCODER_MODE_RISING
882 * @arg @ref LL_LPTIM_ENCODER_MODE_FALLING
883 * @arg @ref LL_LPTIM_ENCODER_MODE_RISING_FALLING
884 * @retval None
886 __STATIC_INLINE void LL_LPTIM_SetEncoderMode(LPTIM_TypeDef *LPTIMx, uint32_t EncoderMode)
888 MODIFY_REG(LPTIMx->CFGR, LPTIM_CFGR_CKPOL, EncoderMode);
892 * @brief Get actual encoder mode.
893 * @rmtoll CFGR CKPOL LL_LPTIM_GetEncoderMode
894 * @param LPTIMx Low-Power Timer instance
895 * @retval Returned value can be one of the following values:
896 * @arg @ref LL_LPTIM_ENCODER_MODE_RISING
897 * @arg @ref LL_LPTIM_ENCODER_MODE_FALLING
898 * @arg @ref LL_LPTIM_ENCODER_MODE_RISING_FALLING
900 __STATIC_INLINE uint32_t LL_LPTIM_GetEncoderMode(LPTIM_TypeDef *LPTIMx)
902 return (uint32_t)(READ_BIT(LPTIMx->CFGR, LPTIM_CFGR_CKPOL));
906 * @brief Enable the encoder mode
907 * @note This function must be called when the LPTIM instance is disabled.
908 * @note In this mode the LPTIM instance must be clocked by an internal clock
909 * source. Also, the prescaler division ratio must be equal to 1.
910 * @note LPTIM instance must be configured in continuous mode prior enabling
911 * the encoder mode.
912 * @rmtoll CFGR ENC LL_LPTIM_EnableEncoderMode
913 * @param LPTIMx Low-Power Timer instance
914 * @retval None
916 __STATIC_INLINE void LL_LPTIM_EnableEncoderMode(LPTIM_TypeDef *LPTIMx)
918 SET_BIT(LPTIMx->CFGR, LPTIM_CFGR_ENC);
922 * @brief Disable the encoder mode
923 * @note This function must be called when the LPTIM instance is disabled.
924 * @rmtoll CFGR ENC LL_LPTIM_DisableEncoderMode
925 * @param LPTIMx Low-Power Timer instance
926 * @retval None
928 __STATIC_INLINE void LL_LPTIM_DisableEncoderMode(LPTIM_TypeDef *LPTIMx)
930 CLEAR_BIT(LPTIMx->CFGR, LPTIM_CFGR_ENC);
934 * @brief Indicates whether the LPTIM operates in encoder mode.
935 * @rmtoll CFGR ENC LL_LPTIM_IsEnabledEncoderMode
936 * @param LPTIMx Low-Power Timer instance
937 * @retval State of bit (1 or 0).
939 __STATIC_INLINE uint32_t LL_LPTIM_IsEnabledEncoderMode(LPTIM_TypeDef *LPTIMx)
941 return (READ_BIT(LPTIMx->CFGR, LPTIM_CFGR_ENC) == (LPTIM_CFGR_ENC));
945 * @}
948 /** @defgroup LPTIM_LL_EF_FLAG_Management FLAG Management
949 * @{
953 * @brief Clear the compare match flag (CMPMCF)
954 * @rmtoll ICR CMPMCF LL_LPTIM_ClearFLAG_CMPM
955 * @param LPTIMx Low-Power Timer instance
956 * @retval None
958 __STATIC_INLINE void LL_LPTIM_ClearFLAG_CMPM(LPTIM_TypeDef *LPTIMx)
960 SET_BIT(LPTIMx->ICR, LPTIM_ICR_CMPMCF);
964 * @brief Inform application whether a compare match interrupt has occurred.
965 * @rmtoll ISR CMPM LL_LPTIM_IsActiveFlag_CMPM
966 * @param LPTIMx Low-Power Timer instance
967 * @retval State of bit (1 or 0).
969 __STATIC_INLINE uint32_t LL_LPTIM_IsActiveFlag_CMPM(LPTIM_TypeDef *LPTIMx)
971 return (READ_BIT(LPTIMx->ISR, LPTIM_ISR_CMPM) == (LPTIM_ISR_CMPM));
975 * @brief Clear the autoreload match flag (ARRMCF)
976 * @rmtoll ICR ARRMCF LL_LPTIM_ClearFLAG_ARRM
977 * @param LPTIMx Low-Power Timer instance
978 * @retval None
980 __STATIC_INLINE void LL_LPTIM_ClearFLAG_ARRM(LPTIM_TypeDef *LPTIMx)
982 SET_BIT(LPTIMx->ICR, LPTIM_ICR_ARRMCF);
986 * @brief Inform application whether a autoreload match interrupt has occured.
987 * @rmtoll ISR ARRM LL_LPTIM_IsActiveFlag_ARRM
988 * @param LPTIMx Low-Power Timer instance
989 * @retval State of bit (1 or 0).
991 __STATIC_INLINE uint32_t LL_LPTIM_IsActiveFlag_ARRM(LPTIM_TypeDef *LPTIMx)
993 return (READ_BIT(LPTIMx->ISR, LPTIM_ISR_ARRM) == (LPTIM_ISR_ARRM));
997 * @brief Clear the external trigger valid edge flag(EXTTRIGCF).
998 * @rmtoll ICR EXTTRIGCF LL_LPTIM_ClearFlag_EXTTRIG
999 * @param LPTIMx Low-Power Timer instance
1000 * @retval None
1002 __STATIC_INLINE void LL_LPTIM_ClearFlag_EXTTRIG(LPTIM_TypeDef *LPTIMx)
1004 SET_BIT(LPTIMx->ICR, LPTIM_ICR_EXTTRIGCF);
1008 * @brief Inform application whether a valid edge on the selected external trigger input has occurred.
1009 * @rmtoll ISR EXTTRIG LL_LPTIM_IsActiveFlag_EXTTRIG
1010 * @param LPTIMx Low-Power Timer instance
1011 * @retval State of bit (1 or 0).
1013 __STATIC_INLINE uint32_t LL_LPTIM_IsActiveFlag_EXTTRIG(LPTIM_TypeDef *LPTIMx)
1015 return (READ_BIT(LPTIMx->ISR, LPTIM_ISR_EXTTRIG) == (LPTIM_ISR_EXTTRIG));
1019 * @brief Clear the compare register update interrupt flag (CMPOKCF).
1020 * @rmtoll ICR CMPOKCF LL_LPTIM_ClearFlag_CMPOK
1021 * @param LPTIMx Low-Power Timer instance
1022 * @retval None
1024 __STATIC_INLINE void LL_LPTIM_ClearFlag_CMPOK(LPTIM_TypeDef *LPTIMx)
1026 SET_BIT(LPTIMx->ICR, LPTIM_ICR_CMPOKCF);
1030 * @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.
1031 * @rmtoll ISR CMPOK LL_LPTIM_IsActiveFlag_CMPOK
1032 * @param LPTIMx Low-Power Timer instance
1033 * @retval State of bit (1 or 0).
1035 __STATIC_INLINE uint32_t LL_LPTIM_IsActiveFlag_CMPOK(LPTIM_TypeDef *LPTIMx)
1037 return (READ_BIT(LPTIMx->ISR, LPTIM_ISR_CMPOK) == (LPTIM_ISR_CMPOK));
1041 * @brief Clear the autoreload register update interrupt flag (ARROKCF).
1042 * @rmtoll ICR ARROKCF LL_LPTIM_ClearFlag_ARROK
1043 * @param LPTIMx Low-Power Timer instance
1044 * @retval None
1046 __STATIC_INLINE void LL_LPTIM_ClearFlag_ARROK(LPTIM_TypeDef *LPTIMx)
1048 SET_BIT(LPTIMx->ICR, LPTIM_ICR_ARROKCF);
1052 * @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.
1053 * @rmtoll ISR ARROK LL_LPTIM_IsActiveFlag_ARROK
1054 * @param LPTIMx Low-Power Timer instance
1055 * @retval State of bit (1 or 0).
1057 __STATIC_INLINE uint32_t LL_LPTIM_IsActiveFlag_ARROK(LPTIM_TypeDef *LPTIMx)
1059 return (READ_BIT(LPTIMx->ISR, LPTIM_ISR_ARROK) == (LPTIM_ISR_ARROK));
1063 * @brief Clear the counter direction change to up interrupt flag (UPCF).
1064 * @rmtoll ICR UPCF LL_LPTIM_ClearFlag_UP
1065 * @param LPTIMx Low-Power Timer instance
1066 * @retval None
1068 __STATIC_INLINE void LL_LPTIM_ClearFlag_UP(LPTIM_TypeDef *LPTIMx)
1070 SET_BIT(LPTIMx->ICR, LPTIM_ICR_UPCF);
1074 * @brief Informs the application whether the counter direction has changed from down to up (when the LPTIM instance operates in encoder mode).
1075 * @rmtoll ISR UP LL_LPTIM_IsActiveFlag_UP
1076 * @param LPTIMx Low-Power Timer instance
1077 * @retval State of bit (1 or 0).
1079 __STATIC_INLINE uint32_t LL_LPTIM_IsActiveFlag_UP(LPTIM_TypeDef *LPTIMx)
1081 return (READ_BIT(LPTIMx->ISR, LPTIM_ISR_UP) == (LPTIM_ISR_UP));
1085 * @brief Clear the counter direction change to down interrupt flag (DOWNCF).
1086 * @rmtoll ICR DOWNCF LL_LPTIM_ClearFlag_DOWN
1087 * @param LPTIMx Low-Power Timer instance
1088 * @retval None
1090 __STATIC_INLINE void LL_LPTIM_ClearFlag_DOWN(LPTIM_TypeDef *LPTIMx)
1092 SET_BIT(LPTIMx->ICR, LPTIM_ICR_DOWNCF);
1096 * @brief Informs the application whether the counter direction has changed from up to down (when the LPTIM instance operates in encoder mode).
1097 * @rmtoll ISR DOWN LL_LPTIM_IsActiveFlag_DOWN
1098 * @param LPTIMx Low-Power Timer instance
1099 * @retval State of bit (1 or 0).
1101 __STATIC_INLINE uint32_t LL_LPTIM_IsActiveFlag_DOWN(LPTIM_TypeDef *LPTIMx)
1103 return (READ_BIT(LPTIMx->ISR, LPTIM_ISR_DOWN) == (LPTIM_ISR_DOWN));
1107 * @}
1110 /** @defgroup LPTIM_LL_EF_IT_Management Interrupt Management
1111 * @{
1115 * @brief Enable compare match interrupt (CMPMIE).
1116 * @rmtoll IER CMPMIE LL_LPTIM_EnableIT_CMPM
1117 * @param LPTIMx Low-Power Timer instance
1118 * @retval None
1120 __STATIC_INLINE void LL_LPTIM_EnableIT_CMPM(LPTIM_TypeDef *LPTIMx)
1122 SET_BIT(LPTIMx->IER, LPTIM_IER_CMPMIE);
1126 * @brief Disable compare match interrupt (CMPMIE).
1127 * @rmtoll IER CMPMIE LL_LPTIM_DisableIT_CMPM
1128 * @param LPTIMx Low-Power Timer instance
1129 * @retval None
1131 __STATIC_INLINE void LL_LPTIM_DisableIT_CMPM(LPTIM_TypeDef *LPTIMx)
1133 CLEAR_BIT(LPTIMx->IER, LPTIM_IER_CMPMIE);
1137 * @brief Indicates whether the compare match interrupt (CMPMIE) is enabled.
1138 * @rmtoll IER CMPMIE LL_LPTIM_IsEnabledIT_CMPM
1139 * @param LPTIMx Low-Power Timer instance
1140 * @retval State of bit (1 or 0).
1142 __STATIC_INLINE uint32_t LL_LPTIM_IsEnabledIT_CMPM(LPTIM_TypeDef *LPTIMx)
1144 return (READ_BIT(LPTIMx->IER, LPTIM_IER_CMPMIE) == (LPTIM_IER_CMPMIE));
1148 * @brief Enable autoreload match interrupt (ARRMIE).
1149 * @rmtoll IER ARRMIE LL_LPTIM_EnableIT_ARRM
1150 * @param LPTIMx Low-Power Timer instance
1151 * @retval None
1153 __STATIC_INLINE void LL_LPTIM_EnableIT_ARRM(LPTIM_TypeDef *LPTIMx)
1155 SET_BIT(LPTIMx->IER, LPTIM_IER_ARRMIE);
1159 * @brief Disable autoreload match interrupt (ARRMIE).
1160 * @rmtoll IER ARRMIE LL_LPTIM_DisableIT_ARRM
1161 * @param LPTIMx Low-Power Timer instance
1162 * @retval None
1164 __STATIC_INLINE void LL_LPTIM_DisableIT_ARRM(LPTIM_TypeDef *LPTIMx)
1166 CLEAR_BIT(LPTIMx->IER, LPTIM_IER_ARRMIE);
1170 * @brief Indicates whether the autoreload match interrupt (ARRMIE) is enabled.
1171 * @rmtoll IER ARRMIE LL_LPTIM_IsEnabledIT_ARRM
1172 * @param LPTIMx Low-Power Timer instance
1173 * @retval State of bit (1 or 0).
1175 __STATIC_INLINE uint32_t LL_LPTIM_IsEnabledIT_ARRM(LPTIM_TypeDef *LPTIMx)
1177 return (READ_BIT(LPTIMx->IER, LPTIM_IER_ARRMIE) == (LPTIM_IER_ARRMIE));
1181 * @brief Enable external trigger valid edge interrupt (EXTTRIGIE).
1182 * @rmtoll IER EXTTRIGIE LL_LPTIM_EnableIT_EXTTRIG
1183 * @param LPTIMx Low-Power Timer instance
1184 * @retval None
1186 __STATIC_INLINE void LL_LPTIM_EnableIT_EXTTRIG(LPTIM_TypeDef *LPTIMx)
1188 SET_BIT(LPTIMx->IER, LPTIM_IER_EXTTRIGIE);
1192 * @brief Disable external trigger valid edge interrupt (EXTTRIGIE).
1193 * @rmtoll IER EXTTRIGIE LL_LPTIM_DisableIT_EXTTRIG
1194 * @param LPTIMx Low-Power Timer instance
1195 * @retval None
1197 __STATIC_INLINE void LL_LPTIM_DisableIT_EXTTRIG(LPTIM_TypeDef *LPTIMx)
1199 CLEAR_BIT(LPTIMx->IER, LPTIM_IER_EXTTRIGIE);
1203 * @brief Indicates external trigger valid edge interrupt (EXTTRIGIE) is enabled.
1204 * @rmtoll IER EXTTRIGIE LL_LPTIM_IsEnabledIT_EXTTRIG
1205 * @param LPTIMx Low-Power Timer instance
1206 * @retval State of bit (1 or 0).
1208 __STATIC_INLINE uint32_t LL_LPTIM_IsEnabledIT_EXTTRIG(LPTIM_TypeDef *LPTIMx)
1210 return (READ_BIT(LPTIMx->IER, LPTIM_IER_EXTTRIGIE) == (LPTIM_IER_EXTTRIGIE));
1214 * @brief Enable compare register write completed interrupt (CMPOKIE).
1215 * @rmtoll IER CMPOKIE LL_LPTIM_EnableIT_CMPOK
1216 * @param LPTIMx Low-Power Timer instance
1217 * @retval None
1219 __STATIC_INLINE void LL_LPTIM_EnableIT_CMPOK(LPTIM_TypeDef *LPTIMx)
1221 SET_BIT(LPTIMx->IER, LPTIM_IER_CMPOKIE);
1225 * @brief Disable compare register write completed interrupt (CMPOKIE).
1226 * @rmtoll IER CMPOKIE LL_LPTIM_DisableIT_CMPOK
1227 * @param LPTIMx Low-Power Timer instance
1228 * @retval None
1230 __STATIC_INLINE void LL_LPTIM_DisableIT_CMPOK(LPTIM_TypeDef *LPTIMx)
1232 CLEAR_BIT(LPTIMx->IER, LPTIM_IER_CMPOKIE);
1236 * @brief Indicates whether the compare register write completed interrupt (CMPOKIE) is enabled.
1237 * @rmtoll IER CMPOKIE LL_LPTIM_IsEnabledIT_CMPOK
1238 * @param LPTIMx Low-Power Timer instance
1239 * @retval State of bit (1 or 0).
1241 __STATIC_INLINE uint32_t LL_LPTIM_IsEnabledIT_CMPOK(LPTIM_TypeDef *LPTIMx)
1243 return (READ_BIT(LPTIMx->IER, LPTIM_IER_CMPOKIE) == (LPTIM_IER_CMPOKIE));
1247 * @brief Enable autoreload register write completed interrupt (ARROKIE).
1248 * @rmtoll IER ARROKIE LL_LPTIM_EnableIT_ARROK
1249 * @param LPTIMx Low-Power Timer instance
1250 * @retval None
1252 __STATIC_INLINE void LL_LPTIM_EnableIT_ARROK(LPTIM_TypeDef *LPTIMx)
1254 SET_BIT(LPTIMx->IER, LPTIM_IER_ARROKIE);
1258 * @brief Disable autoreload register write completed interrupt (ARROKIE).
1259 * @rmtoll IER ARROKIE LL_LPTIM_DisableIT_ARROK
1260 * @param LPTIMx Low-Power Timer instance
1261 * @retval None
1263 __STATIC_INLINE void LL_LPTIM_DisableIT_ARROK(LPTIM_TypeDef *LPTIMx)
1265 CLEAR_BIT(LPTIMx->IER, LPTIM_IER_ARROKIE);
1269 * @brief Indicates whether the autoreload register write completed interrupt (ARROKIE) is enabled.
1270 * @rmtoll IER ARROKIE LL_LPTIM_IsEnabledIT_ARROK
1271 * @param LPTIMx Low-Power Timer instance
1272 * @retval State of bit (1 or 0).
1274 __STATIC_INLINE uint32_t LL_LPTIM_IsEnabledIT_ARROK(LPTIM_TypeDef *LPTIMx)
1276 return (READ_BIT(LPTIMx->IER, LPTIM_IER_ARROKIE) == (LPTIM_IER_ARROKIE));
1280 * @brief Enable direction change to up interrupt (UPIE).
1281 * @rmtoll IER UPIE LL_LPTIM_EnableIT_UP
1282 * @param LPTIMx Low-Power Timer instance
1283 * @retval None
1285 __STATIC_INLINE void LL_LPTIM_EnableIT_UP(LPTIM_TypeDef *LPTIMx)
1287 SET_BIT(LPTIMx->IER, LPTIM_IER_UPIE);
1291 * @brief Disable direction change to up interrupt (UPIE).
1292 * @rmtoll IER UPIE LL_LPTIM_DisableIT_UP
1293 * @param LPTIMx Low-Power Timer instance
1294 * @retval None
1296 __STATIC_INLINE void LL_LPTIM_DisableIT_UP(LPTIM_TypeDef *LPTIMx)
1298 CLEAR_BIT(LPTIMx->IER, LPTIM_IER_UPIE);
1302 * @brief Indicates whether the direction change to up interrupt (UPIE) is enabled.
1303 * @rmtoll IER UPIE LL_LPTIM_IsEnabledIT_UP
1304 * @param LPTIMx Low-Power Timer instance
1305 * @retval State of bit (1 or 0).
1307 __STATIC_INLINE uint32_t LL_LPTIM_IsEnabledIT_UP(LPTIM_TypeDef *LPTIMx)
1309 return (READ_BIT(LPTIMx->IER, LPTIM_IER_UPIE) == (LPTIM_IER_UPIE));
1313 * @brief Enable direction change to down interrupt (DOWNIE).
1314 * @rmtoll IER DOWNIE LL_LPTIM_EnableIT_DOWN
1315 * @param LPTIMx Low-Power Timer instance
1316 * @retval None
1318 __STATIC_INLINE void LL_LPTIM_EnableIT_DOWN(LPTIM_TypeDef *LPTIMx)
1320 SET_BIT(LPTIMx->IER, LPTIM_IER_DOWNIE);
1324 * @brief Disable direction change to down interrupt (DOWNIE).
1325 * @rmtoll IER DOWNIE LL_LPTIM_DisableIT_DOWN
1326 * @param LPTIMx Low-Power Timer instance
1327 * @retval None
1329 __STATIC_INLINE void LL_LPTIM_DisableIT_DOWN(LPTIM_TypeDef *LPTIMx)
1331 CLEAR_BIT(LPTIMx->IER, LPTIM_IER_DOWNIE);
1335 * @brief Indicates whether the direction change to down interrupt (DOWNIE) is enabled.
1336 * @rmtoll IER DOWNIE LL_LPTIM_IsEnabledIT_DOWN
1337 * @param LPTIMx Low-Power Timer instance
1338 * @retval State of bit (1 or 0).
1340 __STATIC_INLINE uint32_t LL_LPTIM_IsEnabledIT_DOWN(LPTIM_TypeDef *LPTIMx)
1342 return (READ_BIT(LPTIMx->IER, LPTIM_IER_DOWNIE) == (LPTIM_IER_DOWNIE));
1346 * @}
1349 #if defined(USE_FULL_LL_DRIVER)
1350 /** @defgroup LPTIM_LL_EF_Init Initialisation and deinitialisation functions
1351 * @{
1354 ErrorStatus LL_LPTIM_DeInit(LPTIM_TypeDef *LPTIMx);
1355 void LL_LPTIM_StructInit(LL_LPTIM_InitTypeDef *LPTIM_InitStruct);
1356 ErrorStatus LL_LPTIM_Init(LPTIM_TypeDef *LPTIMx, LL_LPTIM_InitTypeDef *LPTIM_InitStruct);
1358 * @}
1360 #endif /* USE_FULL_LL_DRIVER */
1363 * @}
1367 * @}
1370 #endif /* LPTIM1 */
1373 * @}
1376 #ifdef __cplusplus
1378 #endif
1380 #endif /* __STM32F7xx_LL_LPTIM_H */
1382 /************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/