Merge pull request #11494 from haslinghuis/dshot_gpio
[betaflight.git] / lib / main / STM32F4 / Drivers / STM32F4xx_HAL_Driver / Inc / stm32f4xx_ll_lptim.h
bloba10827e96d7ce5ad67b8efcdfdbe7332260238cc
1 /**
2 ******************************************************************************
3 * @file stm32f4xx_ll_lptim.h
4 * @author MCD Application Team
5 * @version V1.7.1
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 __STM32F4xx_LL_LPTIM_H
40 #define __STM32F4xx_LL_LPTIM_H
42 #ifdef __cplusplus
43 extern "C" {
44 #endif
46 /* Includes ------------------------------------------------------------------*/
47 #include "stm32f4xx.h"
49 /** @addtogroup STM32F4xx_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_TIM1_TRGO LPTIM_CFGR_TRIGSEL_2 /*!<External input trigger is connected to TIM1*/
213 #define LL_LPTIM_TRIG_SOURCE_TIM5_TRGO (LPTIM_CFGR_TRIGSEL_2 | LPTIM_CFGR_TRIGSEL_0) /*!<External input trigger is connected to TIM5*/
215 * @}
218 /** @defgroup LPTIM_LL_EC_TRIG_FILTER Trigger Filter
219 * @{
221 #define LL_LPTIM_TRIG_FILTER_NONE 0x00000000U /*!<Any trigger active level change is considered as a valid trigger*/
222 #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*/
223 #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*/
224 #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*/
226 * @}
229 /** @defgroup LPTIM_LL_EC_TRIG_POLARITY Trigger Polarity
230 * @{
232 #define LL_LPTIM_TRIG_POLARITY_RISING LPTIM_CFGR_TRIGEN_0 /*!<LPTIM counter starts when a rising edge is detected*/
233 #define LL_LPTIM_TRIG_POLARITY_FALLING LPTIM_CFGR_TRIGEN_1 /*!<LPTIM counter starts when a falling edge is detected*/
234 #define LL_LPTIM_TRIG_POLARITY_RISING_FALLING LPTIM_CFGR_TRIGEN /*!<LPTIM counter starts when a rising or a falling edge is detected*/
236 * @}
239 /** @defgroup LPTIM_LL_EC_CLK_SOURCE Clock Source
240 * @{
242 #define LL_LPTIM_CLK_SOURCE_INTERNAL 0x00000000U /*!<LPTIM is clocked by internal clock source (APB clock or any of the embedded oscillators)*/
243 #define LL_LPTIM_CLK_SOURCE_EXTERNAL LPTIM_CFGR_CKSEL /*!<LPTIM is clocked by an external clock source through the LPTIM external Input1*/
245 * @}
248 /** @defgroup LPTIM_LL_EC_CLK_FILTER Clock Filter
249 * @{
251 #define LL_LPTIM_CLK_FILTER_NONE 0x00000000U /*!<Any external clock signal level change is considered as a valid transition*/
252 #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*/
253 #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*/
254 #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*/
256 * @}
259 /** @defgroup LPTIM_LL_EC_CLK_POLARITY Clock Polarity
260 * @{
262 #define LL_LPTIM_CLK_POLARITY_RISING 0x00000000U /*!< The rising edge is the active edge used for counting*/
263 #define LL_LPTIM_CLK_POLARITY_FALLING LPTIM_CFGR_CKPOL_0 /*!< The falling edge is the active edge used for counting*/
264 #define LL_LPTIM_CLK_POLARITY_RISING_FALLING LPTIM_CFGR_CKPOL_1 /*!< Both edges are active edges*/
266 * @}
269 /** @defgroup LPTIM_LL_EC_ENCODER_MODE Encoder Mode
270 * @{
272 #define LL_LPTIM_ENCODER_MODE_RISING 0x00000000U /*!< The rising edge is the active edge used for counting*/
273 #define LL_LPTIM_ENCODER_MODE_FALLING LPTIM_CFGR_CKPOL_0 /*!< The falling edge is the active edge used for counting*/
274 #define LL_LPTIM_ENCODER_MODE_RISING_FALLING LPTIM_CFGR_CKPOL_1 /*!< Both edges are active edges*/
276 * @}
281 * @}
284 /* Exported macro ------------------------------------------------------------*/
285 /** @defgroup LPTIM_LL_Exported_Macros LPTIM Exported Macros
286 * @{
289 /** @defgroup LPTIM_LL_EM_WRITE_READ Common Write and read registers Macros
290 * @{
294 * @brief Write a value in LPTIM register
295 * @param __INSTANCE__ LPTIM Instance
296 * @param __REG__ Register to be written
297 * @param __VALUE__ Value to be written in the register
298 * @retval None
300 #define LL_LPTIM_WriteReg(__INSTANCE__, __REG__, __VALUE__) WRITE_REG(__INSTANCE__->__REG__, (__VALUE__))
303 * @brief Read a value in LPTIM register
304 * @param __INSTANCE__ LPTIM Instance
305 * @param __REG__ Register to be read
306 * @retval Register value
308 #define LL_LPTIM_ReadReg(__INSTANCE__, __REG__) READ_REG(__INSTANCE__->__REG__)
310 * @}
314 * @}
318 /* Exported functions --------------------------------------------------------*/
319 /** @defgroup LPTIM_LL_Exported_Functions LPTIM Exported Functions
320 * @{
323 /** @defgroup LPTIM_LL_EF_LPTIM_Configuration LPTIM Configuration
324 * @{
328 * @brief Enable the LPTIM instance
329 * @note After setting the ENABLE bit, a delay of two counter clock is needed
330 * before the LPTIM instance is actually enabled.
331 * @rmtoll CR ENABLE LL_LPTIM_Enable
332 * @param LPTIMx Low-Power Timer instance
333 * @retval None
335 __STATIC_INLINE void LL_LPTIM_Enable(LPTIM_TypeDef *LPTIMx)
337 SET_BIT(LPTIMx->CR, LPTIM_CR_ENABLE);
341 * @brief Disable the LPTIM instance
342 * @rmtoll CR ENABLE LL_LPTIM_Disable
343 * @param LPTIMx Low-Power Timer instance
344 * @retval None
346 __STATIC_INLINE void LL_LPTIM_Disable(LPTIM_TypeDef *LPTIMx)
348 CLEAR_BIT(LPTIMx->CR, LPTIM_CR_ENABLE);
352 * @brief Indicates whether the LPTIM instance is enabled.
353 * @rmtoll CR ENABLE LL_LPTIM_IsEnabled
354 * @param LPTIMx Low-Power Timer instance
355 * @retval State of bit (1 or 0).
357 __STATIC_INLINE uint32_t LL_LPTIM_IsEnabled(LPTIM_TypeDef *LPTIMx)
359 return (READ_BIT(LPTIMx->CR, LPTIM_CR_ENABLE) == (LPTIM_CR_ENABLE));
363 * @brief Starts the LPTIM counter in the desired mode.
364 * @note LPTIM instance must be enabled before starting the counter.
365 * @note It is possible to change on the fly from One Shot mode to
366 * Continuous mode.
367 * @rmtoll CR CNTSTRT LL_LPTIM_StartCounter\n
368 * CR SNGSTRT LL_LPTIM_StartCounter
369 * @param LPTIMx Low-Power Timer instance
370 * @param OperatingMode This parameter can be one of the following values:
371 * @arg @ref LL_LPTIM_OPERATING_MODE_CONTINUOUS
372 * @arg @ref LL_LPTIM_OPERATING_MODE_ONESHOT
373 * @retval None
375 __STATIC_INLINE void LL_LPTIM_StartCounter(LPTIM_TypeDef *LPTIMx, uint32_t OperatingMode)
377 MODIFY_REG(LPTIMx->CR, LPTIM_CR_CNTSTRT | LPTIM_CR_SNGSTRT, OperatingMode);
382 * @brief Set the LPTIM registers update mode (enable/disable register preload)
383 * @note This function must be called when the LPTIM instance is disabled.
384 * @rmtoll CFGR PRELOAD LL_LPTIM_SetUpdateMode
385 * @param LPTIMx Low-Power Timer instance
386 * @param UpdateMode This parameter can be one of the following values:
387 * @arg @ref LL_LPTIM_UPDATE_MODE_IMMEDIATE
388 * @arg @ref LL_LPTIM_UPDATE_MODE_ENDOFPERIOD
389 * @retval None
391 __STATIC_INLINE void LL_LPTIM_SetUpdateMode(LPTIM_TypeDef *LPTIMx, uint32_t UpdateMode)
393 MODIFY_REG(LPTIMx->CFGR, LPTIM_CFGR_PRELOAD, UpdateMode);
397 * @brief Get the LPTIM registers update mode
398 * @rmtoll CFGR PRELOAD LL_LPTIM_GetUpdateMode
399 * @param LPTIMx Low-Power Timer instance
400 * @retval Returned value can be one of the following values:
401 * @arg @ref LL_LPTIM_UPDATE_MODE_IMMEDIATE
402 * @arg @ref LL_LPTIM_UPDATE_MODE_ENDOFPERIOD
404 __STATIC_INLINE uint32_t LL_LPTIM_GetUpdateMode(LPTIM_TypeDef *LPTIMx)
406 return (uint32_t)(READ_BIT(LPTIMx->CFGR, LPTIM_CFGR_PRELOAD));
410 * @brief Set the auto reload value
411 * @note The LPTIMx_ARR register content must only be modified when the LPTIM is enabled
412 * @note After a write to the LPTIMx_ARR register a new write operation to the
413 * same register can only be performed when the previous write operation
414 * is completed. Any successive write before the ARROK flag be set, will
415 * lead to unpredictable results.
416 * @note autoreload value be strictly greater than the compare value.
417 * @rmtoll ARR ARR LL_LPTIM_SetAutoReload
418 * @param LPTIMx Low-Power Timer instance
419 * @param AutoReload Value between Min_Data=0x00 and Max_Data=0xFFFF
420 * @retval None
422 __STATIC_INLINE void LL_LPTIM_SetAutoReload(LPTIM_TypeDef *LPTIMx, uint32_t AutoReload)
424 MODIFY_REG(LPTIMx->ARR, LPTIM_ARR_ARR, AutoReload);
428 * @brief Get actual auto reload value
429 * @rmtoll ARR ARR LL_LPTIM_GetAutoReload
430 * @param LPTIMx Low-Power Timer instance
431 * @retval AutoReload Value between Min_Data=0x00 and Max_Data=0xFFFF
433 __STATIC_INLINE uint32_t LL_LPTIM_GetAutoReload(LPTIM_TypeDef *LPTIMx)
435 return (uint32_t)(READ_BIT(LPTIMx->ARR, LPTIM_ARR_ARR));
439 * @brief Set the compare value
440 * @note After a write to the LPTIMx_CMP register a new write operation to the
441 * same register can only be performed when the previous write operation
442 * is completed. Any successive write before the CMPOK flag be set, will
443 * lead to unpredictable results.
444 * @rmtoll CMP CMP LL_LPTIM_SetCompare
445 * @param LPTIMx Low-Power Timer instance
446 * @param CompareValue Value between Min_Data=0x00 and Max_Data=0xFFFF
447 * @retval None
449 __STATIC_INLINE void LL_LPTIM_SetCompare(LPTIM_TypeDef *LPTIMx, uint32_t CompareValue)
451 MODIFY_REG(LPTIMx->CMP, LPTIM_CMP_CMP, CompareValue);
455 * @brief Get actual compare value
456 * @rmtoll CMP CMP LL_LPTIM_GetCompare
457 * @param LPTIMx Low-Power Timer instance
458 * @retval CompareValue Value between Min_Data=0x00 and Max_Data=0xFFFF
460 __STATIC_INLINE uint32_t LL_LPTIM_GetCompare(LPTIM_TypeDef *LPTIMx)
462 return (uint32_t)(READ_BIT(LPTIMx->CMP, LPTIM_CMP_CMP));
466 * @brief Get actual counter value
467 * @note When the LPTIM instance is running with an asynchronous clock, reading
468 * the LPTIMx_CNT register may return unreliable values. So in this case
469 * it is necessary to perform two consecutive read accesses and verify
470 * that the two returned values are identical.
471 * @rmtoll CNT CNT LL_LPTIM_GetCounter
472 * @param LPTIMx Low-Power Timer instance
473 * @retval Counter value
475 __STATIC_INLINE uint32_t LL_LPTIM_GetCounter(LPTIM_TypeDef *LPTIMx)
477 return (uint32_t)(READ_BIT(LPTIMx->CNT, LPTIM_CNT_CNT));
481 * @brief Set the counter mode (selection of the LPTIM counter clock source).
482 * @note The counter mode can be set only when the LPTIM instance is disabled.
483 * @rmtoll CFGR COUNTMODE LL_LPTIM_SetCounterMode
484 * @param LPTIMx Low-Power Timer instance
485 * @param CounterMode This parameter can be one of the following values:
486 * @arg @ref LL_LPTIM_COUNTER_MODE_INTERNAL
487 * @arg @ref LL_LPTIM_COUNTER_MODE_EXTERNAL
488 * @retval None
490 __STATIC_INLINE void LL_LPTIM_SetCounterMode(LPTIM_TypeDef *LPTIMx, uint32_t CounterMode)
492 MODIFY_REG(LPTIMx->CFGR, LPTIM_CFGR_COUNTMODE, CounterMode);
496 * @brief Get the counter mode
497 * @rmtoll CFGR COUNTMODE LL_LPTIM_GetCounterMode
498 * @param LPTIMx Low-Power Timer instance
499 * @retval Returned value can be one of the following values:
500 * @arg @ref LL_LPTIM_COUNTER_MODE_INTERNAL
501 * @arg @ref LL_LPTIM_COUNTER_MODE_EXTERNAL
503 __STATIC_INLINE uint32_t LL_LPTIM_GetCounterMode(LPTIM_TypeDef *LPTIMx)
505 return (uint32_t)(READ_BIT(LPTIMx->CFGR, LPTIM_CFGR_COUNTMODE));
509 * @brief Configure the LPTIM instance output (LPTIMx_OUT)
510 * @note This function must be called when the LPTIM instance is disabled.
511 * @note Regarding the LPTIM output polarity the change takes effect
512 * immediately, so the output default value will change immediately after
513 * the polarity is re-configured, even before the timer is enabled.
514 * @rmtoll CFGR WAVE LL_LPTIM_ConfigOutput\n
515 * CFGR WAVPOL LL_LPTIM_ConfigOutput
516 * @param LPTIMx Low-Power Timer instance
517 * @param Waveform This parameter can be one of the following values:
518 * @arg @ref LL_LPTIM_OUTPUT_WAVEFORM_PWM
519 * @arg @ref LL_LPTIM_OUTPUT_WAVEFORM_SETONCE
520 * @param Polarity This parameter can be one of the following values:
521 * @arg @ref LL_LPTIM_OUTPUT_POLARITY_REGULAR
522 * @arg @ref LL_LPTIM_OUTPUT_POLARITY_INVERSE
523 * @retval None
525 __STATIC_INLINE void LL_LPTIM_ConfigOutput(LPTIM_TypeDef *LPTIMx, uint32_t Waveform, uint32_t Polarity)
527 MODIFY_REG(LPTIMx->CFGR, LPTIM_CFGR_WAVE | LPTIM_CFGR_WAVPOL, Waveform | Polarity);
531 * @brief Set waveform shape
532 * @rmtoll CFGR WAVE LL_LPTIM_SetWaveform
533 * @param LPTIMx Low-Power Timer instance
534 * @param Waveform This parameter can be one of the following values:
535 * @arg @ref LL_LPTIM_OUTPUT_WAVEFORM_PWM
536 * @arg @ref LL_LPTIM_OUTPUT_WAVEFORM_SETONCE
537 * @retval None
539 __STATIC_INLINE void LL_LPTIM_SetWaveform(LPTIM_TypeDef *LPTIMx, uint32_t Waveform)
541 MODIFY_REG(LPTIMx->CFGR, LPTIM_CFGR_WAVE, Waveform);
545 * @brief Get actual waveform shape
546 * @rmtoll CFGR WAVE LL_LPTIM_GetWaveform
547 * @param LPTIMx Low-Power Timer instance
548 * @retval Returned value can be one of the following values:
549 * @arg @ref LL_LPTIM_OUTPUT_WAVEFORM_PWM
550 * @arg @ref LL_LPTIM_OUTPUT_WAVEFORM_SETONCE
552 __STATIC_INLINE uint32_t LL_LPTIM_GetWaveform(LPTIM_TypeDef *LPTIMx)
554 return (uint32_t)(READ_BIT(LPTIMx->CFGR, LPTIM_CFGR_WAVE));
558 * @brief Set output polarity
559 * @rmtoll CFGR WAVPOL LL_LPTIM_SetPolarity
560 * @param LPTIMx Low-Power Timer instance
561 * @param Polarity This parameter can be one of the following values:
562 * @arg @ref LL_LPTIM_OUTPUT_POLARITY_REGULAR
563 * @arg @ref LL_LPTIM_OUTPUT_POLARITY_INVERSE
564 * @retval None
566 __STATIC_INLINE void LL_LPTIM_SetPolarity(LPTIM_TypeDef *LPTIMx, uint32_t Polarity)
568 MODIFY_REG(LPTIMx->CFGR, LPTIM_CFGR_WAVPOL, Polarity);
572 * @brief Get actual output polarity
573 * @rmtoll CFGR WAVPOL LL_LPTIM_GetPolarity
574 * @param LPTIMx Low-Power Timer instance
575 * @retval Returned value can be one of the following values:
576 * @arg @ref LL_LPTIM_OUTPUT_POLARITY_REGULAR
577 * @arg @ref LL_LPTIM_OUTPUT_POLARITY_INVERSE
579 __STATIC_INLINE uint32_t LL_LPTIM_GetPolarity(LPTIM_TypeDef *LPTIMx)
581 return (uint32_t)(READ_BIT(LPTIMx->CFGR, LPTIM_CFGR_WAVPOL));
585 * @brief Set actual prescaler division ratio.
586 * @note This function must be called when the LPTIM instance is disabled.
587 * @note When the LPTIM is configured to be clocked by an internal clock source
588 * and the LPTIM counter is configured to be updated by active edges
589 * detected on the LPTIM external Input1, the internal clock provided to
590 * the LPTIM must be not be prescaled.
591 * @rmtoll CFGR PRESC LL_LPTIM_SetPrescaler
592 * @param LPTIMx Low-Power Timer instance
593 * @param Prescaler This parameter can be one of the following values:
594 * @arg @ref LL_LPTIM_PRESCALER_DIV1
595 * @arg @ref LL_LPTIM_PRESCALER_DIV2
596 * @arg @ref LL_LPTIM_PRESCALER_DIV4
597 * @arg @ref LL_LPTIM_PRESCALER_DIV8
598 * @arg @ref LL_LPTIM_PRESCALER_DIV16
599 * @arg @ref LL_LPTIM_PRESCALER_DIV32
600 * @arg @ref LL_LPTIM_PRESCALER_DIV64
601 * @arg @ref LL_LPTIM_PRESCALER_DIV128
602 * @retval None
604 __STATIC_INLINE void LL_LPTIM_SetPrescaler(LPTIM_TypeDef *LPTIMx, uint32_t Prescaler)
606 MODIFY_REG(LPTIMx->CFGR, LPTIM_CFGR_PRESC, Prescaler);
610 * @brief Get actual prescaler division ratio.
611 * @rmtoll CFGR PRESC LL_LPTIM_GetPrescaler
612 * @param LPTIMx Low-Power Timer instance
613 * @retval Returned value can be one of the following values:
614 * @arg @ref LL_LPTIM_PRESCALER_DIV1
615 * @arg @ref LL_LPTIM_PRESCALER_DIV2
616 * @arg @ref LL_LPTIM_PRESCALER_DIV4
617 * @arg @ref LL_LPTIM_PRESCALER_DIV8
618 * @arg @ref LL_LPTIM_PRESCALER_DIV16
619 * @arg @ref LL_LPTIM_PRESCALER_DIV32
620 * @arg @ref LL_LPTIM_PRESCALER_DIV64
621 * @arg @ref LL_LPTIM_PRESCALER_DIV128
623 __STATIC_INLINE uint32_t LL_LPTIM_GetPrescaler(LPTIM_TypeDef *LPTIMx)
625 return (uint32_t)(READ_BIT(LPTIMx->CFGR, LPTIM_CFGR_PRESC));
630 * @}
633 /** @defgroup LPTIM_LL_EF_Trigger_Configuration Trigger Configuration
634 * @{
638 * @brief Enable the timeout function
639 * @note This function must be called when the LPTIM instance is disabled.
640 * @note The first trigger event will start the timer, any successive trigger
641 * event will reset the counter and the timer will restart.
642 * @note The timeout value corresponds to the compare value; if no trigger
643 * occurs within the expected time frame, the MCU is waked-up by the
644 * compare match event.
645 * @rmtoll CFGR TIMOUT LL_LPTIM_EnableTimeout
646 * @param LPTIMx Low-Power Timer instance
647 * @retval None
649 __STATIC_INLINE void LL_LPTIM_EnableTimeout(LPTIM_TypeDef *LPTIMx)
651 SET_BIT(LPTIMx->CFGR, LPTIM_CFGR_TIMOUT);
655 * @brief Disable the timeout function
656 * @note This function must be called when the LPTIM instance is disabled.
657 * @note A trigger event arriving when the timer is already started will be
658 * ignored.
659 * @rmtoll CFGR TIMOUT LL_LPTIM_DisableTimeout
660 * @param LPTIMx Low-Power Timer instance
661 * @retval None
663 __STATIC_INLINE void LL_LPTIM_DisableTimeout(LPTIM_TypeDef *LPTIMx)
665 CLEAR_BIT(LPTIMx->CFGR, LPTIM_CFGR_TIMOUT);
669 * @brief Indicate whether the timeout function is enabled.
670 * @rmtoll CFGR TIMOUT LL_LPTIM_IsEnabledTimeout
671 * @param LPTIMx Low-Power Timer instance
672 * @retval State of bit (1 or 0).
674 __STATIC_INLINE uint32_t LL_LPTIM_IsEnabledTimeout(LPTIM_TypeDef *LPTIMx)
676 return (READ_BIT(LPTIMx->CFGR, LPTIM_CFGR_TIMOUT) == (LPTIM_CFGR_TIMOUT));
680 * @brief Start the LPTIM counter
681 * @note This function must be called when the LPTIM instance is disabled.
682 * @rmtoll CFGR TRIGEN LL_LPTIM_TrigSw
683 * @param LPTIMx Low-Power Timer instance
684 * @retval None
686 __STATIC_INLINE void LL_LPTIM_TrigSw(LPTIM_TypeDef *LPTIMx)
688 CLEAR_BIT(LPTIMx->CFGR, LPTIM_CFGR_TRIGEN);
692 * @brief Configure the external trigger used as a trigger event for the LPTIM.
693 * @note This function must be called when the LPTIM instance is disabled.
694 * @note An internal clock source must be present when a digital filter is
695 * required for the trigger.
696 * @rmtoll CFGR TRIGSEL LL_LPTIM_ConfigTrigger\n
697 * CFGR TRGFLT LL_LPTIM_ConfigTrigger\n
698 * CFGR TRIGEN LL_LPTIM_ConfigTrigger
699 * @param LPTIMx Low-Power Timer instance
700 * @param Source This parameter can be one of the following values:
701 * @arg @ref LL_LPTIM_TRIG_SOURCE_GPIO
702 * @arg @ref LL_LPTIM_TRIG_SOURCE_RTCALARMA
703 * @arg @ref LL_LPTIM_TRIG_SOURCE_RTCALARMB
704 * @arg @ref LL_LPTIM_TRIG_SOURCE_RTCTAMP1
705 * @arg @ref LL_LPTIM_TRIG_SOURCE_TIM1_TRGO
706 * @arg @ref LL_LPTIM_TRIG_SOURCE_TIM5_TRGO
707 * @param Filter This parameter can be one of the following values:
708 * @arg @ref LL_LPTIM_TRIG_FILTER_NONE
709 * @arg @ref LL_LPTIM_TRIG_FILTER_2
710 * @arg @ref LL_LPTIM_TRIG_FILTER_4
711 * @arg @ref LL_LPTIM_TRIG_FILTER_8
712 * @param Polarity This parameter can be one of the following values:
713 * @arg @ref LL_LPTIM_TRIG_POLARITY_RISING
714 * @arg @ref LL_LPTIM_TRIG_POLARITY_FALLING
715 * @arg @ref LL_LPTIM_TRIG_POLARITY_RISING_FALLING
716 * (*) value not defined in all devices.
717 * @retval None
719 __STATIC_INLINE void LL_LPTIM_ConfigTrigger(LPTIM_TypeDef *LPTIMx, uint32_t Source, uint32_t Filter, uint32_t Polarity)
721 MODIFY_REG(LPTIMx->CFGR, LPTIM_CFGR_TRIGSEL | LPTIM_CFGR_TRGFLT | LPTIM_CFGR_TRIGEN, Source | Filter | Polarity);
725 * @brief Get actual external trigger source.
726 * @rmtoll CFGR TRIGSEL LL_LPTIM_GetTriggerSource
727 * @param LPTIMx Low-Power Timer instance
728 * @retval Returned value can be one of the following values:
729 * @arg @ref LL_LPTIM_TRIG_SOURCE_GPIO
730 * @arg @ref LL_LPTIM_TRIG_SOURCE_RTCALARMA
731 * @arg @ref LL_LPTIM_TRIG_SOURCE_RTCALARMB
732 * @arg @ref LL_LPTIM_TRIG_SOURCE_RTCTAMP1
733 * @arg @ref LL_LPTIM_TRIG_SOURCE_TIM1_TRGO
734 * @arg @ref LL_LPTIM_TRIG_SOURCE_TIM5_TRGO
736 __STATIC_INLINE uint32_t LL_LPTIM_GetTriggerSource(LPTIM_TypeDef *LPTIMx)
738 return (uint32_t)(READ_BIT(LPTIMx->CFGR, LPTIM_CFGR_TRIGSEL));
742 * @brief Get actual external trigger filter.
743 * @rmtoll CFGR TRGFLT LL_LPTIM_GetTriggerFilter
744 * @param LPTIMx Low-Power Timer instance
745 * @retval Returned value can be one of the following values:
746 * @arg @ref LL_LPTIM_TRIG_FILTER_NONE
747 * @arg @ref LL_LPTIM_TRIG_FILTER_2
748 * @arg @ref LL_LPTIM_TRIG_FILTER_4
749 * @arg @ref LL_LPTIM_TRIG_FILTER_8
751 __STATIC_INLINE uint32_t LL_LPTIM_GetTriggerFilter(LPTIM_TypeDef *LPTIMx)
753 return (uint32_t)(READ_BIT(LPTIMx->CFGR, LPTIM_CFGR_TRGFLT));
757 * @brief Get actual external trigger polarity.
758 * @rmtoll CFGR TRIGEN LL_LPTIM_GetTriggerPolarity
759 * @param LPTIMx Low-Power Timer instance
760 * @retval Returned value can be one of the following values:
761 * @arg @ref LL_LPTIM_TRIG_POLARITY_RISING
762 * @arg @ref LL_LPTIM_TRIG_POLARITY_FALLING
763 * @arg @ref LL_LPTIM_TRIG_POLARITY_RISING_FALLING
765 __STATIC_INLINE uint32_t LL_LPTIM_GetTriggerPolarity(LPTIM_TypeDef *LPTIMx)
767 return (uint32_t)(READ_BIT(LPTIMx->CFGR, LPTIM_CFGR_TRIGEN));
771 * @}
774 /** @defgroup LPTIM_LL_EF_Clock_Configuration Clock Configuration
775 * @{
779 * @brief Set the source of the clock used by the LPTIM instance.
780 * @note This function must be called when the LPTIM instance is disabled.
781 * @rmtoll CFGR CKSEL LL_LPTIM_SetClockSource
782 * @param LPTIMx Low-Power Timer instance
783 * @param ClockSource This parameter can be one of the following values:
784 * @arg @ref LL_LPTIM_CLK_SOURCE_INTERNAL
785 * @arg @ref LL_LPTIM_CLK_SOURCE_EXTERNAL
786 * @retval None
788 __STATIC_INLINE void LL_LPTIM_SetClockSource(LPTIM_TypeDef *LPTIMx, uint32_t ClockSource)
790 MODIFY_REG(LPTIMx->CFGR, LPTIM_CFGR_CKSEL, ClockSource);
794 * @brief Get actual LPTIM instance clock source.
795 * @rmtoll CFGR CKSEL LL_LPTIM_GetClockSource
796 * @param LPTIMx Low-Power Timer instance
797 * @retval Returned value can be one of the following values:
798 * @arg @ref LL_LPTIM_CLK_SOURCE_INTERNAL
799 * @arg @ref LL_LPTIM_CLK_SOURCE_EXTERNAL
801 __STATIC_INLINE uint32_t LL_LPTIM_GetClockSource(LPTIM_TypeDef *LPTIMx)
803 return (uint32_t)(READ_BIT(LPTIMx->CFGR, LPTIM_CFGR_CKSEL));
807 * @brief Configure the active edge or edges used by the counter when the LPTIM is clocked by an external clock source.
808 * @note This function must be called when the LPTIM instance is disabled.
809 * @note When both external clock signal edges are considered active ones,
810 * the LPTIM must also be clocked by an internal clock source with a
811 * frequency equal to at least four times the external clock frequency.
812 * @note An internal clock source must be present when a digital filter is
813 * required for external clock.
814 * @rmtoll CFGR CKFLT LL_LPTIM_ConfigClock\n
815 * CFGR CKPOL LL_LPTIM_ConfigClock
816 * @param LPTIMx Low-Power Timer instance
817 * @param ClockFilter This parameter can be one of the following values:
818 * @arg @ref LL_LPTIM_CLK_FILTER_NONE
819 * @arg @ref LL_LPTIM_CLK_FILTER_2
820 * @arg @ref LL_LPTIM_CLK_FILTER_4
821 * @arg @ref LL_LPTIM_CLK_FILTER_8
822 * @param ClockPolarity This parameter can be one of the following values:
823 * @arg @ref LL_LPTIM_CLK_POLARITY_RISING
824 * @arg @ref LL_LPTIM_CLK_POLARITY_FALLING
825 * @arg @ref LL_LPTIM_CLK_POLARITY_RISING_FALLING
826 * @retval None
828 __STATIC_INLINE void LL_LPTIM_ConfigClock(LPTIM_TypeDef *LPTIMx, uint32_t ClockFilter, uint32_t ClockPolarity)
830 MODIFY_REG(LPTIMx->CFGR, LPTIM_CFGR_CKFLT | LPTIM_CFGR_CKPOL, ClockFilter | ClockPolarity);
834 * @brief Get actual clock polarity
835 * @rmtoll CFGR CKPOL LL_LPTIM_GetClockPolarity
836 * @param LPTIMx Low-Power Timer instance
837 * @retval Returned value can be one of the following values:
838 * @arg @ref LL_LPTIM_CLK_POLARITY_RISING
839 * @arg @ref LL_LPTIM_CLK_POLARITY_FALLING
840 * @arg @ref LL_LPTIM_CLK_POLARITY_RISING_FALLING
842 __STATIC_INLINE uint32_t LL_LPTIM_GetClockPolarity(LPTIM_TypeDef *LPTIMx)
844 return (uint32_t)(READ_BIT(LPTIMx->CFGR, LPTIM_CFGR_CKPOL));
848 * @brief Get actual clock digital filter
849 * @rmtoll CFGR CKFLT LL_LPTIM_GetClockFilter
850 * @param LPTIMx Low-Power Timer instance
851 * @retval Returned value can be one of the following values:
852 * @arg @ref LL_LPTIM_CLK_FILTER_NONE
853 * @arg @ref LL_LPTIM_CLK_FILTER_2
854 * @arg @ref LL_LPTIM_CLK_FILTER_4
855 * @arg @ref LL_LPTIM_CLK_FILTER_8
857 __STATIC_INLINE uint32_t LL_LPTIM_GetClockFilter(LPTIM_TypeDef *LPTIMx)
859 return (uint32_t)(READ_BIT(LPTIMx->CFGR, LPTIM_CFGR_CKFLT));
863 * @}
866 /** @defgroup LPTIM_LL_EF_Encoder_Mode Encoder Mode
867 * @{
871 * @brief Configure the encoder mode.
872 * @note This function must be called when the LPTIM instance is disabled.
873 * @rmtoll CFGR CKPOL LL_LPTIM_SetEncoderMode
874 * @param LPTIMx Low-Power Timer instance
875 * @param EncoderMode This parameter can be one of the following values:
876 * @arg @ref LL_LPTIM_ENCODER_MODE_RISING
877 * @arg @ref LL_LPTIM_ENCODER_MODE_FALLING
878 * @arg @ref LL_LPTIM_ENCODER_MODE_RISING_FALLING
879 * @retval None
881 __STATIC_INLINE void LL_LPTIM_SetEncoderMode(LPTIM_TypeDef *LPTIMx, uint32_t EncoderMode)
883 MODIFY_REG(LPTIMx->CFGR, LPTIM_CFGR_CKPOL, EncoderMode);
887 * @brief Get actual encoder mode.
888 * @rmtoll CFGR CKPOL LL_LPTIM_GetEncoderMode
889 * @param LPTIMx Low-Power Timer instance
890 * @retval Returned value can be one of the following values:
891 * @arg @ref LL_LPTIM_ENCODER_MODE_RISING
892 * @arg @ref LL_LPTIM_ENCODER_MODE_FALLING
893 * @arg @ref LL_LPTIM_ENCODER_MODE_RISING_FALLING
895 __STATIC_INLINE uint32_t LL_LPTIM_GetEncoderMode(LPTIM_TypeDef *LPTIMx)
897 return (uint32_t)(READ_BIT(LPTIMx->CFGR, LPTIM_CFGR_CKPOL));
901 * @brief Enable the encoder mode
902 * @note This function must be called when the LPTIM instance is disabled.
903 * @note In this mode the LPTIM instance must be clocked by an internal clock
904 * source. Also, the prescaler division ratio must be equal to 1.
905 * @note LPTIM instance must be configured in continuous mode prior enabling
906 * the encoder mode.
907 * @rmtoll CFGR ENC LL_LPTIM_EnableEncoderMode
908 * @param LPTIMx Low-Power Timer instance
909 * @retval None
911 __STATIC_INLINE void LL_LPTIM_EnableEncoderMode(LPTIM_TypeDef *LPTIMx)
913 SET_BIT(LPTIMx->CFGR, LPTIM_CFGR_ENC);
917 * @brief Disable the encoder mode
918 * @note This function must be called when the LPTIM instance is disabled.
919 * @rmtoll CFGR ENC LL_LPTIM_DisableEncoderMode
920 * @param LPTIMx Low-Power Timer instance
921 * @retval None
923 __STATIC_INLINE void LL_LPTIM_DisableEncoderMode(LPTIM_TypeDef *LPTIMx)
925 CLEAR_BIT(LPTIMx->CFGR, LPTIM_CFGR_ENC);
929 * @brief Indicates whether the LPTIM operates in encoder mode.
930 * @rmtoll CFGR ENC LL_LPTIM_IsEnabledEncoderMode
931 * @param LPTIMx Low-Power Timer instance
932 * @retval State of bit (1 or 0).
934 __STATIC_INLINE uint32_t LL_LPTIM_IsEnabledEncoderMode(LPTIM_TypeDef *LPTIMx)
936 return (READ_BIT(LPTIMx->CFGR, LPTIM_CFGR_ENC) == (LPTIM_CFGR_ENC));
940 * @}
943 /** @defgroup LPTIM_LL_EF_FLAG_Management FLAG Management
944 * @{
948 * @brief Clear the compare match flag (CMPMCF)
949 * @rmtoll ICR CMPMCF LL_LPTIM_ClearFLAG_CMPM
950 * @param LPTIMx Low-Power Timer instance
951 * @retval None
953 __STATIC_INLINE void LL_LPTIM_ClearFLAG_CMPM(LPTIM_TypeDef *LPTIMx)
955 SET_BIT(LPTIMx->ICR, LPTIM_ICR_CMPMCF);
959 * @brief Inform application whether a compare match interrupt has occurred.
960 * @rmtoll ISR CMPM LL_LPTIM_IsActiveFlag_CMPM
961 * @param LPTIMx Low-Power Timer instance
962 * @retval State of bit (1 or 0).
964 __STATIC_INLINE uint32_t LL_LPTIM_IsActiveFlag_CMPM(LPTIM_TypeDef *LPTIMx)
966 return (READ_BIT(LPTIMx->ISR, LPTIM_ISR_CMPM) == (LPTIM_ISR_CMPM));
970 * @brief Clear the autoreload match flag (ARRMCF)
971 * @rmtoll ICR ARRMCF LL_LPTIM_ClearFLAG_ARRM
972 * @param LPTIMx Low-Power Timer instance
973 * @retval None
975 __STATIC_INLINE void LL_LPTIM_ClearFLAG_ARRM(LPTIM_TypeDef *LPTIMx)
977 SET_BIT(LPTIMx->ICR, LPTIM_ICR_ARRMCF);
981 * @brief Inform application whether a autoreload match interrupt has occured.
982 * @rmtoll ISR ARRM LL_LPTIM_IsActiveFlag_ARRM
983 * @param LPTIMx Low-Power Timer instance
984 * @retval State of bit (1 or 0).
986 __STATIC_INLINE uint32_t LL_LPTIM_IsActiveFlag_ARRM(LPTIM_TypeDef *LPTIMx)
988 return (READ_BIT(LPTIMx->ISR, LPTIM_ISR_ARRM) == (LPTIM_ISR_ARRM));
992 * @brief Clear the external trigger valid edge flag(EXTTRIGCF).
993 * @rmtoll ICR EXTTRIGCF LL_LPTIM_ClearFlag_EXTTRIG
994 * @param LPTIMx Low-Power Timer instance
995 * @retval None
997 __STATIC_INLINE void LL_LPTIM_ClearFlag_EXTTRIG(LPTIM_TypeDef *LPTIMx)
999 SET_BIT(LPTIMx->ICR, LPTIM_ICR_EXTTRIGCF);
1003 * @brief Inform application whether a valid edge on the selected external trigger input has occurred.
1004 * @rmtoll ISR EXTTRIG LL_LPTIM_IsActiveFlag_EXTTRIG
1005 * @param LPTIMx Low-Power Timer instance
1006 * @retval State of bit (1 or 0).
1008 __STATIC_INLINE uint32_t LL_LPTIM_IsActiveFlag_EXTTRIG(LPTIM_TypeDef *LPTIMx)
1010 return (READ_BIT(LPTIMx->ISR, LPTIM_ISR_EXTTRIG) == (LPTIM_ISR_EXTTRIG));
1014 * @brief Clear the compare register update interrupt flag (CMPOKCF).
1015 * @rmtoll ICR CMPOKCF LL_LPTIM_ClearFlag_CMPOK
1016 * @param LPTIMx Low-Power Timer instance
1017 * @retval None
1019 __STATIC_INLINE void LL_LPTIM_ClearFlag_CMPOK(LPTIM_TypeDef *LPTIMx)
1021 SET_BIT(LPTIMx->ICR, LPTIM_ICR_CMPOKCF);
1025 * @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.
1026 * @rmtoll ISR CMPOK LL_LPTIM_IsActiveFlag_CMPOK
1027 * @param LPTIMx Low-Power Timer instance
1028 * @retval State of bit (1 or 0).
1030 __STATIC_INLINE uint32_t LL_LPTIM_IsActiveFlag_CMPOK(LPTIM_TypeDef *LPTIMx)
1032 return (READ_BIT(LPTIMx->ISR, LPTIM_ISR_CMPOK) == (LPTIM_ISR_CMPOK));
1036 * @brief Clear the autoreload register update interrupt flag (ARROKCF).
1037 * @rmtoll ICR ARROKCF LL_LPTIM_ClearFlag_ARROK
1038 * @param LPTIMx Low-Power Timer instance
1039 * @retval None
1041 __STATIC_INLINE void LL_LPTIM_ClearFlag_ARROK(LPTIM_TypeDef *LPTIMx)
1043 SET_BIT(LPTIMx->ICR, LPTIM_ICR_ARROKCF);
1047 * @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.
1048 * @rmtoll ISR ARROK LL_LPTIM_IsActiveFlag_ARROK
1049 * @param LPTIMx Low-Power Timer instance
1050 * @retval State of bit (1 or 0).
1052 __STATIC_INLINE uint32_t LL_LPTIM_IsActiveFlag_ARROK(LPTIM_TypeDef *LPTIMx)
1054 return (READ_BIT(LPTIMx->ISR, LPTIM_ISR_ARROK) == (LPTIM_ISR_ARROK));
1058 * @brief Clear the counter direction change to up interrupt flag (UPCF).
1059 * @rmtoll ICR UPCF LL_LPTIM_ClearFlag_UP
1060 * @param LPTIMx Low-Power Timer instance
1061 * @retval None
1063 __STATIC_INLINE void LL_LPTIM_ClearFlag_UP(LPTIM_TypeDef *LPTIMx)
1065 SET_BIT(LPTIMx->ICR, LPTIM_ICR_UPCF);
1069 * @brief Informs the application whether the counter direction has changed from down to up (when the LPTIM instance operates in encoder mode).
1070 * @rmtoll ISR UP LL_LPTIM_IsActiveFlag_UP
1071 * @param LPTIMx Low-Power Timer instance
1072 * @retval State of bit (1 or 0).
1074 __STATIC_INLINE uint32_t LL_LPTIM_IsActiveFlag_UP(LPTIM_TypeDef *LPTIMx)
1076 return (READ_BIT(LPTIMx->ISR, LPTIM_ISR_UP) == (LPTIM_ISR_UP));
1080 * @brief Clear the counter direction change to down interrupt flag (DOWNCF).
1081 * @rmtoll ICR DOWNCF LL_LPTIM_ClearFlag_DOWN
1082 * @param LPTIMx Low-Power Timer instance
1083 * @retval None
1085 __STATIC_INLINE void LL_LPTIM_ClearFlag_DOWN(LPTIM_TypeDef *LPTIMx)
1087 SET_BIT(LPTIMx->ICR, LPTIM_ICR_DOWNCF);
1091 * @brief Informs the application whether the counter direction has changed from up to down (when the LPTIM instance operates in encoder mode).
1092 * @rmtoll ISR DOWN LL_LPTIM_IsActiveFlag_DOWN
1093 * @param LPTIMx Low-Power Timer instance
1094 * @retval State of bit (1 or 0).
1096 __STATIC_INLINE uint32_t LL_LPTIM_IsActiveFlag_DOWN(LPTIM_TypeDef *LPTIMx)
1098 return (READ_BIT(LPTIMx->ISR, LPTIM_ISR_DOWN) == (LPTIM_ISR_DOWN));
1102 * @}
1105 /** @defgroup LPTIM_LL_EF_IT_Management Interrupt Management
1106 * @{
1110 * @brief Enable compare match interrupt (CMPMIE).
1111 * @rmtoll IER CMPMIE LL_LPTIM_EnableIT_CMPM
1112 * @param LPTIMx Low-Power Timer instance
1113 * @retval None
1115 __STATIC_INLINE void LL_LPTIM_EnableIT_CMPM(LPTIM_TypeDef *LPTIMx)
1117 SET_BIT(LPTIMx->IER, LPTIM_IER_CMPMIE);
1121 * @brief Disable compare match interrupt (CMPMIE).
1122 * @rmtoll IER CMPMIE LL_LPTIM_DisableIT_CMPM
1123 * @param LPTIMx Low-Power Timer instance
1124 * @retval None
1126 __STATIC_INLINE void LL_LPTIM_DisableIT_CMPM(LPTIM_TypeDef *LPTIMx)
1128 CLEAR_BIT(LPTIMx->IER, LPTIM_IER_CMPMIE);
1132 * @brief Indicates whether the compare match interrupt (CMPMIE) is enabled.
1133 * @rmtoll IER CMPMIE LL_LPTIM_IsEnabledIT_CMPM
1134 * @param LPTIMx Low-Power Timer instance
1135 * @retval State of bit (1 or 0).
1137 __STATIC_INLINE uint32_t LL_LPTIM_IsEnabledIT_CMPM(LPTIM_TypeDef *LPTIMx)
1139 return (READ_BIT(LPTIMx->IER, LPTIM_IER_CMPMIE) == (LPTIM_IER_CMPMIE));
1143 * @brief Enable autoreload match interrupt (ARRMIE).
1144 * @rmtoll IER ARRMIE LL_LPTIM_EnableIT_ARRM
1145 * @param LPTIMx Low-Power Timer instance
1146 * @retval None
1148 __STATIC_INLINE void LL_LPTIM_EnableIT_ARRM(LPTIM_TypeDef *LPTIMx)
1150 SET_BIT(LPTIMx->IER, LPTIM_IER_ARRMIE);
1154 * @brief Disable autoreload match interrupt (ARRMIE).
1155 * @rmtoll IER ARRMIE LL_LPTIM_DisableIT_ARRM
1156 * @param LPTIMx Low-Power Timer instance
1157 * @retval None
1159 __STATIC_INLINE void LL_LPTIM_DisableIT_ARRM(LPTIM_TypeDef *LPTIMx)
1161 CLEAR_BIT(LPTIMx->IER, LPTIM_IER_ARRMIE);
1165 * @brief Indicates whether the autoreload match interrupt (ARRMIE) is enabled.
1166 * @rmtoll IER ARRMIE LL_LPTIM_IsEnabledIT_ARRM
1167 * @param LPTIMx Low-Power Timer instance
1168 * @retval State of bit (1 or 0).
1170 __STATIC_INLINE uint32_t LL_LPTIM_IsEnabledIT_ARRM(LPTIM_TypeDef *LPTIMx)
1172 return (READ_BIT(LPTIMx->IER, LPTIM_IER_ARRMIE) == (LPTIM_IER_ARRMIE));
1176 * @brief Enable external trigger valid edge interrupt (EXTTRIGIE).
1177 * @rmtoll IER EXTTRIGIE LL_LPTIM_EnableIT_EXTTRIG
1178 * @param LPTIMx Low-Power Timer instance
1179 * @retval None
1181 __STATIC_INLINE void LL_LPTIM_EnableIT_EXTTRIG(LPTIM_TypeDef *LPTIMx)
1183 SET_BIT(LPTIMx->IER, LPTIM_IER_EXTTRIGIE);
1187 * @brief Disable external trigger valid edge interrupt (EXTTRIGIE).
1188 * @rmtoll IER EXTTRIGIE LL_LPTIM_DisableIT_EXTTRIG
1189 * @param LPTIMx Low-Power Timer instance
1190 * @retval None
1192 __STATIC_INLINE void LL_LPTIM_DisableIT_EXTTRIG(LPTIM_TypeDef *LPTIMx)
1194 CLEAR_BIT(LPTIMx->IER, LPTIM_IER_EXTTRIGIE);
1198 * @brief Indicates external trigger valid edge interrupt (EXTTRIGIE) is enabled.
1199 * @rmtoll IER EXTTRIGIE LL_LPTIM_IsEnabledIT_EXTTRIG
1200 * @param LPTIMx Low-Power Timer instance
1201 * @retval State of bit (1 or 0).
1203 __STATIC_INLINE uint32_t LL_LPTIM_IsEnabledIT_EXTTRIG(LPTIM_TypeDef *LPTIMx)
1205 return (READ_BIT(LPTIMx->IER, LPTIM_IER_EXTTRIGIE) == (LPTIM_IER_EXTTRIGIE));
1209 * @brief Enable compare register write completed interrupt (CMPOKIE).
1210 * @rmtoll IER CMPOKIE LL_LPTIM_EnableIT_CMPOK
1211 * @param LPTIMx Low-Power Timer instance
1212 * @retval None
1214 __STATIC_INLINE void LL_LPTIM_EnableIT_CMPOK(LPTIM_TypeDef *LPTIMx)
1216 SET_BIT(LPTIMx->IER, LPTIM_IER_CMPOKIE);
1220 * @brief Disable compare register write completed interrupt (CMPOKIE).
1221 * @rmtoll IER CMPOKIE LL_LPTIM_DisableIT_CMPOK
1222 * @param LPTIMx Low-Power Timer instance
1223 * @retval None
1225 __STATIC_INLINE void LL_LPTIM_DisableIT_CMPOK(LPTIM_TypeDef *LPTIMx)
1227 CLEAR_BIT(LPTIMx->IER, LPTIM_IER_CMPOKIE);
1231 * @brief Indicates whether the compare register write completed interrupt (CMPOKIE) is enabled.
1232 * @rmtoll IER CMPOKIE LL_LPTIM_IsEnabledIT_CMPOK
1233 * @param LPTIMx Low-Power Timer instance
1234 * @retval State of bit (1 or 0).
1236 __STATIC_INLINE uint32_t LL_LPTIM_IsEnabledIT_CMPOK(LPTIM_TypeDef *LPTIMx)
1238 return (READ_BIT(LPTIMx->IER, LPTIM_IER_CMPOKIE) == (LPTIM_IER_CMPOKIE));
1242 * @brief Enable autoreload register write completed interrupt (ARROKIE).
1243 * @rmtoll IER ARROKIE LL_LPTIM_EnableIT_ARROK
1244 * @param LPTIMx Low-Power Timer instance
1245 * @retval None
1247 __STATIC_INLINE void LL_LPTIM_EnableIT_ARROK(LPTIM_TypeDef *LPTIMx)
1249 SET_BIT(LPTIMx->IER, LPTIM_IER_ARROKIE);
1253 * @brief Disable autoreload register write completed interrupt (ARROKIE).
1254 * @rmtoll IER ARROKIE LL_LPTIM_DisableIT_ARROK
1255 * @param LPTIMx Low-Power Timer instance
1256 * @retval None
1258 __STATIC_INLINE void LL_LPTIM_DisableIT_ARROK(LPTIM_TypeDef *LPTIMx)
1260 CLEAR_BIT(LPTIMx->IER, LPTIM_IER_ARROKIE);
1264 * @brief Indicates whether the autoreload register write completed interrupt (ARROKIE) is enabled.
1265 * @rmtoll IER ARROKIE LL_LPTIM_IsEnabledIT_ARROK
1266 * @param LPTIMx Low-Power Timer instance
1267 * @retval State of bit (1 or 0).
1269 __STATIC_INLINE uint32_t LL_LPTIM_IsEnabledIT_ARROK(LPTIM_TypeDef *LPTIMx)
1271 return (READ_BIT(LPTIMx->IER, LPTIM_IER_ARROKIE) == (LPTIM_IER_ARROKIE));
1275 * @brief Enable direction change to up interrupt (UPIE).
1276 * @rmtoll IER UPIE LL_LPTIM_EnableIT_UP
1277 * @param LPTIMx Low-Power Timer instance
1278 * @retval None
1280 __STATIC_INLINE void LL_LPTIM_EnableIT_UP(LPTIM_TypeDef *LPTIMx)
1282 SET_BIT(LPTIMx->IER, LPTIM_IER_UPIE);
1286 * @brief Disable direction change to up interrupt (UPIE).
1287 * @rmtoll IER UPIE LL_LPTIM_DisableIT_UP
1288 * @param LPTIMx Low-Power Timer instance
1289 * @retval None
1291 __STATIC_INLINE void LL_LPTIM_DisableIT_UP(LPTIM_TypeDef *LPTIMx)
1293 CLEAR_BIT(LPTIMx->IER, LPTIM_IER_UPIE);
1297 * @brief Indicates whether the direction change to up interrupt (UPIE) is enabled.
1298 * @rmtoll IER UPIE LL_LPTIM_IsEnabledIT_UP
1299 * @param LPTIMx Low-Power Timer instance
1300 * @retval State of bit (1 or 0).
1302 __STATIC_INLINE uint32_t LL_LPTIM_IsEnabledIT_UP(LPTIM_TypeDef *LPTIMx)
1304 return (READ_BIT(LPTIMx->IER, LPTIM_IER_UPIE) == (LPTIM_IER_UPIE));
1308 * @brief Enable direction change to down interrupt (DOWNIE).
1309 * @rmtoll IER DOWNIE LL_LPTIM_EnableIT_DOWN
1310 * @param LPTIMx Low-Power Timer instance
1311 * @retval None
1313 __STATIC_INLINE void LL_LPTIM_EnableIT_DOWN(LPTIM_TypeDef *LPTIMx)
1315 SET_BIT(LPTIMx->IER, LPTIM_IER_DOWNIE);
1319 * @brief Disable direction change to down interrupt (DOWNIE).
1320 * @rmtoll IER DOWNIE LL_LPTIM_DisableIT_DOWN
1321 * @param LPTIMx Low-Power Timer instance
1322 * @retval None
1324 __STATIC_INLINE void LL_LPTIM_DisableIT_DOWN(LPTIM_TypeDef *LPTIMx)
1326 CLEAR_BIT(LPTIMx->IER, LPTIM_IER_DOWNIE);
1330 * @brief Indicates whether the direction change to down interrupt (DOWNIE) is enabled.
1331 * @rmtoll IER DOWNIE LL_LPTIM_IsEnabledIT_DOWN
1332 * @param LPTIMx Low-Power Timer instance
1333 * @retval State of bit (1 or 0).
1335 __STATIC_INLINE uint32_t LL_LPTIM_IsEnabledIT_DOWN(LPTIM_TypeDef *LPTIMx)
1337 return (READ_BIT(LPTIMx->IER, LPTIM_IER_DOWNIE) == (LPTIM_IER_DOWNIE));
1341 * @}
1344 #if defined(USE_FULL_LL_DRIVER)
1345 /** @defgroup LPTIM_LL_EF_Init Initialisation and deinitialisation functions
1346 * @{
1349 ErrorStatus LL_LPTIM_DeInit(LPTIM_TypeDef *LPTIMx);
1350 void LL_LPTIM_StructInit(LL_LPTIM_InitTypeDef *LPTIM_InitStruct);
1351 ErrorStatus LL_LPTIM_Init(LPTIM_TypeDef *LPTIMx, LL_LPTIM_InitTypeDef *LPTIM_InitStruct);
1353 * @}
1355 #endif /* USE_FULL_LL_DRIVER */
1358 * @}
1362 * @}
1365 #endif /* LPTIM1 */
1368 * @}
1371 #ifdef __cplusplus
1373 #endif
1375 #endif /* __STM32F4xx_LL_LPTIM_H */
1377 /************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/