2 ******************************************************************************
3 * @file stm32f4xx_ll_tim.h
4 * @author MCD Application Team
7 * @brief Header file of TIM LL module.
8 ******************************************************************************
11 * <h2><center>© 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_TIM_H
40 #define __STM32F4xx_LL_TIM_H
46 /* Includes ------------------------------------------------------------------*/
47 #include "stm32f4xx.h"
49 /** @addtogroup STM32F4xx_LL_Driver
53 #if defined (TIM1) || defined (TIM2) || defined (TIM3) || defined (TIM4) || defined (TIM5) || defined (TIM6) || defined (TIM7) || defined (TIM8) || defined (TIM9) || defined (TIM10) || defined (TIM11) || defined (TIM12) || defined (TIM13) || defined (TIM14)
55 /** @defgroup TIM_LL TIM
59 /* Private types -------------------------------------------------------------*/
60 /* Private variables ---------------------------------------------------------*/
61 /** @defgroup TIM_LL_Private_Variables TIM Private Variables
64 static const uint8_t OFFSET_TAB_CCMRx
[] =
66 0x00U
, /* 0: TIMx_CH1 */
67 0x00U
, /* 1: TIMx_CH1N */
68 0x00U
, /* 2: TIMx_CH2 */
69 0x00U
, /* 3: TIMx_CH2N */
70 0x04U
, /* 4: TIMx_CH3 */
71 0x04U
, /* 5: TIMx_CH3N */
72 0x04U
/* 6: TIMx_CH4 */
75 static const uint8_t SHIFT_TAB_OCxx
[] =
77 0U, /* 0: OC1M, OC1FE, OC1PE */
79 8U, /* 2: OC2M, OC2FE, OC2PE */
81 0U, /* 4: OC3M, OC3FE, OC3PE */
83 8U /* 6: OC4M, OC4FE, OC4PE */
86 static const uint8_t SHIFT_TAB_ICxx
[] =
88 0U, /* 0: CC1S, IC1PSC, IC1F */
90 8U, /* 2: CC2S, IC2PSC, IC2F */
92 0U, /* 4: CC3S, IC3PSC, IC3F */
94 8U /* 6: CC4S, IC4PSC, IC4F */
97 static const uint8_t SHIFT_TAB_CCxP
[] =
108 static const uint8_t SHIFT_TAB_OISx
[] =
123 /* Private constants ---------------------------------------------------------*/
124 /** @defgroup TIM_LL_Private_Constants TIM Private Constants
129 /* Remap mask definitions */
130 #define TIMx_OR_RMP_SHIFT 16U
131 #define TIMx_OR_RMP_MASK 0x0000FFFFU
132 #define TIM2_OR_RMP_MASK (TIM_OR_ITR1_RMP << TIMx_OR_RMP_SHIFT)
133 #define TIM5_OR_RMP_MASK (TIM_OR_TI4_RMP << TIMx_OR_RMP_SHIFT)
134 #define TIM11_OR_RMP_MASK (TIM_OR_TI1_RMP << TIMx_OR_RMP_SHIFT)
136 /* Mask used to set the TDG[x:0] of the DTG bits of the TIMx_BDTR register */
137 #define DT_DELAY_1 ((uint8_t)0x7FU)
138 #define DT_DELAY_2 ((uint8_t)0x3FU)
139 #define DT_DELAY_3 ((uint8_t)0x1FU)
140 #define DT_DELAY_4 ((uint8_t)0x1FU)
142 /* Mask used to set the DTG[7:5] bits of the DTG bits of the TIMx_BDTR register */
143 #define DT_RANGE_1 ((uint8_t)0x00U)
144 #define DT_RANGE_2 ((uint8_t)0x80U)
145 #define DT_RANGE_3 ((uint8_t)0xC0U)
146 #define DT_RANGE_4 ((uint8_t)0xE0U)
153 /* Private macros ------------------------------------------------------------*/
154 /** @defgroup TIM_LL_Private_Macros TIM Private Macros
157 /** @brief Convert channel id into channel index.
158 * @param __CHANNEL__ This parameter can be one of the following values:
159 * @arg @ref LL_TIM_CHANNEL_CH1
160 * @arg @ref LL_TIM_CHANNEL_CH1N
161 * @arg @ref LL_TIM_CHANNEL_CH2
162 * @arg @ref LL_TIM_CHANNEL_CH2N
163 * @arg @ref LL_TIM_CHANNEL_CH3
164 * @arg @ref LL_TIM_CHANNEL_CH3N
165 * @arg @ref LL_TIM_CHANNEL_CH4
168 #define TIM_GET_CHANNEL_INDEX( __CHANNEL__) \
169 (((__CHANNEL__) == LL_TIM_CHANNEL_CH1) ? 0U :\
170 ((__CHANNEL__) == LL_TIM_CHANNEL_CH1N) ? 1U :\
171 ((__CHANNEL__) == LL_TIM_CHANNEL_CH2) ? 2U :\
172 ((__CHANNEL__) == LL_TIM_CHANNEL_CH2N) ? 3U :\
173 ((__CHANNEL__) == LL_TIM_CHANNEL_CH3) ? 4U :\
174 ((__CHANNEL__) == LL_TIM_CHANNEL_CH3N) ? 5U : 6U)
176 /** @brief Calculate the deadtime sampling period(in ps).
177 * @param __TIMCLK__ timer input clock frequency (in Hz).
178 * @param __CKD__ This parameter can be one of the following values:
179 * @arg @ref LL_TIM_CLOCKDIVISION_DIV1
180 * @arg @ref LL_TIM_CLOCKDIVISION_DIV2
181 * @arg @ref LL_TIM_CLOCKDIVISION_DIV4
184 #define TIM_CALC_DTS(__TIMCLK__, __CKD__) \
185 (((__CKD__) == LL_TIM_CLOCKDIVISION_DIV1) ? ((uint64_t)1000000000000U/(__TIMCLK__)) : \
186 ((__CKD__) == LL_TIM_CLOCKDIVISION_DIV2) ? ((uint64_t)1000000000000U/((__TIMCLK__) >> 1U)) : \
187 ((uint64_t)1000000000000U/((__TIMCLK__) >> 2U)))
193 /* Exported types ------------------------------------------------------------*/
194 #if defined(USE_FULL_LL_DRIVER)
195 /** @defgroup TIM_LL_ES_INIT TIM Exported Init structure
200 * @brief TIM Time Base configuration structure definition.
204 uint16_t Prescaler
; /*!< Specifies the prescaler value used to divide the TIM clock.
205 This parameter can be a number between Min_Data=0x0000 and Max_Data=0xFFFF.
207 This feature can be modified afterwards using unitary function @ref LL_TIM_SetPrescaler().*/
209 uint32_t CounterMode
; /*!< Specifies the counter mode.
210 This parameter can be a value of @ref TIM_LL_EC_COUNTERMODE.
212 This feature can be modified afterwards using unitary function @ref LL_TIM_SetCounterMode().*/
214 uint32_t Autoreload
; /*!< Specifies the auto reload value to be loaded into the active
215 Auto-Reload Register at the next update event.
216 This parameter must be a number between Min_Data=0x0000 and Max_Data=0xFFFF.
217 Some timer instances may support 32 bits counters. In that case this parameter must be a number between 0x0000 and 0xFFFFFFFF.
219 This feature can be modified afterwards using unitary function @ref LL_TIM_SetAutoReload().*/
221 uint32_t ClockDivision
; /*!< Specifies the clock division.
222 This parameter can be a value of @ref TIM_LL_EC_CLOCKDIVISION.
224 This feature can be modified afterwards using unitary function @ref LL_TIM_SetClockDivision().*/
226 uint8_t RepetitionCounter
; /*!< Specifies the repetition counter value. Each time the RCR downcounter
227 reaches zero, an update event is generated and counting restarts
228 from the RCR value (N).
229 This means in PWM mode that (N+1) corresponds to:
230 - the number of PWM periods in edge-aligned mode
231 - the number of half PWM period in center-aligned mode
232 This parameter must be a number between 0x00 and 0xFF.
234 This feature can be modified afterwards using unitary function @ref LL_TIM_SetRepetitionCounter().*/
235 } LL_TIM_InitTypeDef
;
238 * @brief TIM Output Compare configuration structure definition.
242 uint32_t OCMode
; /*!< Specifies the output mode.
243 This parameter can be a value of @ref TIM_LL_EC_OCMODE.
245 This feature can be modified afterwards using unitary function @ref LL_TIM_OC_SetMode().*/
247 uint32_t OCState
; /*!< Specifies the TIM Output Compare state.
248 This parameter can be a value of @ref TIM_LL_EC_OCSTATE.
250 This feature can be modified afterwards using unitary functions @ref LL_TIM_CC_EnableChannel() or @ref LL_TIM_CC_DisableChannel().*/
252 uint32_t OCNState
; /*!< Specifies the TIM complementary Output Compare state.
253 This parameter can be a value of @ref TIM_LL_EC_OCSTATE.
255 This feature can be modified afterwards using unitary functions @ref LL_TIM_CC_EnableChannel() or @ref LL_TIM_CC_DisableChannel().*/
257 uint32_t CompareValue
; /*!< Specifies the Compare value to be loaded into the Capture Compare Register.
258 This parameter can be a number between Min_Data=0x0000 and Max_Data=0xFFFF.
260 This feature can be modified afterwards using unitary function LL_TIM_OC_SetCompareCHx (x=1..6).*/
262 uint32_t OCPolarity
; /*!< Specifies the output polarity.
263 This parameter can be a value of @ref TIM_LL_EC_OCPOLARITY.
265 This feature can be modified afterwards using unitary function @ref LL_TIM_OC_SetPolarity().*/
267 uint32_t OCNPolarity
; /*!< Specifies the complementary output polarity.
268 This parameter can be a value of @ref TIM_LL_EC_OCPOLARITY.
270 This feature can be modified afterwards using unitary function @ref LL_TIM_OC_SetPolarity().*/
273 uint32_t OCIdleState
; /*!< Specifies the TIM Output Compare pin state during Idle state.
274 This parameter can be a value of @ref TIM_LL_EC_OCIDLESTATE.
276 This feature can be modified afterwards using unitary function @ref LL_TIM_OC_SetIdleState().*/
278 uint32_t OCNIdleState
; /*!< Specifies the TIM Output Compare pin state during Idle state.
279 This parameter can be a value of @ref TIM_LL_EC_OCIDLESTATE.
281 This feature can be modified afterwards using unitary function @ref LL_TIM_OC_SetIdleState().*/
282 } LL_TIM_OC_InitTypeDef
;
285 * @brief TIM Input Capture configuration structure definition.
291 uint32_t ICPolarity
; /*!< Specifies the active edge of the input signal.
292 This parameter can be a value of @ref TIM_LL_EC_IC_POLARITY.
294 This feature can be modified afterwards using unitary function @ref LL_TIM_IC_SetPolarity().*/
296 uint32_t ICActiveInput
; /*!< Specifies the input.
297 This parameter can be a value of @ref TIM_LL_EC_ACTIVEINPUT.
299 This feature can be modified afterwards using unitary function @ref LL_TIM_IC_SetActiveInput().*/
301 uint32_t ICPrescaler
; /*!< Specifies the Input Capture Prescaler.
302 This parameter can be a value of @ref TIM_LL_EC_ICPSC.
304 This feature can be modified afterwards using unitary function @ref LL_TIM_IC_SetPrescaler().*/
306 uint32_t ICFilter
; /*!< Specifies the input capture filter.
307 This parameter can be a value of @ref TIM_LL_EC_IC_FILTER.
309 This feature can be modified afterwards using unitary function @ref LL_TIM_IC_SetFilter().*/
310 } LL_TIM_IC_InitTypeDef
;
314 * @brief TIM Encoder interface configuration structure definition.
318 uint32_t EncoderMode
; /*!< Specifies the encoder resolution (x2 or x4).
319 This parameter can be a value of @ref TIM_LL_EC_ENCODERMODE.
321 This feature can be modified afterwards using unitary function @ref LL_TIM_SetEncoderMode().*/
323 uint32_t IC1Polarity
; /*!< Specifies the active edge of TI1 input.
324 This parameter can be a value of @ref TIM_LL_EC_IC_POLARITY.
326 This feature can be modified afterwards using unitary function @ref LL_TIM_IC_SetPolarity().*/
328 uint32_t IC1ActiveInput
; /*!< Specifies the TI1 input source
329 This parameter can be a value of @ref TIM_LL_EC_ACTIVEINPUT.
331 This feature can be modified afterwards using unitary function @ref LL_TIM_IC_SetActiveInput().*/
333 uint32_t IC1Prescaler
; /*!< Specifies the TI1 input prescaler value.
334 This parameter can be a value of @ref TIM_LL_EC_ICPSC.
336 This feature can be modified afterwards using unitary function @ref LL_TIM_IC_SetPrescaler().*/
338 uint32_t IC1Filter
; /*!< Specifies the TI1 input filter.
339 This parameter can be a value of @ref TIM_LL_EC_IC_FILTER.
341 This feature can be modified afterwards using unitary function @ref LL_TIM_IC_SetFilter().*/
343 uint32_t IC2Polarity
; /*!< Specifies the active edge of TI2 input.
344 This parameter can be a value of @ref TIM_LL_EC_IC_POLARITY.
346 This feature can be modified afterwards using unitary function @ref LL_TIM_IC_SetPolarity().*/
348 uint32_t IC2ActiveInput
; /*!< Specifies the TI2 input source
349 This parameter can be a value of @ref TIM_LL_EC_ACTIVEINPUT.
351 This feature can be modified afterwards using unitary function @ref LL_TIM_IC_SetActiveInput().*/
353 uint32_t IC2Prescaler
; /*!< Specifies the TI2 input prescaler value.
354 This parameter can be a value of @ref TIM_LL_EC_ICPSC.
356 This feature can be modified afterwards using unitary function @ref LL_TIM_IC_SetPrescaler().*/
358 uint32_t IC2Filter
; /*!< Specifies the TI2 input filter.
359 This parameter can be a value of @ref TIM_LL_EC_IC_FILTER.
361 This feature can be modified afterwards using unitary function @ref LL_TIM_IC_SetFilter().*/
363 } LL_TIM_ENCODER_InitTypeDef
;
366 * @brief TIM Hall sensor interface configuration structure definition.
371 uint32_t IC1Polarity
; /*!< Specifies the active edge of TI1 input.
372 This parameter can be a value of @ref TIM_LL_EC_IC_POLARITY.
374 This feature can be modified afterwards using unitary function @ref LL_TIM_IC_SetPolarity().*/
376 uint32_t IC1Prescaler
; /*!< Specifies the TI1 input prescaler value.
377 Prescaler must be set to get a maximum counter period longer than the
378 time interval between 2 consecutive changes on the Hall inputs.
379 This parameter can be a value of @ref TIM_LL_EC_ICPSC.
381 This feature can be modified afterwards using unitary function @ref LL_TIM_IC_SetPrescaler().*/
383 uint32_t IC1Filter
; /*!< Specifies the TI1 input filter.
384 This parameter can be a value of @ref TIM_LL_EC_IC_FILTER.
386 This feature can be modified afterwards using unitary function @ref LL_TIM_IC_SetFilter().*/
388 uint32_t CommutationDelay
; /*!< Specifies the compare value to be loaded into the Capture Compare Register.
389 A positive pulse (TRGO event) is generated with a programmable delay every time
390 a change occurs on the Hall inputs.
391 This parameter can be a number between Min_Data = 0x0000 and Max_Data = 0xFFFF.
393 This feature can be modified afterwards using unitary function @ref LL_TIM_OC_SetCompareCH2().*/
394 } LL_TIM_HALLSENSOR_InitTypeDef
;
397 * @brief BDTR (Break and Dead Time) structure definition
401 uint32_t OSSRState
; /*!< Specifies the Off-State selection used in Run mode.
402 This parameter can be a value of @ref TIM_LL_EC_OSSR
404 This feature can be modified afterwards using unitary function @ref LL_TIM_SetOffStates()
406 @note This bit-field cannot be modified as long as LOCK level 2 has been programmed. */
408 uint32_t OSSIState
; /*!< Specifies the Off-State used in Idle state.
409 This parameter can be a value of @ref TIM_LL_EC_OSSI
411 This feature can be modified afterwards using unitary function @ref LL_TIM_SetOffStates()
413 @note This bit-field cannot be modified as long as LOCK level 2 has been programmed. */
415 uint32_t LockLevel
; /*!< Specifies the LOCK level parameters.
416 This parameter can be a value of @ref TIM_LL_EC_LOCKLEVEL
418 @note The LOCK bits can be written only once after the reset. Once the TIMx_BDTR register
419 has been written, their content is frozen until the next reset.*/
421 uint8_t DeadTime
; /*!< Specifies the delay time between the switching-off and the
422 switching-on of the outputs.
423 This parameter can be a number between Min_Data = 0x00 and Max_Data = 0xFF.
425 This feature can be modified afterwards using unitary function @ref LL_TIM_OC_SetDeadTime()
427 @note This bit-field can not be modified as long as LOCK level 1, 2 or 3 has been programmed. */
429 uint16_t BreakState
; /*!< Specifies whether the TIM Break input is enabled or not.
430 This parameter can be a value of @ref TIM_LL_EC_BREAK_ENABLE
432 This feature can be modified afterwards using unitary functions @ref LL_TIM_EnableBRK() or @ref LL_TIM_DisableBRK()
434 @note This bit-field can not be modified as long as LOCK level 1 has been programmed. */
436 uint32_t BreakPolarity
; /*!< Specifies the TIM Break Input pin polarity.
437 This parameter can be a value of @ref TIM_LL_EC_BREAK_POLARITY
439 This feature can be modified afterwards using unitary function @ref LL_TIM_ConfigBRK()
441 @note This bit-field can not be modified as long as LOCK level 1 has been programmed. */
443 uint32_t AutomaticOutput
; /*!< Specifies whether the TIM Automatic Output feature is enabled or not.
444 This parameter can be a value of @ref TIM_LL_EC_AUTOMATICOUTPUT_ENABLE
446 This feature can be modified afterwards using unitary functions @ref LL_TIM_EnableAutomaticOutput() or @ref LL_TIM_DisableAutomaticOutput()
448 @note This bit-field can not be modified as long as LOCK level 1 has been programmed. */
449 } LL_TIM_BDTR_InitTypeDef
;
454 #endif /* USE_FULL_LL_DRIVER */
456 /* Exported constants --------------------------------------------------------*/
457 /** @defgroup TIM_LL_Exported_Constants TIM Exported Constants
461 /** @defgroup TIM_LL_EC_GET_FLAG Get Flags Defines
462 * @brief Flags defines which can be used with LL_TIM_ReadReg function.
465 #define LL_TIM_SR_UIF TIM_SR_UIF /*!< Update interrupt flag */
466 #define LL_TIM_SR_CC1IF TIM_SR_CC1IF /*!< Capture/compare 1 interrupt flag */
467 #define LL_TIM_SR_CC2IF TIM_SR_CC2IF /*!< Capture/compare 2 interrupt flag */
468 #define LL_TIM_SR_CC3IF TIM_SR_CC3IF /*!< Capture/compare 3 interrupt flag */
469 #define LL_TIM_SR_CC4IF TIM_SR_CC4IF /*!< Capture/compare 4 interrupt flag */
470 #define LL_TIM_SR_COMIF TIM_SR_COMIF /*!< COM interrupt flag */
471 #define LL_TIM_SR_TIF TIM_SR_TIF /*!< Trigger interrupt flag */
472 #define LL_TIM_SR_BIF TIM_SR_BIF /*!< Break interrupt flag */
473 #define LL_TIM_SR_CC1OF TIM_SR_CC1OF /*!< Capture/Compare 1 overcapture flag */
474 #define LL_TIM_SR_CC2OF TIM_SR_CC2OF /*!< Capture/Compare 2 overcapture flag */
475 #define LL_TIM_SR_CC3OF TIM_SR_CC3OF /*!< Capture/Compare 3 overcapture flag */
476 #define LL_TIM_SR_CC4OF TIM_SR_CC4OF /*!< Capture/Compare 4 overcapture flag */
481 #if defined(USE_FULL_LL_DRIVER)
482 /** @defgroup TIM_LL_EC_BREAK_ENABLE Break Enable
485 #define LL_TIM_BREAK_DISABLE 0x00000000U /*!< Break function disabled */
486 #define LL_TIM_BREAK_ENABLE TIM_BDTR_BKE /*!< Break function enabled */
491 /** @defgroup TIM_LL_EC_AUTOMATICOUTPUT_ENABLE Automatic output enable
494 #define LL_TIM_AUTOMATICOUTPUT_DISABLE 0x00000000U /*!< MOE can be set only by software */
495 #define LL_TIM_AUTOMATICOUTPUT_ENABLE TIM_BDTR_AOE /*!< MOE can be set by software or automatically at the next update event */
499 #endif /* USE_FULL_LL_DRIVER */
501 /** @defgroup TIM_LL_EC_IT IT Defines
502 * @brief IT defines which can be used with LL_TIM_ReadReg and LL_TIM_WriteReg functions.
505 #define LL_TIM_DIER_UIE TIM_DIER_UIE /*!< Update interrupt enable */
506 #define LL_TIM_DIER_CC1IE TIM_DIER_CC1IE /*!< Capture/compare 1 interrupt enable */
507 #define LL_TIM_DIER_CC2IE TIM_DIER_CC2IE /*!< Capture/compare 2 interrupt enable */
508 #define LL_TIM_DIER_CC3IE TIM_DIER_CC3IE /*!< Capture/compare 3 interrupt enable */
509 #define LL_TIM_DIER_CC4IE TIM_DIER_CC4IE /*!< Capture/compare 4 interrupt enable */
510 #define LL_TIM_DIER_COMIE TIM_DIER_COMIE /*!< COM interrupt enable */
511 #define LL_TIM_DIER_TIE TIM_DIER_TIE /*!< Trigger interrupt enable */
512 #define LL_TIM_DIER_BIE TIM_DIER_BIE /*!< Break interrupt enable */
517 /** @defgroup TIM_LL_EC_UPDATESOURCE Update Source
520 #define LL_TIM_UPDATESOURCE_REGULAR 0x00000000U /*!< Counter overflow/underflow, Setting the UG bit or Update generation through the slave mode controller generates an update request */
521 #define LL_TIM_UPDATESOURCE_COUNTER TIM_CR1_URS /*!< Only counter overflow/underflow generates an update request */
526 /** @defgroup TIM_LL_EC_ONEPULSEMODE One Pulse Mode
529 #define LL_TIM_ONEPULSEMODE_SINGLE TIM_CR1_OPM /*!< Counter is not stopped at update event */
530 #define LL_TIM_ONEPULSEMODE_REPETITIVE 0x00000000U /*!< Counter stops counting at the next update event */
535 /** @defgroup TIM_LL_EC_COUNTERMODE Counter Mode
538 #define LL_TIM_COUNTERMODE_UP 0x00000000U /*!<Counter used as upcounter */
539 #define LL_TIM_COUNTERMODE_DOWN TIM_CR1_DIR /*!< Counter used as downcounter */
540 #define LL_TIM_COUNTERMODE_CENTER_UP TIM_CR1_CMS_0 /*!< The counter counts up and down alternatively. Output compare interrupt flags of output channels are set only when the counter is counting down. */
541 #define LL_TIM_COUNTERMODE_CENTER_DOWN TIM_CR1_CMS_1 /*!<The counter counts up and down alternatively. Output compare interrupt flags of output channels are set only when the counter is counting up */
542 #define LL_TIM_COUNTERMODE_CENTER_UP_DOWN TIM_CR1_CMS /*!< The counter counts up and down alternatively. Output compare interrupt flags of output channels are set only when the counter is counting up or down. */
547 /** @defgroup TIM_LL_EC_CLOCKDIVISION Clock Division
550 #define LL_TIM_CLOCKDIVISION_DIV1 0x00000000U /*!< tDTS=tCK_INT */
551 #define LL_TIM_CLOCKDIVISION_DIV2 TIM_CR1_CKD_0 /*!< tDTS=2*tCK_INT */
552 #define LL_TIM_CLOCKDIVISION_DIV4 TIM_CR1_CKD_1 /*!< tDTS=4*tCK_INT */
557 /** @defgroup TIM_LL_EC_COUNTERDIRECTION Counter Direction
560 #define LL_TIM_COUNTERDIRECTION_UP 0x00000000U /*!< Timer counter counts up */
561 #define LL_TIM_COUNTERDIRECTION_DOWN TIM_CR1_DIR /*!< Timer counter counts down */
566 /** @defgroup TIM_LL_EC_CCUPDATESOURCE Capture Compare Update Source
569 #define LL_TIM_CCUPDATESOURCE_COMG_ONLY 0x00000000U /*!< Capture/compare control bits are updated by setting the COMG bit only */
570 #define LL_TIM_CCUPDATESOURCE_COMG_AND_TRGI TIM_CR2_CCUS /*!< Capture/compare control bits are updated by setting the COMG bit or when a rising edge occurs on trigger input (TRGI) */
575 /** @defgroup TIM_LL_EC_CCDMAREQUEST Capture Compare DMA Request
578 #define LL_TIM_CCDMAREQUEST_CC 0x00000000U /*!< CCx DMA request sent when CCx event occurs */
579 #define LL_TIM_CCDMAREQUEST_UPDATE TIM_CR2_CCDS /*!< CCx DMA requests sent when update event occurs */
584 /** @defgroup TIM_LL_EC_LOCKLEVEL Lock Level
587 #define LL_TIM_LOCKLEVEL_OFF 0x00000000U /*!< LOCK OFF - No bit is write protected */
588 #define LL_TIM_LOCKLEVEL_1 TIM_BDTR_LOCK_0 /*!< LOCK Level 1 */
589 #define LL_TIM_LOCKLEVEL_2 TIM_BDTR_LOCK_1 /*!< LOCK Level 2 */
590 #define LL_TIM_LOCKLEVEL_3 TIM_BDTR_LOCK /*!< LOCK Level 3 */
595 /** @defgroup TIM_LL_EC_CHANNEL Channel
598 #define LL_TIM_CHANNEL_CH1 TIM_CCER_CC1E /*!< Timer input/output channel 1 */
599 #define LL_TIM_CHANNEL_CH1N TIM_CCER_CC1NE /*!< Timer complementary output channel 1 */
600 #define LL_TIM_CHANNEL_CH2 TIM_CCER_CC2E /*!< Timer input/output channel 2 */
601 #define LL_TIM_CHANNEL_CH2N TIM_CCER_CC2NE /*!< Timer complementary output channel 2 */
602 #define LL_TIM_CHANNEL_CH3 TIM_CCER_CC3E /*!< Timer input/output channel 3 */
603 #define LL_TIM_CHANNEL_CH3N TIM_CCER_CC3NE /*!< Timer complementary output channel 3 */
604 #define LL_TIM_CHANNEL_CH4 TIM_CCER_CC4E /*!< Timer input/output channel 4 */
609 #if defined(USE_FULL_LL_DRIVER)
610 /** @defgroup TIM_LL_EC_OCSTATE Output Configuration State
613 #define LL_TIM_OCSTATE_DISABLE 0x00000000U /*!< OCx is not active */
614 #define LL_TIM_OCSTATE_ENABLE TIM_CCER_CC1E /*!< OCx signal is output on the corresponding output pin */
618 #endif /* USE_FULL_LL_DRIVER */
620 /** @defgroup TIM_LL_EC_OCMODE Output Configuration Mode
623 #define LL_TIM_OCMODE_FROZEN 0x00000000U /*!<The comparison between the output compare register TIMx_CCRy and the counter TIMx_CNT has no effect on the output channel level */
624 #define LL_TIM_OCMODE_ACTIVE TIM_CCMR1_OC1M_0 /*!<OCyREF is forced high on compare match*/
625 #define LL_TIM_OCMODE_INACTIVE TIM_CCMR1_OC1M_1 /*!<OCyREF is forced low on compare match*/
626 #define LL_TIM_OCMODE_TOGGLE (TIM_CCMR1_OC1M_1 | TIM_CCMR1_OC1M_0) /*!<OCyREF toggles on compare match*/
627 #define LL_TIM_OCMODE_FORCED_INACTIVE TIM_CCMR1_OC1M_2 /*!<OCyREF is forced low*/
628 #define LL_TIM_OCMODE_FORCED_ACTIVE (TIM_CCMR1_OC1M_2 | TIM_CCMR1_OC1M_0) /*!<OCyREF is forced high*/
629 #define LL_TIM_OCMODE_PWM1 (TIM_CCMR1_OC1M_2 | TIM_CCMR1_OC1M_1) /*!<In upcounting, channel y is active as long as TIMx_CNT<TIMx_CCRy else inactive. In downcounting, channel y is inactive as long as TIMx_CNT>TIMx_CCRy else active.*/
630 #define LL_TIM_OCMODE_PWM2 (TIM_CCMR1_OC1M_2 | TIM_CCMR1_OC1M_1 | TIM_CCMR1_OC1M_0) /*!<In upcounting, channel y is inactive as long as TIMx_CNT<TIMx_CCRy else active. In downcounting, channel y is active as long as TIMx_CNT>TIMx_CCRy else inactive*/
635 /** @defgroup TIM_LL_EC_OCPOLARITY Output Configuration Polarity
638 #define LL_TIM_OCPOLARITY_HIGH 0x00000000U /*!< OCxactive high*/
639 #define LL_TIM_OCPOLARITY_LOW TIM_CCER_CC1P /*!< OCxactive low*/
644 /** @defgroup TIM_LL_EC_OCIDLESTATE Output Configuration Idle State
647 #define LL_TIM_OCIDLESTATE_LOW 0x00000000U /*!<OCx=0 (after a dead-time if OC is implemented) when MOE=0*/
648 #define LL_TIM_OCIDLESTATE_HIGH TIM_CR2_OIS1 /*!<OCx=1 (after a dead-time if OC is implemented) when MOE=0*/
654 /** @defgroup TIM_LL_EC_ACTIVEINPUT Active Input Selection
657 #define LL_TIM_ACTIVEINPUT_DIRECTTI (TIM_CCMR1_CC1S_0 << 16U) /*!< ICx is mapped on TIx */
658 #define LL_TIM_ACTIVEINPUT_INDIRECTTI (TIM_CCMR1_CC1S_1 << 16U) /*!< ICx is mapped on TIy */
659 #define LL_TIM_ACTIVEINPUT_TRC (TIM_CCMR1_CC1S << 16U) /*!< ICx is mapped on TRC */
664 /** @defgroup TIM_LL_EC_ICPSC Input Configuration Prescaler
667 #define LL_TIM_ICPSC_DIV1 0x00000000U /*!< No prescaler, capture is done each time an edge is detected on the capture input */
668 #define LL_TIM_ICPSC_DIV2 (TIM_CCMR1_IC1PSC_0 << 16U) /*!< Capture is done once every 2 events */
669 #define LL_TIM_ICPSC_DIV4 (TIM_CCMR1_IC1PSC_1 << 16U) /*!< Capture is done once every 4 events */
670 #define LL_TIM_ICPSC_DIV8 (TIM_CCMR1_IC1PSC << 16U) /*!< Capture is done once every 8 events */
675 /** @defgroup TIM_LL_EC_IC_FILTER Input Configuration Filter
678 #define LL_TIM_IC_FILTER_FDIV1 0x00000000U /*!< No filter, sampling is done at fDTS */
679 #define LL_TIM_IC_FILTER_FDIV1_N2 (TIM_CCMR1_IC1F_0 << 16U) /*!< fSAMPLING=fCK_INT, N=2 */
680 #define LL_TIM_IC_FILTER_FDIV1_N4 (TIM_CCMR1_IC1F_1 << 16U) /*!< fSAMPLING=fCK_INT, N=4 */
681 #define LL_TIM_IC_FILTER_FDIV1_N8 ((TIM_CCMR1_IC1F_1 | TIM_CCMR1_IC1F_0) << 16U) /*!< fSAMPLING=fCK_INT, N=8 */
682 #define LL_TIM_IC_FILTER_FDIV2_N6 (TIM_CCMR1_IC1F_2 << 16U) /*!< fSAMPLING=fDTS/2, N=6 */
683 #define LL_TIM_IC_FILTER_FDIV2_N8 ((TIM_CCMR1_IC1F_2 | TIM_CCMR1_IC1F_0) << 16U) /*!< fSAMPLING=fDTS/2, N=8 */
684 #define LL_TIM_IC_FILTER_FDIV4_N6 ((TIM_CCMR1_IC1F_2 | TIM_CCMR1_IC1F_1) << 16U) /*!< fSAMPLING=fDTS/4, N=6 */
685 #define LL_TIM_IC_FILTER_FDIV4_N8 ((TIM_CCMR1_IC1F_2 | TIM_CCMR1_IC1F_1 | TIM_CCMR1_IC1F_0) << 16U) /*!< fSAMPLING=fDTS/4, N=8 */
686 #define LL_TIM_IC_FILTER_FDIV8_N6 (TIM_CCMR1_IC1F_3 << 16U) /*!< fSAMPLING=fDTS/8, N=6 */
687 #define LL_TIM_IC_FILTER_FDIV8_N8 ((TIM_CCMR1_IC1F_3 | TIM_CCMR1_IC1F_0) << 16U) /*!< fSAMPLING=fDTS/8, N=8 */
688 #define LL_TIM_IC_FILTER_FDIV16_N5 ((TIM_CCMR1_IC1F_3 | TIM_CCMR1_IC1F_1) << 16U) /*!< fSAMPLING=fDTS/16, N=5 */
689 #define LL_TIM_IC_FILTER_FDIV16_N6 ((TIM_CCMR1_IC1F_3 | TIM_CCMR1_IC1F_1 | TIM_CCMR1_IC1F_0) << 16U) /*!< fSAMPLING=fDTS/16, N=6 */
690 #define LL_TIM_IC_FILTER_FDIV16_N8 ((TIM_CCMR1_IC1F_3 | TIM_CCMR1_IC1F_2) << 16U) /*!< fSAMPLING=fDTS/16, N=8 */
691 #define LL_TIM_IC_FILTER_FDIV32_N5 ((TIM_CCMR1_IC1F_3 | TIM_CCMR1_IC1F_2 | TIM_CCMR1_IC1F_0) << 16U) /*!< fSAMPLING=fDTS/32, N=5 */
692 #define LL_TIM_IC_FILTER_FDIV32_N6 ((TIM_CCMR1_IC1F_3 | TIM_CCMR1_IC1F_2 | TIM_CCMR1_IC1F_1) << 16U) /*!< fSAMPLING=fDTS/32, N=6 */
693 #define LL_TIM_IC_FILTER_FDIV32_N8 (TIM_CCMR1_IC1F << 16U) /*!< fSAMPLING=fDTS/32, N=8 */
698 /** @defgroup TIM_LL_EC_IC_POLARITY Input Configuration Polarity
701 #define LL_TIM_IC_POLARITY_RISING 0x00000000U /*!< The circuit is sensitive to TIxFP1 rising edge, TIxFP1 is not inverted */
702 #define LL_TIM_IC_POLARITY_FALLING TIM_CCER_CC1P /*!< The circuit is sensitive to TIxFP1 falling edge, TIxFP1 is inverted */
703 #define LL_TIM_IC_POLARITY_BOTHEDGE (TIM_CCER_CC1P | TIM_CCER_CC1NP) /*!< The circuit is sensitive to both TIxFP1 rising and falling edges, TIxFP1 is not inverted */
708 /** @defgroup TIM_LL_EC_CLOCKSOURCE Clock Source
711 #define LL_TIM_CLOCKSOURCE_INTERNAL 0x00000000U /*!< The timer is clocked by the internal clock provided from the RCC */
712 #define LL_TIM_CLOCKSOURCE_EXT_MODE1 (TIM_SMCR_SMS_2 | TIM_SMCR_SMS_1 | TIM_SMCR_SMS_0) /*!< Counter counts at each rising or falling edge on a selected inpu t*/
713 #define LL_TIM_CLOCKSOURCE_EXT_MODE2 TIM_SMCR_ECE /*!< Counter counts at each rising or falling edge on the external trigger input ETR */
718 /** @defgroup TIM_LL_EC_ENCODERMODE Encoder Mode
721 #define LL_TIM_ENCODERMODE_X2_TI1 TIM_SMCR_SMS_0 /*!< Encoder mode 1 - Counter counts up/down on TI2FP2 edge depending on TI1FP1 level */
722 #define LL_TIM_ENCODERMODE_X2_TI2 TIM_SMCR_SMS_1 /*!< Encoder mode 2 - Counter counts up/down on TI1FP1 edge depending on TI2FP2 level */
723 #define LL_TIM_ENCODERMODE_X4_TI12 (TIM_SMCR_SMS_1 | TIM_SMCR_SMS_0) /*!< Encoder mode 3 - Counter counts up/down on both TI1FP1 and TI2FP2 edges depending on the level of the other input l */
728 /** @defgroup TIM_LL_EC_TRGO Trigger Output
731 #define LL_TIM_TRGO_RESET 0x00000000U /*!< UG bit from the TIMx_EGR register is used as trigger output */
732 #define LL_TIM_TRGO_ENABLE TIM_CR2_MMS_0 /*!< Counter Enable signal (CNT_EN) is used as trigger output */
733 #define LL_TIM_TRGO_UPDATE TIM_CR2_MMS_1 /*!< Update event is used as trigger output */
734 #define LL_TIM_TRGO_CC1IF (TIM_CR2_MMS_1 | TIM_CR2_MMS_0) /*!< CC1 capture or a compare match is used as trigger output */
735 #define LL_TIM_TRGO_OC1REF TIM_CR2_MMS_2 /*!< OC1REF signal is used as trigger output */
736 #define LL_TIM_TRGO_OC2REF (TIM_CR2_MMS_2 | TIM_CR2_MMS_0) /*!< OC2REF signal is used as trigger output */
737 #define LL_TIM_TRGO_OC3REF (TIM_CR2_MMS_2 | TIM_CR2_MMS_1) /*!< OC3REF signal is used as trigger output */
738 #define LL_TIM_TRGO_OC4REF (TIM_CR2_MMS_2 | TIM_CR2_MMS_1 | TIM_CR2_MMS_0) /*!< OC4REF signal is used as trigger output */
744 /** @defgroup TIM_LL_EC_SLAVEMODE Slave Mode
747 #define LL_TIM_SLAVEMODE_DISABLED 0x00000000U /*!< Slave mode disabled */
748 #define LL_TIM_SLAVEMODE_RESET TIM_SMCR_SMS_2 /*!< Reset Mode - Rising edge of the selected trigger input (TRGI) reinitializes the counter */
749 #define LL_TIM_SLAVEMODE_GATED (TIM_SMCR_SMS_2 | TIM_SMCR_SMS_0) /*!< Gated Mode - The counter clock is enabled when the trigger input (TRGI) is high */
750 #define LL_TIM_SLAVEMODE_TRIGGER (TIM_SMCR_SMS_2 | TIM_SMCR_SMS_1) /*!< Trigger Mode - The counter starts at a rising edge of the trigger TRGI */
755 /** @defgroup TIM_LL_EC_TS Trigger Selection
758 #define LL_TIM_TS_ITR0 0x00000000U /*!< Internal Trigger 0 (ITR0) is used as trigger input */
759 #define LL_TIM_TS_ITR1 TIM_SMCR_TS_0 /*!< Internal Trigger 1 (ITR1) is used as trigger input */
760 #define LL_TIM_TS_ITR2 TIM_SMCR_TS_1 /*!< Internal Trigger 2 (ITR2) is used as trigger input */
761 #define LL_TIM_TS_ITR3 (TIM_SMCR_TS_0 | TIM_SMCR_TS_1) /*!< Internal Trigger 3 (ITR3) is used as trigger input */
762 #define LL_TIM_TS_TI1F_ED TIM_SMCR_TS_2 /*!< TI1 Edge Detector (TI1F_ED) is used as trigger input */
763 #define LL_TIM_TS_TI1FP1 (TIM_SMCR_TS_2 | TIM_SMCR_TS_0) /*!< Filtered Timer Input 1 (TI1FP1) is used as trigger input */
764 #define LL_TIM_TS_TI2FP2 (TIM_SMCR_TS_2 | TIM_SMCR_TS_1) /*!< Filtered Timer Input 2 (TI12P2) is used as trigger input */
765 #define LL_TIM_TS_ETRF (TIM_SMCR_TS_2 | TIM_SMCR_TS_1 | TIM_SMCR_TS_0) /*!< Filtered external Trigger (ETRF) is used as trigger input */
770 /** @defgroup TIM_LL_EC_ETR_POLARITY External Trigger Polarity
773 #define LL_TIM_ETR_POLARITY_NONINVERTED 0x00000000U /*!< ETR is non-inverted, active at high level or rising edge */
774 #define LL_TIM_ETR_POLARITY_INVERTED TIM_SMCR_ETP /*!< ETR is inverted, active at low level or falling edge */
779 /** @defgroup TIM_LL_EC_ETR_PRESCALER External Trigger Prescaler
782 #define LL_TIM_ETR_PRESCALER_DIV1 0x00000000U /*!< ETR prescaler OFF */
783 #define LL_TIM_ETR_PRESCALER_DIV2 TIM_SMCR_ETPS_0 /*!< ETR frequency is divided by 2 */
784 #define LL_TIM_ETR_PRESCALER_DIV4 TIM_SMCR_ETPS_1 /*!< ETR frequency is divided by 4 */
785 #define LL_TIM_ETR_PRESCALER_DIV8 TIM_SMCR_ETPS /*!< ETR frequency is divided by 8 */
790 /** @defgroup TIM_LL_EC_ETR_FILTER External Trigger Filter
793 #define LL_TIM_ETR_FILTER_FDIV1 0x00000000U /*!< No filter, sampling is done at fDTS */
794 #define LL_TIM_ETR_FILTER_FDIV1_N2 TIM_SMCR_ETF_0 /*!< fSAMPLING=fCK_INT, N=2 */
795 #define LL_TIM_ETR_FILTER_FDIV1_N4 TIM_SMCR_ETF_1 /*!< fSAMPLING=fCK_INT, N=4 */
796 #define LL_TIM_ETR_FILTER_FDIV1_N8 (TIM_SMCR_ETF_1 | TIM_SMCR_ETF_0) /*!< fSAMPLING=fCK_INT, N=8 */
797 #define LL_TIM_ETR_FILTER_FDIV2_N6 TIM_SMCR_ETF_2 /*!< fSAMPLING=fDTS/2, N=6 */
798 #define LL_TIM_ETR_FILTER_FDIV2_N8 (TIM_SMCR_ETF_2 | TIM_SMCR_ETF_0) /*!< fSAMPLING=fDTS/2, N=8 */
799 #define LL_TIM_ETR_FILTER_FDIV4_N6 (TIM_SMCR_ETF_2 | TIM_SMCR_ETF_1) /*!< fSAMPLING=fDTS/4, N=6 */
800 #define LL_TIM_ETR_FILTER_FDIV4_N8 (TIM_SMCR_ETF_2 | TIM_SMCR_ETF_1 | TIM_SMCR_ETF_0) /*!< fSAMPLING=fDTS/4, N=8 */
801 #define LL_TIM_ETR_FILTER_FDIV8_N6 TIM_SMCR_ETF_3 /*!< fSAMPLING=fDTS/8, N=8 */
802 #define LL_TIM_ETR_FILTER_FDIV8_N8 (TIM_SMCR_ETF_3 | TIM_SMCR_ETF_0) /*!< fSAMPLING=fDTS/16, N=5 */
803 #define LL_TIM_ETR_FILTER_FDIV16_N5 (TIM_SMCR_ETF_3 | TIM_SMCR_ETF_1) /*!< fSAMPLING=fDTS/16, N=6 */
804 #define LL_TIM_ETR_FILTER_FDIV16_N6 (TIM_SMCR_ETF_3 | TIM_SMCR_ETF_1 | TIM_SMCR_ETF_0) /*!< fSAMPLING=fDTS/16, N=8 */
805 #define LL_TIM_ETR_FILTER_FDIV16_N8 (TIM_SMCR_ETF_3 | TIM_SMCR_ETF_2) /*!< fSAMPLING=fDTS/16, N=5 */
806 #define LL_TIM_ETR_FILTER_FDIV32_N5 (TIM_SMCR_ETF_3 | TIM_SMCR_ETF_2 | TIM_SMCR_ETF_0) /*!< fSAMPLING=fDTS/32, N=5 */
807 #define LL_TIM_ETR_FILTER_FDIV32_N6 (TIM_SMCR_ETF_3 | TIM_SMCR_ETF_2 | TIM_SMCR_ETF_1) /*!< fSAMPLING=fDTS/32, N=6 */
808 #define LL_TIM_ETR_FILTER_FDIV32_N8 TIM_SMCR_ETF /*!< fSAMPLING=fDTS/32, N=8 */
814 /** @defgroup TIM_LL_EC_BREAK_POLARITY break polarity
817 #define LL_TIM_BREAK_POLARITY_LOW 0x00000000U /*!< Break input BRK is active low */
818 #define LL_TIM_BREAK_POLARITY_HIGH TIM_BDTR_BKP /*!< Break input BRK is active high */
826 /** @defgroup TIM_LL_EC_OSSI OSSI
829 #define LL_TIM_OSSI_DISABLE 0x00000000U /*!< When inactive, OCx/OCxN outputs are disabled */
830 #define LL_TIM_OSSI_ENABLE TIM_BDTR_OSSI /*!< When inactive, OxC/OCxN outputs are first forced with their inactive level then forced to their idle level after the deadtime */
835 /** @defgroup TIM_LL_EC_OSSR OSSR
838 #define LL_TIM_OSSR_DISABLE 0x00000000U /*!< When inactive, OCx/OCxN outputs are disabled */
839 #define LL_TIM_OSSR_ENABLE TIM_BDTR_OSSR /*!< When inactive, OC/OCN outputs are enabled with their inactive level as soon as CCxE=1 or CCxNE=1 */
845 /** @defgroup TIM_LL_EC_DMABURST_BASEADDR DMA Burst Base Address
848 #define LL_TIM_DMABURST_BASEADDR_CR1 0x00000000U /*!< TIMx_CR1 register is the DMA base address for DMA burst */
849 #define LL_TIM_DMABURST_BASEADDR_CR2 TIM_DCR_DBA_0 /*!< TIMx_CR2 register is the DMA base address for DMA burst */
850 #define LL_TIM_DMABURST_BASEADDR_SMCR TIM_DCR_DBA_1 /*!< TIMx_SMCR register is the DMA base address for DMA burst */
851 #define LL_TIM_DMABURST_BASEADDR_DIER (TIM_DCR_DBA_1 | TIM_DCR_DBA_0) /*!< TIMx_DIER register is the DMA base address for DMA burst */
852 #define LL_TIM_DMABURST_BASEADDR_SR TIM_DCR_DBA_2 /*!< TIMx_SR register is the DMA base address for DMA burst */
853 #define LL_TIM_DMABURST_BASEADDR_EGR (TIM_DCR_DBA_2 | TIM_DCR_DBA_0) /*!< TIMx_EGR register is the DMA base address for DMA burst */
854 #define LL_TIM_DMABURST_BASEADDR_CCMR1 (TIM_DCR_DBA_2 | TIM_DCR_DBA_1) /*!< TIMx_CCMR1 register is the DMA base address for DMA burst */
855 #define LL_TIM_DMABURST_BASEADDR_CCMR2 (TIM_DCR_DBA_2 | TIM_DCR_DBA_1 | TIM_DCR_DBA_0) /*!< TIMx_CCMR2 register is the DMA base address for DMA burst */
856 #define LL_TIM_DMABURST_BASEADDR_CCER TIM_DCR_DBA_3 /*!< TIMx_CCER register is the DMA base address for DMA burst */
857 #define LL_TIM_DMABURST_BASEADDR_CNT (TIM_DCR_DBA_3 | TIM_DCR_DBA_0) /*!< TIMx_CNT register is the DMA base address for DMA burst */
858 #define LL_TIM_DMABURST_BASEADDR_PSC (TIM_DCR_DBA_3 | TIM_DCR_DBA_1) /*!< TIMx_PSC register is the DMA base address for DMA burst */
859 #define LL_TIM_DMABURST_BASEADDR_ARR (TIM_DCR_DBA_3 | TIM_DCR_DBA_1 | TIM_DCR_DBA_0) /*!< TIMx_ARR register is the DMA base address for DMA burst */
860 #define LL_TIM_DMABURST_BASEADDR_RCR (TIM_DCR_DBA_3 | TIM_DCR_DBA_2) /*!< TIMx_RCR register is the DMA base address for DMA burst */
861 #define LL_TIM_DMABURST_BASEADDR_CCR1 (TIM_DCR_DBA_3 | TIM_DCR_DBA_2 | TIM_DCR_DBA_0) /*!< TIMx_CCR1 register is the DMA base address for DMA burst */
862 #define LL_TIM_DMABURST_BASEADDR_CCR2 (TIM_DCR_DBA_3 | TIM_DCR_DBA_2 | TIM_DCR_DBA_1) /*!< TIMx_CCR2 register is the DMA base address for DMA burst */
863 #define LL_TIM_DMABURST_BASEADDR_CCR3 (TIM_DCR_DBA_3 | TIM_DCR_DBA_2 | TIM_DCR_DBA_1 | TIM_DCR_DBA_0) /*!< TIMx_CCR3 register is the DMA base address for DMA burst */
864 #define LL_TIM_DMABURST_BASEADDR_CCR4 TIM_DCR_DBA_4 /*!< TIMx_CCR4 register is the DMA base address for DMA burst */
865 #define LL_TIM_DMABURST_BASEADDR_BDTR (TIM_DCR_DBA_4 | TIM_DCR_DBA_0) /*!< TIMx_BDTR register is the DMA base address for DMA burst */
866 #define LL_TIM_DMABURST_BASEADDR_OR (TIM_DCR_DBA_4 | TIM_DCR_DBA_2 | TIM_DCR_DBA_0)
871 /** @defgroup TIM_LL_EC_DMABURST_LENGTH DMA Burst Length
874 #define LL_TIM_DMABURST_LENGTH_1TRANSFER 0x00000000U /*!< Transfer is done to 1 register starting from the DMA burst base address */
875 #define LL_TIM_DMABURST_LENGTH_2TRANSFERS TIM_DCR_DBL_0 /*!< Transfer is done to 2 registers starting from the DMA burst base address */
876 #define LL_TIM_DMABURST_LENGTH_3TRANSFERS TIM_DCR_DBL_1 /*!< Transfer is done to 3 registers starting from the DMA burst base address */
877 #define LL_TIM_DMABURST_LENGTH_4TRANSFERS (TIM_DCR_DBL_1 | TIM_DCR_DBL_0) /*!< Transfer is done to 4 registers starting from the DMA burst base address */
878 #define LL_TIM_DMABURST_LENGTH_5TRANSFERS TIM_DCR_DBL_2 /*!< Transfer is done to 5 registers starting from the DMA burst base address */
879 #define LL_TIM_DMABURST_LENGTH_6TRANSFERS (TIM_DCR_DBL_2 | TIM_DCR_DBL_0) /*!< Transfer is done to 6 registers starting from the DMA burst base address */
880 #define LL_TIM_DMABURST_LENGTH_7TRANSFERS (TIM_DCR_DBL_2 | TIM_DCR_DBL_1) /*!< Transfer is done to 7 registers starting from the DMA burst base address */
881 #define LL_TIM_DMABURST_LENGTH_8TRANSFERS (TIM_DCR_DBL_2 | TIM_DCR_DBL_1 | TIM_DCR_DBL_0) /*!< Transfer is done to 1 registers starting from the DMA burst base address */
882 #define LL_TIM_DMABURST_LENGTH_9TRANSFERS TIM_DCR_DBL_3 /*!< Transfer is done to 9 registers starting from the DMA burst base address */
883 #define LL_TIM_DMABURST_LENGTH_10TRANSFERS (TIM_DCR_DBL_3 | TIM_DCR_DBL_0) /*!< Transfer is done to 10 registers starting from the DMA burst base address */
884 #define LL_TIM_DMABURST_LENGTH_11TRANSFERS (TIM_DCR_DBL_3 | TIM_DCR_DBL_1) /*!< Transfer is done to 11 registers starting from the DMA burst base address */
885 #define LL_TIM_DMABURST_LENGTH_12TRANSFERS (TIM_DCR_DBL_3 | TIM_DCR_DBL_1 | TIM_DCR_DBL_0) /*!< Transfer is done to 12 registers starting from the DMA burst base address */
886 #define LL_TIM_DMABURST_LENGTH_13TRANSFERS (TIM_DCR_DBL_3 | TIM_DCR_DBL_2) /*!< Transfer is done to 13 registers starting from the DMA burst base address */
887 #define LL_TIM_DMABURST_LENGTH_14TRANSFERS (TIM_DCR_DBL_3 | TIM_DCR_DBL_2 | TIM_DCR_DBL_0) /*!< Transfer is done to 14 registers starting from the DMA burst base address */
888 #define LL_TIM_DMABURST_LENGTH_15TRANSFERS (TIM_DCR_DBL_3 | TIM_DCR_DBL_2 | TIM_DCR_DBL_1) /*!< Transfer is done to 15 registers starting from the DMA burst base address */
889 #define LL_TIM_DMABURST_LENGTH_16TRANSFERS (TIM_DCR_DBL_3 | TIM_DCR_DBL_2 | TIM_DCR_DBL_1 | TIM_DCR_DBL_0) /*!< Transfer is done to 16 registers starting from the DMA burst base address */
890 #define LL_TIM_DMABURST_LENGTH_17TRANSFERS TIM_DCR_DBL_4 /*!< Transfer is done to 17 registers starting from the DMA burst base address */
891 #define LL_TIM_DMABURST_LENGTH_18TRANSFERS (TIM_DCR_DBL_4 | TIM_DCR_DBL_0) /*!< Transfer is done to 18 registers starting from the DMA burst base address */
897 /** @defgroup TIM_LL_EC_TIM2_ITR1_RMP_TIM8 TIM2 Internal Trigger1 Remap TIM8
900 #define LL_TIM_TIM2_ITR1_RMP_TIM8_TRGO TIM2_OR_RMP_MASK /*!< TIM2_ITR1 is connected to TIM8_TRGO */
901 #define LL_TIM_TIM2_ITR1_RMP_OTG_FS_SOF (TIM_OR_ITR1_RMP_1 | TIM2_OR_RMP_MASK) /*!< TIM2_ITR1 is connected to OTG_FS SOF */
902 #define LL_TIM_TIM2_ITR1_RMP_OTG_HS_SOF (TIM_OR_ITR1_RMP | TIM2_OR_RMP_MASK) /*!< TIM2_ITR1 is connected to OTG_HS SOF */
907 /** @defgroup TIM_LL_EC_TIM5_TI4_RMP TIM5 External Input Ch4 Remap
910 #define LL_TIM_TIM5_TI4_RMP_GPIO TIM5_OR_RMP_MASK /*!< TIM5 channel 4 is connected to GPIO */
911 #define LL_TIM_TIM5_TI4_RMP_LSI (TIM_OR_TI4_RMP_0 | TIM5_OR_RMP_MASK) /*!< TIM5 channel 4 is connected to LSI internal clock */
912 #define LL_TIM_TIM5_TI4_RMP_LSE (TIM_OR_TI4_RMP_1 | TIM5_OR_RMP_MASK) /*!< TIM5 channel 4 is connected to LSE */
913 #define LL_TIM_TIM5_TI4_RMP_RTC (TIM_OR_TI4_RMP | TIM5_OR_RMP_MASK) /*!< TIM5 channel 4 is connected to RTC wakeup interrupt */
918 /** @defgroup TIM_LL_EC_TIM11_TI1_RMP TIM11 External Input Capture 1 Remap
921 #define LL_TIM_TIM11_TI1_RMP_GPIO TIM11_OR_RMP_MASK /*!< TIM11 channel 1 is connected to GPIO */
922 #define LL_TIM_TIM11_TI1_RMP_GPIO1 (TIM_OR_TI1_RMP_0 | TIM11_OR_RMP_MASK) /*!< TIM11 channel 1 is connected to GPIO */
923 #define LL_TIM_TIM11_TI1_RMP_GPIO2 (TIM_OR_TI1_RMP | TIM11_OR_RMP_MASK) /*!< TIM11 channel 1 is connected to GPIO */
924 #define LL_TIM_TIM11_TI1_RMP_HSE_RTC (TIM_OR_TI1_RMP_1 | TIM11_OR_RMP_MASK) /*!< TIM11 channel 1 is connected to HSE_RTC */
934 /* Exported macro ------------------------------------------------------------*/
935 /** @defgroup TIM_LL_Exported_Macros TIM Exported Macros
939 /** @defgroup TIM_LL_EM_WRITE_READ Common Write and read registers Macros
943 * @brief Write a value in TIM register.
944 * @param __INSTANCE__ TIM Instance
945 * @param __REG__ Register to be written
946 * @param __VALUE__ Value to be written in the register
949 #define LL_TIM_WriteReg(__INSTANCE__, __REG__, __VALUE__) WRITE_REG(__INSTANCE__->__REG__, (__VALUE__))
952 * @brief Read a value in TIM register.
953 * @param __INSTANCE__ TIM Instance
954 * @param __REG__ Register to be read
955 * @retval Register value
957 #define LL_TIM_ReadReg(__INSTANCE__, __REG__) READ_REG(__INSTANCE__->__REG__)
962 /** @defgroup TIM_LL_EM_Exported_Macros Exported_Macros
967 * @brief HELPER macro calculating DTG[0:7] in the TIMx_BDTR register to achieve the requested dead time duration.
968 * @note ex: @ref __LL_TIM_CALC_DEADTIME (80000000, @ref LL_TIM_GetClockDivision (), 120);
969 * @param __TIMCLK__ timer input clock frequency (in Hz)
970 * @param __CKD__ This parameter can be one of the following values:
971 * @arg @ref LL_TIM_CLOCKDIVISION_DIV1
972 * @arg @ref LL_TIM_CLOCKDIVISION_DIV2
973 * @arg @ref LL_TIM_CLOCKDIVISION_DIV4
974 * @param __DT__ deadtime duration (in ns)
977 #define __LL_TIM_CALC_DEADTIME(__TIMCLK__, __CKD__, __DT__) \
978 ( (((uint64_t)((__DT__)*1000U)) < ((DT_DELAY_1+1U) * TIM_CALC_DTS((__TIMCLK__), (__CKD__)))) ? (uint8_t)(((uint64_t)((__DT__)*1000U) / TIM_CALC_DTS((__TIMCLK__), (__CKD__))) & DT_DELAY_1) : \
979 (((uint64_t)((__DT__)*1000U)) < (64U + (DT_DELAY_2+1U)) * 2U * TIM_CALC_DTS((__TIMCLK__), (__CKD__))) ? (uint8_t)(DT_RANGE_2 | ((uint8_t)((uint8_t)((((uint64_t)((__DT__)*1000U))/ TIM_CALC_DTS((__TIMCLK__), (__CKD__))) >> 1U) - (uint8_t) 64U) & DT_DELAY_2)) :\
980 (((uint64_t)((__DT__)*1000U)) < (32U + (DT_DELAY_3+1U)) * 8U * TIM_CALC_DTS((__TIMCLK__), (__CKD__))) ? (uint8_t)(DT_RANGE_3 | ((uint8_t)((uint8_t)(((((uint64_t)(__DT__)*1000U))/ TIM_CALC_DTS((__TIMCLK__), (__CKD__))) >> 3U) - (uint8_t) 32U) & DT_DELAY_3)) :\
981 (((uint64_t)((__DT__)*1000U)) < (32U + (DT_DELAY_4+1U)) * 16U * TIM_CALC_DTS((__TIMCLK__), (__CKD__))) ? (uint8_t)(DT_RANGE_4 | ((uint8_t)((uint8_t)(((((uint64_t)(__DT__)*1000U))/ TIM_CALC_DTS((__TIMCLK__), (__CKD__))) >> 4U) - (uint8_t) 32U) & DT_DELAY_4)) :\
985 * @brief HELPER macro calculating the prescaler value to achieve the required counter clock frequency.
986 * @note ex: @ref __LL_TIM_CALC_PSC (80000000, 1000000);
987 * @param __TIMCLK__ timer input clock frequency (in Hz)
988 * @param __CNTCLK__ counter clock frequency (in Hz)
989 * @retval Prescaler value (between Min_Data=0 and Max_Data=65535)
991 #define __LL_TIM_CALC_PSC(__TIMCLK__, __CNTCLK__) \
992 ((__TIMCLK__) >= (__CNTCLK__)) ? (uint32_t)((__TIMCLK__)/(__CNTCLK__) - 1U) : 0U
995 * @brief HELPER macro calculating the auto-reload value to achieve the required output signal frequency.
996 * @note ex: @ref __LL_TIM_CALC_ARR (1000000, @ref LL_TIM_GetPrescaler (), 10000);
997 * @param __TIMCLK__ timer input clock frequency (in Hz)
998 * @param __PSC__ prescaler
999 * @param __FREQ__ output signal frequency (in Hz)
1000 * @retval Auto-reload value (between Min_Data=0 and Max_Data=65535)
1002 #define __LL_TIM_CALC_ARR(__TIMCLK__, __PSC__, __FREQ__) \
1003 (((__TIMCLK__)/((__PSC__) + 1U)) >= (__FREQ__)) ? ((__TIMCLK__)/((__FREQ__) * ((__PSC__) + 1U)) - 1U) : 0U
1006 * @brief HELPER macro calculating the compare value required to achieve the required timer output compare active/inactive delay.
1007 * @note ex: @ref __LL_TIM_CALC_DELAY (1000000, @ref LL_TIM_GetPrescaler (), 10);
1008 * @param __TIMCLK__ timer input clock frequency (in Hz)
1009 * @param __PSC__ prescaler
1010 * @param __DELAY__ timer output compare active/inactive delay (in us)
1011 * @retval Compare value (between Min_Data=0 and Max_Data=65535)
1013 #define __LL_TIM_CALC_DELAY(__TIMCLK__, __PSC__, __DELAY__) \
1014 ((uint32_t)(((uint64_t)(__TIMCLK__) * (uint64_t)(__DELAY__)) \
1015 / ((uint64_t)1000000U * (uint64_t)((__PSC__) + 1U))))
1018 * @brief HELPER macro calculating the auto-reload value to achieve the required pulse duration (when the timer operates in one pulse mode).
1019 * @note ex: @ref __LL_TIM_CALC_PULSE (1000000, @ref LL_TIM_GetPrescaler (), 10, 20);
1020 * @param __TIMCLK__ timer input clock frequency (in Hz)
1021 * @param __PSC__ prescaler
1022 * @param __DELAY__ timer output compare active/inactive delay (in us)
1023 * @param __PULSE__ pulse duration (in us)
1024 * @retval Auto-reload value (between Min_Data=0 and Max_Data=65535)
1026 #define __LL_TIM_CALC_PULSE(__TIMCLK__, __PSC__, __DELAY__, __PULSE__) \
1027 ((uint32_t)(__LL_TIM_CALC_DELAY((__TIMCLK__), (__PSC__), (__PULSE__)) \
1028 + __LL_TIM_CALC_DELAY((__TIMCLK__), (__PSC__), (__DELAY__))))
1031 * @brief HELPER macro retrieving the ratio of the input capture prescaler
1032 * @note ex: @ref __LL_TIM_GET_ICPSC_RATIO (@ref LL_TIM_IC_GetPrescaler ());
1033 * @param __ICPSC__ This parameter can be one of the following values:
1034 * @arg @ref LL_TIM_ICPSC_DIV1
1035 * @arg @ref LL_TIM_ICPSC_DIV2
1036 * @arg @ref LL_TIM_ICPSC_DIV4
1037 * @arg @ref LL_TIM_ICPSC_DIV8
1038 * @retval Input capture prescaler ratio (1, 2, 4 or 8)
1040 #define __LL_TIM_GET_ICPSC_RATIO(__ICPSC__) \
1041 ((uint32_t)(0x01U << (((__ICPSC__) >> 16U) >> TIM_CCMR1_IC1PSC_Pos)))
1053 /* Exported functions --------------------------------------------------------*/
1054 /** @defgroup TIM_LL_Exported_Functions TIM Exported Functions
1058 /** @defgroup TIM_LL_EF_Time_Base Time Base configuration
1062 * @brief Enable timer counter.
1063 * @rmtoll CR1 CEN LL_TIM_EnableCounter
1064 * @param TIMx Timer instance
1067 __STATIC_INLINE
void LL_TIM_EnableCounter(TIM_TypeDef
*TIMx
)
1069 SET_BIT(TIMx
->CR1
, TIM_CR1_CEN
);
1073 * @brief Disable timer counter.
1074 * @rmtoll CR1 CEN LL_TIM_DisableCounter
1075 * @param TIMx Timer instance
1078 __STATIC_INLINE
void LL_TIM_DisableCounter(TIM_TypeDef
*TIMx
)
1080 CLEAR_BIT(TIMx
->CR1
, TIM_CR1_CEN
);
1084 * @brief Indicates whether the timer counter is enabled.
1085 * @rmtoll CR1 CEN LL_TIM_IsEnabledCounter
1086 * @param TIMx Timer instance
1087 * @retval State of bit (1 or 0).
1089 __STATIC_INLINE
uint32_t LL_TIM_IsEnabledCounter(TIM_TypeDef
*TIMx
)
1091 return (READ_BIT(TIMx
->CR1
, TIM_CR1_CEN
) == (TIM_CR1_CEN
));
1095 * @brief Enable update event generation.
1096 * @rmtoll CR1 UDIS LL_TIM_EnableUpdateEvent
1097 * @param TIMx Timer instance
1100 __STATIC_INLINE
void LL_TIM_EnableUpdateEvent(TIM_TypeDef
*TIMx
)
1102 SET_BIT(TIMx
->CR1
, TIM_CR1_UDIS
);
1106 * @brief Disable update event generation.
1107 * @rmtoll CR1 UDIS LL_TIM_DisableUpdateEvent
1108 * @param TIMx Timer instance
1111 __STATIC_INLINE
void LL_TIM_DisableUpdateEvent(TIM_TypeDef
*TIMx
)
1113 CLEAR_BIT(TIMx
->CR1
, TIM_CR1_UDIS
);
1117 * @brief Indicates whether update event generation is enabled.
1118 * @rmtoll CR1 UDIS LL_TIM_IsEnabledUpdateEvent
1119 * @param TIMx Timer instance
1120 * @retval State of bit (1 or 0).
1122 __STATIC_INLINE
uint32_t LL_TIM_IsEnabledUpdateEvent(TIM_TypeDef
*TIMx
)
1124 return (READ_BIT(TIMx
->CR1
, TIM_CR1_UDIS
) == (TIM_CR1_UDIS
));
1128 * @brief Set update event source
1129 * @note Update event source set to LL_TIM_UPDATESOURCE_REGULAR: any of the following events
1130 * generate an update interrupt or DMA request if enabled:
1131 * - Counter overflow/underflow
1132 * - Setting the UG bit
1133 * - Update generation through the slave mode controller
1134 * @note Update event source set to LL_TIM_UPDATESOURCE_COUNTER: only counter
1135 * overflow/underflow generates an update interrupt or DMA request if enabled.
1136 * @rmtoll CR1 URS LL_TIM_SetUpdateSource
1137 * @param TIMx Timer instance
1138 * @param UpdateSource This parameter can be one of the following values:
1139 * @arg @ref LL_TIM_UPDATESOURCE_REGULAR
1140 * @arg @ref LL_TIM_UPDATESOURCE_COUNTER
1143 __STATIC_INLINE
void LL_TIM_SetUpdateSource(TIM_TypeDef
*TIMx
, uint32_t UpdateSource
)
1145 MODIFY_REG(TIMx
->CR1
, TIM_CR1_URS
, UpdateSource
);
1149 * @brief Get actual event update source
1150 * @rmtoll CR1 URS LL_TIM_GetUpdateSource
1151 * @param TIMx Timer instance
1152 * @retval Returned value can be one of the following values:
1153 * @arg @ref LL_TIM_UPDATESOURCE_REGULAR
1154 * @arg @ref LL_TIM_UPDATESOURCE_COUNTER
1156 __STATIC_INLINE
uint32_t LL_TIM_GetUpdateSource(TIM_TypeDef
*TIMx
)
1158 return (uint32_t)(READ_BIT(TIMx
->CR1
, TIM_CR1_URS
));
1162 * @brief Set one pulse mode (one shot v.s. repetitive).
1163 * @rmtoll CR1 OPM LL_TIM_SetOnePulseMode
1164 * @param TIMx Timer instance
1165 * @param OnePulseMode This parameter can be one of the following values:
1166 * @arg @ref LL_TIM_ONEPULSEMODE_SINGLE
1167 * @arg @ref LL_TIM_ONEPULSEMODE_REPETITIVE
1170 __STATIC_INLINE
void LL_TIM_SetOnePulseMode(TIM_TypeDef
*TIMx
, uint32_t OnePulseMode
)
1172 MODIFY_REG(TIMx
->CR1
, TIM_CR1_OPM
, OnePulseMode
);
1176 * @brief Get actual one pulse mode.
1177 * @rmtoll CR1 OPM LL_TIM_GetOnePulseMode
1178 * @param TIMx Timer instance
1179 * @retval Returned value can be one of the following values:
1180 * @arg @ref LL_TIM_ONEPULSEMODE_SINGLE
1181 * @arg @ref LL_TIM_ONEPULSEMODE_REPETITIVE
1183 __STATIC_INLINE
uint32_t LL_TIM_GetOnePulseMode(TIM_TypeDef
*TIMx
)
1185 return (uint32_t)(READ_BIT(TIMx
->CR1
, TIM_CR1_OPM
));
1189 * @brief Set the timer counter counting mode.
1190 * @note Macro @ref IS_TIM_COUNTER_MODE_SELECT_INSTANCE(TIMx) can be used to
1191 * check whether or not the counter mode selection feature is supported
1192 * by a timer instance.
1193 * @rmtoll CR1 DIR LL_TIM_SetCounterMode\n
1194 * CR1 CMS LL_TIM_SetCounterMode
1195 * @param TIMx Timer instance
1196 * @param CounterMode This parameter can be one of the following values:
1197 * @arg @ref LL_TIM_COUNTERMODE_UP
1198 * @arg @ref LL_TIM_COUNTERMODE_DOWN
1199 * @arg @ref LL_TIM_COUNTERMODE_CENTER_UP
1200 * @arg @ref LL_TIM_COUNTERMODE_CENTER_DOWN
1201 * @arg @ref LL_TIM_COUNTERMODE_CENTER_UP_DOWN
1204 __STATIC_INLINE
void LL_TIM_SetCounterMode(TIM_TypeDef
*TIMx
, uint32_t CounterMode
)
1206 MODIFY_REG(TIMx
->CR1
, TIM_CR1_DIR
| TIM_CR1_CMS
, CounterMode
);
1210 * @brief Get actual counter mode.
1211 * @note Macro @ref IS_TIM_COUNTER_MODE_SELECT_INSTANCE(TIMx) can be used to
1212 * check whether or not the counter mode selection feature is supported
1213 * by a timer instance.
1214 * @rmtoll CR1 DIR LL_TIM_GetCounterMode\n
1215 * CR1 CMS LL_TIM_GetCounterMode
1216 * @param TIMx Timer instance
1217 * @retval Returned value can be one of the following values:
1218 * @arg @ref LL_TIM_COUNTERMODE_UP
1219 * @arg @ref LL_TIM_COUNTERMODE_DOWN
1220 * @arg @ref LL_TIM_COUNTERMODE_CENTER_UP
1221 * @arg @ref LL_TIM_COUNTERMODE_CENTER_DOWN
1222 * @arg @ref LL_TIM_COUNTERMODE_CENTER_UP_DOWN
1224 __STATIC_INLINE
uint32_t LL_TIM_GetCounterMode(TIM_TypeDef
*TIMx
)
1226 return (uint32_t)(READ_BIT(TIMx
->CR1
, TIM_CR1_DIR
| TIM_CR1_CMS
));
1230 * @brief Enable auto-reload (ARR) preload.
1231 * @rmtoll CR1 ARPE LL_TIM_EnableARRPreload
1232 * @param TIMx Timer instance
1235 __STATIC_INLINE
void LL_TIM_EnableARRPreload(TIM_TypeDef
*TIMx
)
1237 SET_BIT(TIMx
->CR1
, TIM_CR1_ARPE
);
1241 * @brief Disable auto-reload (ARR) preload.
1242 * @rmtoll CR1 ARPE LL_TIM_DisableARRPreload
1243 * @param TIMx Timer instance
1246 __STATIC_INLINE
void LL_TIM_DisableARRPreload(TIM_TypeDef
*TIMx
)
1248 CLEAR_BIT(TIMx
->CR1
, TIM_CR1_ARPE
);
1252 * @brief Indicates whether auto-reload (ARR) preload is enabled.
1253 * @rmtoll CR1 ARPE LL_TIM_IsEnabledARRPreload
1254 * @param TIMx Timer instance
1255 * @retval State of bit (1 or 0).
1257 __STATIC_INLINE
uint32_t LL_TIM_IsEnabledARRPreload(TIM_TypeDef
*TIMx
)
1259 return (READ_BIT(TIMx
->CR1
, TIM_CR1_ARPE
) == (TIM_CR1_ARPE
));
1263 * @brief Set the division ratio between the timer clock and the sampling clock used by the dead-time generators (when supported) and the digital filters.
1264 * @note Macro @ref IS_TIM_CLOCK_DIVISION_INSTANCE(TIMx) can be used to check
1265 * whether or not the clock division feature is supported by the timer
1267 * @rmtoll CR1 CKD LL_TIM_SetClockDivision
1268 * @param TIMx Timer instance
1269 * @param ClockDivision This parameter can be one of the following values:
1270 * @arg @ref LL_TIM_CLOCKDIVISION_DIV1
1271 * @arg @ref LL_TIM_CLOCKDIVISION_DIV2
1272 * @arg @ref LL_TIM_CLOCKDIVISION_DIV4
1275 __STATIC_INLINE
void LL_TIM_SetClockDivision(TIM_TypeDef
*TIMx
, uint32_t ClockDivision
)
1277 MODIFY_REG(TIMx
->CR1
, TIM_CR1_CKD
, ClockDivision
);
1281 * @brief Get the actual division ratio between the timer clock and the sampling clock used by the dead-time generators (when supported) and the digital filters.
1282 * @note Macro @ref IS_TIM_CLOCK_DIVISION_INSTANCE(TIMx) can be used to check
1283 * whether or not the clock division feature is supported by the timer
1285 * @rmtoll CR1 CKD LL_TIM_GetClockDivision
1286 * @param TIMx Timer instance
1287 * @retval Returned value can be one of the following values:
1288 * @arg @ref LL_TIM_CLOCKDIVISION_DIV1
1289 * @arg @ref LL_TIM_CLOCKDIVISION_DIV2
1290 * @arg @ref LL_TIM_CLOCKDIVISION_DIV4
1292 __STATIC_INLINE
uint32_t LL_TIM_GetClockDivision(TIM_TypeDef
*TIMx
)
1294 return (uint32_t)(READ_BIT(TIMx
->CR1
, TIM_CR1_CKD
));
1298 * @brief Set the counter value.
1299 * @note Macro @ref IS_TIM_32B_COUNTER_INSTANCE(TIMx) can be used to check
1300 * whether or not a timer instance supports a 32 bits counter.
1301 * @rmtoll CNT CNT LL_TIM_SetCounter
1302 * @param TIMx Timer instance
1303 * @param Counter Counter value (between Min_Data=0 and Max_Data=0xFFFF or 0xFFFFFFFF)
1306 __STATIC_INLINE
void LL_TIM_SetCounter(TIM_TypeDef
*TIMx
, uint32_t Counter
)
1308 WRITE_REG(TIMx
->CNT
, Counter
);
1312 * @brief Get the counter value.
1313 * @note Macro @ref IS_TIM_32B_COUNTER_INSTANCE(TIMx) can be used to check
1314 * whether or not a timer instance supports a 32 bits counter.
1315 * @rmtoll CNT CNT LL_TIM_GetCounter
1316 * @param TIMx Timer instance
1317 * @retval Counter value (between Min_Data=0 and Max_Data=0xFFFF or 0xFFFFFFFF)
1319 __STATIC_INLINE
uint32_t LL_TIM_GetCounter(TIM_TypeDef
*TIMx
)
1321 return (uint32_t)(READ_REG(TIMx
->CNT
));
1325 * @brief Get the current direction of the counter
1326 * @rmtoll CR1 DIR LL_TIM_GetDirection
1327 * @param TIMx Timer instance
1328 * @retval Returned value can be one of the following values:
1329 * @arg @ref LL_TIM_COUNTERDIRECTION_UP
1330 * @arg @ref LL_TIM_COUNTERDIRECTION_DOWN
1332 __STATIC_INLINE
uint32_t LL_TIM_GetDirection(TIM_TypeDef
*TIMx
)
1334 return (uint32_t)(READ_BIT(TIMx
->CR1
, TIM_CR1_DIR
));
1338 * @brief Set the prescaler value.
1339 * @note The counter clock frequency CK_CNT is equal to fCK_PSC / (PSC[15:0] + 1).
1340 * @note The prescaler can be changed on the fly as this control register is buffered. The new
1341 * prescaler ratio is taken into account at the next update event.
1342 * @note Helper macro @ref __LL_TIM_CALC_PSC can be used to calculate the Prescaler parameter
1343 * @rmtoll PSC PSC LL_TIM_SetPrescaler
1344 * @param TIMx Timer instance
1345 * @param Prescaler between Min_Data=0 and Max_Data=65535
1348 __STATIC_INLINE
void LL_TIM_SetPrescaler(TIM_TypeDef
*TIMx
, uint32_t Prescaler
)
1350 WRITE_REG(TIMx
->PSC
, Prescaler
);
1354 * @brief Get the prescaler value.
1355 * @rmtoll PSC PSC LL_TIM_GetPrescaler
1356 * @param TIMx Timer instance
1357 * @retval Prescaler value between Min_Data=0 and Max_Data=65535
1359 __STATIC_INLINE
uint32_t LL_TIM_GetPrescaler(TIM_TypeDef
*TIMx
)
1361 return (uint32_t)(READ_REG(TIMx
->PSC
));
1365 * @brief Set the auto-reload value.
1366 * @note The counter is blocked while the auto-reload value is null.
1367 * @note Macro @ref IS_TIM_32B_COUNTER_INSTANCE(TIMx) can be used to check
1368 * whether or not a timer instance supports a 32 bits counter.
1369 * @note Helper macro @ref __LL_TIM_CALC_ARR can be used to calculate the AutoReload parameter
1370 * @rmtoll ARR ARR LL_TIM_SetAutoReload
1371 * @param TIMx Timer instance
1372 * @param AutoReload between Min_Data=0 and Max_Data=65535
1375 __STATIC_INLINE
void LL_TIM_SetAutoReload(TIM_TypeDef
*TIMx
, uint32_t AutoReload
)
1377 WRITE_REG(TIMx
->ARR
, AutoReload
);
1381 * @brief Get the auto-reload value.
1382 * @rmtoll ARR ARR LL_TIM_GetAutoReload
1383 * @note Macro @ref IS_TIM_32B_COUNTER_INSTANCE(TIMx) can be used to check
1384 * whether or not a timer instance supports a 32 bits counter.
1385 * @param TIMx Timer instance
1386 * @retval Auto-reload value
1388 __STATIC_INLINE
uint32_t LL_TIM_GetAutoReload(TIM_TypeDef
*TIMx
)
1390 return (uint32_t)(READ_REG(TIMx
->ARR
));
1394 * @brief Set the repetition counter value.
1395 * @note Macro @ref IS_TIM_REPETITION_COUNTER_INSTANCE(TIMx) can be used to check
1396 * whether or not a timer instance supports a repetition counter.
1397 * @rmtoll RCR REP LL_TIM_SetRepetitionCounter
1398 * @param TIMx Timer instance
1399 * @param RepetitionCounter between Min_Data=0 and Max_Data=255
1402 __STATIC_INLINE
void LL_TIM_SetRepetitionCounter(TIM_TypeDef
*TIMx
, uint32_t RepetitionCounter
)
1404 WRITE_REG(TIMx
->RCR
, RepetitionCounter
);
1408 * @brief Get the repetition counter value.
1409 * @note Macro @ref IS_TIM_REPETITION_COUNTER_INSTANCE(TIMx) can be used to check
1410 * whether or not a timer instance supports a repetition counter.
1411 * @rmtoll RCR REP LL_TIM_GetRepetitionCounter
1412 * @param TIMx Timer instance
1413 * @retval Repetition counter value
1415 __STATIC_INLINE
uint32_t LL_TIM_GetRepetitionCounter(TIM_TypeDef
*TIMx
)
1417 return (uint32_t)(READ_REG(TIMx
->RCR
));
1424 /** @defgroup TIM_LL_EF_Capture_Compare Capture Compare configuration
1428 * @brief Enable the capture/compare control bits (CCxE, CCxNE and OCxM) preload.
1429 * @note CCxE, CCxNE and OCxM bits are preloaded, after having been written,
1430 * they are updated only when a commutation event (COM) occurs.
1431 * @note Only on channels that have a complementary output.
1432 * @note Macro @ref IS_TIM_COMMUTATION_EVENT_INSTANCE(TIMx) can be used to check
1433 * whether or not a timer instance is able to generate a commutation event.
1434 * @rmtoll CR2 CCPC LL_TIM_CC_EnablePreload
1435 * @param TIMx Timer instance
1438 __STATIC_INLINE
void LL_TIM_CC_EnablePreload(TIM_TypeDef
*TIMx
)
1440 SET_BIT(TIMx
->CR2
, TIM_CR2_CCPC
);
1444 * @brief Disable the capture/compare control bits (CCxE, CCxNE and OCxM) preload.
1445 * @note Macro @ref IS_TIM_COMMUTATION_EVENT_INSTANCE(TIMx) can be used to check
1446 * whether or not a timer instance is able to generate a commutation event.
1447 * @rmtoll CR2 CCPC LL_TIM_CC_DisablePreload
1448 * @param TIMx Timer instance
1451 __STATIC_INLINE
void LL_TIM_CC_DisablePreload(TIM_TypeDef
*TIMx
)
1453 CLEAR_BIT(TIMx
->CR2
, TIM_CR2_CCPC
);
1457 * @brief Set the updated source of the capture/compare control bits (CCxE, CCxNE and OCxM).
1458 * @note Macro @ref IS_TIM_COMMUTATION_EVENT_INSTANCE(TIMx) can be used to check
1459 * whether or not a timer instance is able to generate a commutation event.
1460 * @rmtoll CR2 CCUS LL_TIM_CC_SetUpdate
1461 * @param TIMx Timer instance
1462 * @param CCUpdateSource This parameter can be one of the following values:
1463 * @arg @ref LL_TIM_CCUPDATESOURCE_COMG_ONLY
1464 * @arg @ref LL_TIM_CCUPDATESOURCE_COMG_AND_TRGI
1467 __STATIC_INLINE
void LL_TIM_CC_SetUpdate(TIM_TypeDef
*TIMx
, uint32_t CCUpdateSource
)
1469 MODIFY_REG(TIMx
->CR2
, TIM_CR2_CCUS
, CCUpdateSource
);
1473 * @brief Set the trigger of the capture/compare DMA request.
1474 * @rmtoll CR2 CCDS LL_TIM_CC_SetDMAReqTrigger
1475 * @param TIMx Timer instance
1476 * @param DMAReqTrigger This parameter can be one of the following values:
1477 * @arg @ref LL_TIM_CCDMAREQUEST_CC
1478 * @arg @ref LL_TIM_CCDMAREQUEST_UPDATE
1481 __STATIC_INLINE
void LL_TIM_CC_SetDMAReqTrigger(TIM_TypeDef
*TIMx
, uint32_t DMAReqTrigger
)
1483 MODIFY_REG(TIMx
->CR2
, TIM_CR2_CCDS
, DMAReqTrigger
);
1487 * @brief Get actual trigger of the capture/compare DMA request.
1488 * @rmtoll CR2 CCDS LL_TIM_CC_GetDMAReqTrigger
1489 * @param TIMx Timer instance
1490 * @retval Returned value can be one of the following values:
1491 * @arg @ref LL_TIM_CCDMAREQUEST_CC
1492 * @arg @ref LL_TIM_CCDMAREQUEST_UPDATE
1494 __STATIC_INLINE
uint32_t LL_TIM_CC_GetDMAReqTrigger(TIM_TypeDef
*TIMx
)
1496 return (uint32_t)(READ_BIT(TIMx
->CR2
, TIM_CR2_CCDS
));
1500 * @brief Set the lock level to freeze the
1501 * configuration of several capture/compare parameters.
1502 * @note Macro @ref IS_TIM_BREAK_INSTANCE(TIMx) can be used to check whether or not
1503 * the lock mechanism is supported by a timer instance.
1504 * @rmtoll BDTR LOCK LL_TIM_CC_SetLockLevel
1505 * @param TIMx Timer instance
1506 * @param LockLevel This parameter can be one of the following values:
1507 * @arg @ref LL_TIM_LOCKLEVEL_OFF
1508 * @arg @ref LL_TIM_LOCKLEVEL_1
1509 * @arg @ref LL_TIM_LOCKLEVEL_2
1510 * @arg @ref LL_TIM_LOCKLEVEL_3
1513 __STATIC_INLINE
void LL_TIM_CC_SetLockLevel(TIM_TypeDef
*TIMx
, uint32_t LockLevel
)
1515 MODIFY_REG(TIMx
->BDTR
, TIM_BDTR_LOCK
, LockLevel
);
1519 * @brief Enable capture/compare channels.
1520 * @rmtoll CCER CC1E LL_TIM_CC_EnableChannel\n
1521 * CCER CC1NE LL_TIM_CC_EnableChannel\n
1522 * CCER CC2E LL_TIM_CC_EnableChannel\n
1523 * CCER CC2NE LL_TIM_CC_EnableChannel\n
1524 * CCER CC3E LL_TIM_CC_EnableChannel\n
1525 * CCER CC3NE LL_TIM_CC_EnableChannel\n
1526 * CCER CC4E LL_TIM_CC_EnableChannel
1527 * @param TIMx Timer instance
1528 * @param Channels This parameter can be a combination of the following values:
1529 * @arg @ref LL_TIM_CHANNEL_CH1
1530 * @arg @ref LL_TIM_CHANNEL_CH1N
1531 * @arg @ref LL_TIM_CHANNEL_CH2
1532 * @arg @ref LL_TIM_CHANNEL_CH2N
1533 * @arg @ref LL_TIM_CHANNEL_CH3
1534 * @arg @ref LL_TIM_CHANNEL_CH3N
1535 * @arg @ref LL_TIM_CHANNEL_CH4
1538 __STATIC_INLINE
void LL_TIM_CC_EnableChannel(TIM_TypeDef
*TIMx
, uint32_t Channels
)
1540 SET_BIT(TIMx
->CCER
, Channels
);
1544 * @brief Disable capture/compare channels.
1545 * @rmtoll CCER CC1E LL_TIM_CC_DisableChannel\n
1546 * CCER CC1NE LL_TIM_CC_DisableChannel\n
1547 * CCER CC2E LL_TIM_CC_DisableChannel\n
1548 * CCER CC2NE LL_TIM_CC_DisableChannel\n
1549 * CCER CC3E LL_TIM_CC_DisableChannel\n
1550 * CCER CC3NE LL_TIM_CC_DisableChannel\n
1551 * CCER CC4E LL_TIM_CC_DisableChannel
1552 * @param TIMx Timer instance
1553 * @param Channels This parameter can be a combination of the following values:
1554 * @arg @ref LL_TIM_CHANNEL_CH1
1555 * @arg @ref LL_TIM_CHANNEL_CH1N
1556 * @arg @ref LL_TIM_CHANNEL_CH2
1557 * @arg @ref LL_TIM_CHANNEL_CH2N
1558 * @arg @ref LL_TIM_CHANNEL_CH3
1559 * @arg @ref LL_TIM_CHANNEL_CH3N
1560 * @arg @ref LL_TIM_CHANNEL_CH4
1563 __STATIC_INLINE
void LL_TIM_CC_DisableChannel(TIM_TypeDef
*TIMx
, uint32_t Channels
)
1565 CLEAR_BIT(TIMx
->CCER
, Channels
);
1569 * @brief Indicate whether channel(s) is(are) enabled.
1570 * @rmtoll CCER CC1E LL_TIM_CC_IsEnabledChannel\n
1571 * CCER CC1NE LL_TIM_CC_IsEnabledChannel\n
1572 * CCER CC2E LL_TIM_CC_IsEnabledChannel\n
1573 * CCER CC2NE LL_TIM_CC_IsEnabledChannel\n
1574 * CCER CC3E LL_TIM_CC_IsEnabledChannel\n
1575 * CCER CC3NE LL_TIM_CC_IsEnabledChannel\n
1576 * CCER CC4E LL_TIM_CC_IsEnabledChannel
1577 * @param TIMx Timer instance
1578 * @param Channels This parameter can be a combination of the following values:
1579 * @arg @ref LL_TIM_CHANNEL_CH1
1580 * @arg @ref LL_TIM_CHANNEL_CH1N
1581 * @arg @ref LL_TIM_CHANNEL_CH2
1582 * @arg @ref LL_TIM_CHANNEL_CH2N
1583 * @arg @ref LL_TIM_CHANNEL_CH3
1584 * @arg @ref LL_TIM_CHANNEL_CH3N
1585 * @arg @ref LL_TIM_CHANNEL_CH4
1586 * @retval State of bit (1 or 0).
1588 __STATIC_INLINE
uint32_t LL_TIM_CC_IsEnabledChannel(TIM_TypeDef
*TIMx
, uint32_t Channels
)
1590 return (READ_BIT(TIMx
->CCER
, Channels
) == (Channels
));
1597 /** @defgroup TIM_LL_EF_Output_Channel Output channel configuration
1601 * @brief Configure an output channel.
1602 * @rmtoll CCMR1 CC1S LL_TIM_OC_ConfigOutput\n
1603 * CCMR1 CC2S LL_TIM_OC_ConfigOutput\n
1604 * CCMR2 CC3S LL_TIM_OC_ConfigOutput\n
1605 * CCMR2 CC4S LL_TIM_OC_ConfigOutput\n
1606 * CCER CC1P LL_TIM_OC_ConfigOutput\n
1607 * CCER CC2P LL_TIM_OC_ConfigOutput\n
1608 * CCER CC3P LL_TIM_OC_ConfigOutput\n
1609 * CCER CC4P LL_TIM_OC_ConfigOutput\n
1610 * CR2 OIS1 LL_TIM_OC_ConfigOutput\n
1611 * CR2 OIS2 LL_TIM_OC_ConfigOutput\n
1612 * CR2 OIS3 LL_TIM_OC_ConfigOutput\n
1613 * CR2 OIS4 LL_TIM_OC_ConfigOutput
1614 * @param TIMx Timer instance
1615 * @param Channel This parameter can be one of the following values:
1616 * @arg @ref LL_TIM_CHANNEL_CH1
1617 * @arg @ref LL_TIM_CHANNEL_CH2
1618 * @arg @ref LL_TIM_CHANNEL_CH3
1619 * @arg @ref LL_TIM_CHANNEL_CH4
1620 * @param Configuration This parameter must be a combination of all the following values:
1621 * @arg @ref LL_TIM_OCPOLARITY_HIGH or @ref LL_TIM_OCPOLARITY_LOW
1622 * @arg @ref LL_TIM_OCIDLESTATE_LOW or @ref LL_TIM_OCIDLESTATE_HIGH
1625 __STATIC_INLINE
void LL_TIM_OC_ConfigOutput(TIM_TypeDef
*TIMx
, uint32_t Channel
, uint32_t Configuration
)
1627 register uint8_t iChannel
= TIM_GET_CHANNEL_INDEX(Channel
);
1628 register uint32_t *pReg
= (uint32_t *)((uint32_t)((uint32_t)(&TIMx
->CCMR1
) + OFFSET_TAB_CCMRx
[iChannel
]));
1629 CLEAR_BIT(*pReg
, (TIM_CCMR1_CC1S
<< SHIFT_TAB_OCxx
[iChannel
]));
1630 MODIFY_REG(TIMx
->CCER
, (TIM_CCER_CC1P
<< SHIFT_TAB_CCxP
[iChannel
]),
1631 (Configuration
& TIM_CCER_CC1P
) << SHIFT_TAB_CCxP
[iChannel
]);
1632 MODIFY_REG(TIMx
->CR2
, (TIM_CR2_OIS1
<< SHIFT_TAB_OISx
[iChannel
]),
1633 (Configuration
& TIM_CR2_OIS1
) << SHIFT_TAB_OISx
[iChannel
]);
1637 * @brief Define the behavior of the output reference signal OCxREF from which
1638 * OCx and OCxN (when relevant) are derived.
1639 * @rmtoll CCMR1 OC1M LL_TIM_OC_SetMode\n
1640 * CCMR1 OC2M LL_TIM_OC_SetMode\n
1641 * CCMR2 OC3M LL_TIM_OC_SetMode\n
1642 * CCMR2 OC4M LL_TIM_OC_SetMode
1643 * @param TIMx Timer instance
1644 * @param Channel This parameter can be one of the following values:
1645 * @arg @ref LL_TIM_CHANNEL_CH1
1646 * @arg @ref LL_TIM_CHANNEL_CH2
1647 * @arg @ref LL_TIM_CHANNEL_CH3
1648 * @arg @ref LL_TIM_CHANNEL_CH4
1649 * @param Mode This parameter can be one of the following values:
1650 * @arg @ref LL_TIM_OCMODE_FROZEN
1651 * @arg @ref LL_TIM_OCMODE_ACTIVE
1652 * @arg @ref LL_TIM_OCMODE_INACTIVE
1653 * @arg @ref LL_TIM_OCMODE_TOGGLE
1654 * @arg @ref LL_TIM_OCMODE_FORCED_INACTIVE
1655 * @arg @ref LL_TIM_OCMODE_FORCED_ACTIVE
1656 * @arg @ref LL_TIM_OCMODE_PWM1
1657 * @arg @ref LL_TIM_OCMODE_PWM2
1660 __STATIC_INLINE
void LL_TIM_OC_SetMode(TIM_TypeDef
*TIMx
, uint32_t Channel
, uint32_t Mode
)
1662 register uint8_t iChannel
= TIM_GET_CHANNEL_INDEX(Channel
);
1663 register uint32_t *pReg
= (uint32_t *)((uint32_t)((uint32_t)(&TIMx
->CCMR1
) + OFFSET_TAB_CCMRx
[iChannel
]));
1664 MODIFY_REG(*pReg
, ((TIM_CCMR1_OC1M
| TIM_CCMR1_CC1S
) << SHIFT_TAB_OCxx
[iChannel
]), Mode
<< SHIFT_TAB_OCxx
[iChannel
]);
1668 * @brief Get the output compare mode of an output channel.
1669 * @rmtoll CCMR1 OC1M LL_TIM_OC_GetMode\n
1670 * CCMR1 OC2M LL_TIM_OC_GetMode\n
1671 * CCMR2 OC3M LL_TIM_OC_GetMode\n
1672 * CCMR2 OC4M LL_TIM_OC_GetMode
1673 * @param TIMx Timer instance
1674 * @param Channel This parameter can be one of the following values:
1675 * @arg @ref LL_TIM_CHANNEL_CH1
1676 * @arg @ref LL_TIM_CHANNEL_CH2
1677 * @arg @ref LL_TIM_CHANNEL_CH3
1678 * @arg @ref LL_TIM_CHANNEL_CH4
1679 * @retval Returned value can be one of the following values:
1680 * @arg @ref LL_TIM_OCMODE_FROZEN
1681 * @arg @ref LL_TIM_OCMODE_ACTIVE
1682 * @arg @ref LL_TIM_OCMODE_INACTIVE
1683 * @arg @ref LL_TIM_OCMODE_TOGGLE
1684 * @arg @ref LL_TIM_OCMODE_FORCED_INACTIVE
1685 * @arg @ref LL_TIM_OCMODE_FORCED_ACTIVE
1686 * @arg @ref LL_TIM_OCMODE_PWM1
1687 * @arg @ref LL_TIM_OCMODE_PWM2
1689 __STATIC_INLINE
uint32_t LL_TIM_OC_GetMode(TIM_TypeDef
*TIMx
, uint32_t Channel
)
1691 register uint8_t iChannel
= TIM_GET_CHANNEL_INDEX(Channel
);
1692 register uint32_t *pReg
= (uint32_t *)((uint32_t)((uint32_t)(&TIMx
->CCMR1
) + OFFSET_TAB_CCMRx
[iChannel
]));
1693 return (READ_BIT(*pReg
, ((TIM_CCMR1_OC1M
| TIM_CCMR1_CC1S
) << SHIFT_TAB_OCxx
[iChannel
])) >> SHIFT_TAB_OCxx
[iChannel
]);
1697 * @brief Set the polarity of an output channel.
1698 * @rmtoll CCER CC1P LL_TIM_OC_SetPolarity\n
1699 * CCER CC1NP LL_TIM_OC_SetPolarity\n
1700 * CCER CC2P LL_TIM_OC_SetPolarity\n
1701 * CCER CC2NP LL_TIM_OC_SetPolarity\n
1702 * CCER CC3P LL_TIM_OC_SetPolarity\n
1703 * CCER CC3NP LL_TIM_OC_SetPolarity\n
1704 * CCER CC4P LL_TIM_OC_SetPolarity
1705 * @param TIMx Timer instance
1706 * @param Channel This parameter can be one of the following values:
1707 * @arg @ref LL_TIM_CHANNEL_CH1
1708 * @arg @ref LL_TIM_CHANNEL_CH1N
1709 * @arg @ref LL_TIM_CHANNEL_CH2
1710 * @arg @ref LL_TIM_CHANNEL_CH2N
1711 * @arg @ref LL_TIM_CHANNEL_CH3
1712 * @arg @ref LL_TIM_CHANNEL_CH3N
1713 * @arg @ref LL_TIM_CHANNEL_CH4
1714 * @param Polarity This parameter can be one of the following values:
1715 * @arg @ref LL_TIM_OCPOLARITY_HIGH
1716 * @arg @ref LL_TIM_OCPOLARITY_LOW
1719 __STATIC_INLINE
void LL_TIM_OC_SetPolarity(TIM_TypeDef
*TIMx
, uint32_t Channel
, uint32_t Polarity
)
1721 register uint8_t iChannel
= TIM_GET_CHANNEL_INDEX(Channel
);
1722 MODIFY_REG(TIMx
->CCER
, (TIM_CCER_CC1P
<< SHIFT_TAB_CCxP
[iChannel
]), Polarity
<< SHIFT_TAB_CCxP
[iChannel
]);
1726 * @brief Get the polarity of an output channel.
1727 * @rmtoll CCER CC1P LL_TIM_OC_GetPolarity\n
1728 * CCER CC1NP LL_TIM_OC_GetPolarity\n
1729 * CCER CC2P LL_TIM_OC_GetPolarity\n
1730 * CCER CC2NP LL_TIM_OC_GetPolarity\n
1731 * CCER CC3P LL_TIM_OC_GetPolarity\n
1732 * CCER CC3NP LL_TIM_OC_GetPolarity\n
1733 * CCER CC4P LL_TIM_OC_GetPolarity
1734 * @param TIMx Timer instance
1735 * @param Channel This parameter can be one of the following values:
1736 * @arg @ref LL_TIM_CHANNEL_CH1
1737 * @arg @ref LL_TIM_CHANNEL_CH1N
1738 * @arg @ref LL_TIM_CHANNEL_CH2
1739 * @arg @ref LL_TIM_CHANNEL_CH2N
1740 * @arg @ref LL_TIM_CHANNEL_CH3
1741 * @arg @ref LL_TIM_CHANNEL_CH3N
1742 * @arg @ref LL_TIM_CHANNEL_CH4
1743 * @retval Returned value can be one of the following values:
1744 * @arg @ref LL_TIM_OCPOLARITY_HIGH
1745 * @arg @ref LL_TIM_OCPOLARITY_LOW
1747 __STATIC_INLINE
uint32_t LL_TIM_OC_GetPolarity(TIM_TypeDef
*TIMx
, uint32_t Channel
)
1749 register uint8_t iChannel
= TIM_GET_CHANNEL_INDEX(Channel
);
1750 return (READ_BIT(TIMx
->CCER
, (TIM_CCER_CC1P
<< SHIFT_TAB_CCxP
[iChannel
])) >> SHIFT_TAB_CCxP
[iChannel
]);
1754 * @brief Set the IDLE state of an output channel
1755 * @note This function is significant only for the timer instances
1756 * supporting the break feature. Macro @ref IS_TIM_BREAK_INSTANCE(TIMx)
1757 * can be used to check whether or not a timer instance provides
1759 * @rmtoll CR2 OIS1 LL_TIM_OC_SetIdleState\n
1760 * CR2 OIS1N LL_TIM_OC_SetIdleState\n
1761 * CR2 OIS2 LL_TIM_OC_SetIdleState\n
1762 * CR2 OIS2N LL_TIM_OC_SetIdleState\n
1763 * CR2 OIS3 LL_TIM_OC_SetIdleState\n
1764 * CR2 OIS3N LL_TIM_OC_SetIdleState\n
1765 * CR2 OIS4 LL_TIM_OC_SetIdleState
1766 * @param TIMx Timer instance
1767 * @param Channel This parameter can be one of the following values:
1768 * @arg @ref LL_TIM_CHANNEL_CH1
1769 * @arg @ref LL_TIM_CHANNEL_CH1N
1770 * @arg @ref LL_TIM_CHANNEL_CH2
1771 * @arg @ref LL_TIM_CHANNEL_CH2N
1772 * @arg @ref LL_TIM_CHANNEL_CH3
1773 * @arg @ref LL_TIM_CHANNEL_CH3N
1774 * @arg @ref LL_TIM_CHANNEL_CH4
1775 * @param IdleState This parameter can be one of the following values:
1776 * @arg @ref LL_TIM_OCIDLESTATE_LOW
1777 * @arg @ref LL_TIM_OCIDLESTATE_HIGH
1780 __STATIC_INLINE
void LL_TIM_OC_SetIdleState(TIM_TypeDef
*TIMx
, uint32_t Channel
, uint32_t IdleState
)
1782 register uint8_t iChannel
= TIM_GET_CHANNEL_INDEX(Channel
);
1783 MODIFY_REG(TIMx
->CR2
, (TIM_CR2_OIS1
<< SHIFT_TAB_OISx
[iChannel
]), IdleState
<< SHIFT_TAB_OISx
[iChannel
]);
1787 * @brief Get the IDLE state of an output channel
1788 * @rmtoll CR2 OIS1 LL_TIM_OC_GetIdleState\n
1789 * CR2 OIS1N LL_TIM_OC_GetIdleState\n
1790 * CR2 OIS2 LL_TIM_OC_GetIdleState\n
1791 * CR2 OIS2N LL_TIM_OC_GetIdleState\n
1792 * CR2 OIS3 LL_TIM_OC_GetIdleState\n
1793 * CR2 OIS3N LL_TIM_OC_GetIdleState\n
1794 * CR2 OIS4 LL_TIM_OC_GetIdleState
1795 * @param TIMx Timer instance
1796 * @param Channel This parameter can be one of the following values:
1797 * @arg @ref LL_TIM_CHANNEL_CH1
1798 * @arg @ref LL_TIM_CHANNEL_CH1N
1799 * @arg @ref LL_TIM_CHANNEL_CH2
1800 * @arg @ref LL_TIM_CHANNEL_CH2N
1801 * @arg @ref LL_TIM_CHANNEL_CH3
1802 * @arg @ref LL_TIM_CHANNEL_CH3N
1803 * @arg @ref LL_TIM_CHANNEL_CH4
1804 * @retval Returned value can be one of the following values:
1805 * @arg @ref LL_TIM_OCIDLESTATE_LOW
1806 * @arg @ref LL_TIM_OCIDLESTATE_HIGH
1808 __STATIC_INLINE
uint32_t LL_TIM_OC_GetIdleState(TIM_TypeDef
*TIMx
, uint32_t Channel
)
1810 register uint8_t iChannel
= TIM_GET_CHANNEL_INDEX(Channel
);
1811 return (READ_BIT(TIMx
->CR2
, (TIM_CR2_OIS1
<< SHIFT_TAB_OISx
[iChannel
])) >> SHIFT_TAB_OISx
[iChannel
]);
1815 * @brief Enable fast mode for the output channel.
1816 * @note Acts only if the channel is configured in PWM1 or PWM2 mode.
1817 * @rmtoll CCMR1 OC1FE LL_TIM_OC_EnableFast\n
1818 * CCMR1 OC2FE LL_TIM_OC_EnableFast\n
1819 * CCMR2 OC3FE LL_TIM_OC_EnableFast\n
1820 * CCMR2 OC4FE LL_TIM_OC_EnableFast
1821 * @param TIMx Timer instance
1822 * @param Channel This parameter can be one of the following values:
1823 * @arg @ref LL_TIM_CHANNEL_CH1
1824 * @arg @ref LL_TIM_CHANNEL_CH2
1825 * @arg @ref LL_TIM_CHANNEL_CH3
1826 * @arg @ref LL_TIM_CHANNEL_CH4
1829 __STATIC_INLINE
void LL_TIM_OC_EnableFast(TIM_TypeDef
*TIMx
, uint32_t Channel
)
1831 register uint8_t iChannel
= TIM_GET_CHANNEL_INDEX(Channel
);
1832 register uint32_t *pReg
= (uint32_t *)((uint32_t)((uint32_t)(&TIMx
->CCMR1
) + OFFSET_TAB_CCMRx
[iChannel
]));
1833 SET_BIT(*pReg
, (TIM_CCMR1_OC1FE
<< SHIFT_TAB_OCxx
[iChannel
]));
1838 * @brief Disable fast mode for the output channel.
1839 * @rmtoll CCMR1 OC1FE LL_TIM_OC_DisableFast\n
1840 * CCMR1 OC2FE LL_TIM_OC_DisableFast\n
1841 * CCMR2 OC3FE LL_TIM_OC_DisableFast\n
1842 * CCMR2 OC4FE LL_TIM_OC_DisableFast
1843 * @param TIMx Timer instance
1844 * @param Channel This parameter can be one of the following values:
1845 * @arg @ref LL_TIM_CHANNEL_CH1
1846 * @arg @ref LL_TIM_CHANNEL_CH2
1847 * @arg @ref LL_TIM_CHANNEL_CH3
1848 * @arg @ref LL_TIM_CHANNEL_CH4
1851 __STATIC_INLINE
void LL_TIM_OC_DisableFast(TIM_TypeDef
*TIMx
, uint32_t Channel
)
1853 register uint8_t iChannel
= TIM_GET_CHANNEL_INDEX(Channel
);
1854 register uint32_t *pReg
= (uint32_t *)((uint32_t)((uint32_t)(&TIMx
->CCMR1
) + OFFSET_TAB_CCMRx
[iChannel
]));
1855 CLEAR_BIT(*pReg
, (TIM_CCMR1_OC1FE
<< SHIFT_TAB_OCxx
[iChannel
]));
1860 * @brief Indicates whether fast mode is enabled for the output channel.
1861 * @rmtoll CCMR1 OC1FE LL_TIM_OC_IsEnabledFast\n
1862 * CCMR1 OC2FE LL_TIM_OC_IsEnabledFast\n
1863 * CCMR2 OC3FE LL_TIM_OC_IsEnabledFast\n
1864 * CCMR2 OC4FE LL_TIM_OC_IsEnabledFast\n
1865 * @param TIMx Timer instance
1866 * @param Channel This parameter can be one of the following values:
1867 * @arg @ref LL_TIM_CHANNEL_CH1
1868 * @arg @ref LL_TIM_CHANNEL_CH2
1869 * @arg @ref LL_TIM_CHANNEL_CH3
1870 * @arg @ref LL_TIM_CHANNEL_CH4
1871 * @retval State of bit (1 or 0).
1873 __STATIC_INLINE
uint32_t LL_TIM_OC_IsEnabledFast(TIM_TypeDef
*TIMx
, uint32_t Channel
)
1875 register uint8_t iChannel
= TIM_GET_CHANNEL_INDEX(Channel
);
1876 register uint32_t *pReg
= (uint32_t *)((uint32_t)((uint32_t)(&TIMx
->CCMR1
) + OFFSET_TAB_CCMRx
[iChannel
]));
1877 register uint32_t bitfield
= TIM_CCMR1_OC1FE
<< SHIFT_TAB_OCxx
[iChannel
];
1878 return (READ_BIT(*pReg
, bitfield
) == bitfield
);
1882 * @brief Enable compare register (TIMx_CCRx) preload for the output channel.
1883 * @rmtoll CCMR1 OC1PE LL_TIM_OC_EnablePreload\n
1884 * CCMR1 OC2PE LL_TIM_OC_EnablePreload\n
1885 * CCMR2 OC3PE LL_TIM_OC_EnablePreload\n
1886 * CCMR2 OC4PE LL_TIM_OC_EnablePreload
1887 * @param TIMx Timer instance
1888 * @param Channel This parameter can be one of the following values:
1889 * @arg @ref LL_TIM_CHANNEL_CH1
1890 * @arg @ref LL_TIM_CHANNEL_CH2
1891 * @arg @ref LL_TIM_CHANNEL_CH3
1892 * @arg @ref LL_TIM_CHANNEL_CH4
1895 __STATIC_INLINE
void LL_TIM_OC_EnablePreload(TIM_TypeDef
*TIMx
, uint32_t Channel
)
1897 register uint8_t iChannel
= TIM_GET_CHANNEL_INDEX(Channel
);
1898 register uint32_t *pReg
= (uint32_t *)((uint32_t)((uint32_t)(&TIMx
->CCMR1
) + OFFSET_TAB_CCMRx
[iChannel
]));
1899 SET_BIT(*pReg
, (TIM_CCMR1_OC1PE
<< SHIFT_TAB_OCxx
[iChannel
]));
1903 * @brief Disable compare register (TIMx_CCRx) preload for the output channel.
1904 * @rmtoll CCMR1 OC1PE LL_TIM_OC_DisablePreload\n
1905 * CCMR1 OC2PE LL_TIM_OC_DisablePreload\n
1906 * CCMR2 OC3PE LL_TIM_OC_DisablePreload\n
1907 * CCMR2 OC4PE LL_TIM_OC_DisablePreload
1908 * @param TIMx Timer instance
1909 * @param Channel This parameter can be one of the following values:
1910 * @arg @ref LL_TIM_CHANNEL_CH1
1911 * @arg @ref LL_TIM_CHANNEL_CH2
1912 * @arg @ref LL_TIM_CHANNEL_CH3
1913 * @arg @ref LL_TIM_CHANNEL_CH4
1916 __STATIC_INLINE
void LL_TIM_OC_DisablePreload(TIM_TypeDef
*TIMx
, uint32_t Channel
)
1918 register uint8_t iChannel
= TIM_GET_CHANNEL_INDEX(Channel
);
1919 register uint32_t *pReg
= (uint32_t *)((uint32_t)((uint32_t)(&TIMx
->CCMR1
) + OFFSET_TAB_CCMRx
[iChannel
]));
1920 CLEAR_BIT(*pReg
, (TIM_CCMR1_OC1PE
<< SHIFT_TAB_OCxx
[iChannel
]));
1924 * @brief Indicates whether compare register (TIMx_CCRx) preload is enabled for the output channel.
1925 * @rmtoll CCMR1 OC1PE LL_TIM_OC_IsEnabledPreload\n
1926 * CCMR1 OC2PE LL_TIM_OC_IsEnabledPreload\n
1927 * CCMR2 OC3PE LL_TIM_OC_IsEnabledPreload\n
1928 * CCMR2 OC4PE LL_TIM_OC_IsEnabledPreload\n
1929 * @param TIMx Timer instance
1930 * @param Channel This parameter can be one of the following values:
1931 * @arg @ref LL_TIM_CHANNEL_CH1
1932 * @arg @ref LL_TIM_CHANNEL_CH2
1933 * @arg @ref LL_TIM_CHANNEL_CH3
1934 * @arg @ref LL_TIM_CHANNEL_CH4
1935 * @retval State of bit (1 or 0).
1937 __STATIC_INLINE
uint32_t LL_TIM_OC_IsEnabledPreload(TIM_TypeDef
*TIMx
, uint32_t Channel
)
1939 register uint8_t iChannel
= TIM_GET_CHANNEL_INDEX(Channel
);
1940 register uint32_t *pReg
= (uint32_t *)((uint32_t)((uint32_t)(&TIMx
->CCMR1
) + OFFSET_TAB_CCMRx
[iChannel
]));
1941 register uint32_t bitfield
= TIM_CCMR1_OC1PE
<< SHIFT_TAB_OCxx
[iChannel
];
1942 return (READ_BIT(*pReg
, bitfield
) == bitfield
);
1946 * @brief Enable clearing the output channel on an external event.
1947 * @note This function can only be used in Output compare and PWM modes. It does not work in Forced mode.
1948 * @note Macro @ref IS_TIM_OCXREF_CLEAR_INSTANCE(TIMx) can be used to check whether
1949 * or not a timer instance can clear the OCxREF signal on an external event.
1950 * @rmtoll CCMR1 OC1CE LL_TIM_OC_EnableClear\n
1951 * CCMR1 OC2CE LL_TIM_OC_EnableClear\n
1952 * CCMR2 OC3CE LL_TIM_OC_EnableClear\n
1953 * CCMR2 OC4CE LL_TIM_OC_EnableClear
1954 * @param TIMx Timer instance
1955 * @param Channel This parameter can be one of the following values:
1956 * @arg @ref LL_TIM_CHANNEL_CH1
1957 * @arg @ref LL_TIM_CHANNEL_CH2
1958 * @arg @ref LL_TIM_CHANNEL_CH3
1959 * @arg @ref LL_TIM_CHANNEL_CH4
1962 __STATIC_INLINE
void LL_TIM_OC_EnableClear(TIM_TypeDef
*TIMx
, uint32_t Channel
)
1964 register uint8_t iChannel
= TIM_GET_CHANNEL_INDEX(Channel
);
1965 register uint32_t *pReg
= (uint32_t *)((uint32_t)((uint32_t)(&TIMx
->CCMR1
) + OFFSET_TAB_CCMRx
[iChannel
]));
1966 SET_BIT(*pReg
, (TIM_CCMR1_OC1CE
<< SHIFT_TAB_OCxx
[iChannel
]));
1970 * @brief Disable clearing the output channel on an external event.
1971 * @note Macro @ref IS_TIM_OCXREF_CLEAR_INSTANCE(TIMx) can be used to check whether
1972 * or not a timer instance can clear the OCxREF signal on an external event.
1973 * @rmtoll CCMR1 OC1CE LL_TIM_OC_DisableClear\n
1974 * CCMR1 OC2CE LL_TIM_OC_DisableClear\n
1975 * CCMR2 OC3CE LL_TIM_OC_DisableClear\n
1976 * CCMR2 OC4CE LL_TIM_OC_DisableClear
1977 * @param TIMx Timer instance
1978 * @param Channel This parameter can be one of the following values:
1979 * @arg @ref LL_TIM_CHANNEL_CH1
1980 * @arg @ref LL_TIM_CHANNEL_CH2
1981 * @arg @ref LL_TIM_CHANNEL_CH3
1982 * @arg @ref LL_TIM_CHANNEL_CH4
1985 __STATIC_INLINE
void LL_TIM_OC_DisableClear(TIM_TypeDef
*TIMx
, uint32_t Channel
)
1987 register uint8_t iChannel
= TIM_GET_CHANNEL_INDEX(Channel
);
1988 register uint32_t *pReg
= (uint32_t *)((uint32_t)((uint32_t)(&TIMx
->CCMR1
) + OFFSET_TAB_CCMRx
[iChannel
]));
1989 CLEAR_BIT(*pReg
, (TIM_CCMR1_OC1CE
<< SHIFT_TAB_OCxx
[iChannel
]));
1993 * @brief Indicates clearing the output channel on an external event is enabled for the output channel.
1994 * @note This function enables clearing the output channel on an external event.
1995 * @note This function can only be used in Output compare and PWM modes. It does not work in Forced mode.
1996 * @note Macro @ref IS_TIM_OCXREF_CLEAR_INSTANCE(TIMx) can be used to check whether
1997 * or not a timer instance can clear the OCxREF signal on an external event.
1998 * @rmtoll CCMR1 OC1CE LL_TIM_OC_IsEnabledClear\n
1999 * CCMR1 OC2CE LL_TIM_OC_IsEnabledClear\n
2000 * CCMR2 OC3CE LL_TIM_OC_IsEnabledClear\n
2001 * CCMR2 OC4CE LL_TIM_OC_IsEnabledClear\n
2002 * @param TIMx Timer instance
2003 * @param Channel This parameter can be one of the following values:
2004 * @arg @ref LL_TIM_CHANNEL_CH1
2005 * @arg @ref LL_TIM_CHANNEL_CH2
2006 * @arg @ref LL_TIM_CHANNEL_CH3
2007 * @arg @ref LL_TIM_CHANNEL_CH4
2008 * @retval State of bit (1 or 0).
2010 __STATIC_INLINE
uint32_t LL_TIM_OC_IsEnabledClear(TIM_TypeDef
*TIMx
, uint32_t Channel
)
2012 register uint8_t iChannel
= TIM_GET_CHANNEL_INDEX(Channel
);
2013 register uint32_t *pReg
= (uint32_t *)((uint32_t)((uint32_t)(&TIMx
->CCMR1
) + OFFSET_TAB_CCMRx
[iChannel
]));
2014 register uint32_t bitfield
= TIM_CCMR1_OC1CE
<< SHIFT_TAB_OCxx
[iChannel
];
2015 return (READ_BIT(*pReg
, bitfield
) == bitfield
);
2019 * @brief Set the dead-time delay (delay inserted between the rising edge of the OCxREF signal and the rising edge if the Ocx and OCxN signals).
2020 * @note Macro @ref IS_TIM_BREAK_INSTANCE(TIMx) can be used to check whether or not
2021 * dead-time insertion feature is supported by a timer instance.
2022 * @note Helper macro @ref __LL_TIM_CALC_DEADTIME can be used to calculate the DeadTime parameter
2023 * @rmtoll BDTR DTG LL_TIM_OC_SetDeadTime
2024 * @param TIMx Timer instance
2025 * @param DeadTime between Min_Data=0 and Max_Data=255
2028 __STATIC_INLINE
void LL_TIM_OC_SetDeadTime(TIM_TypeDef
*TIMx
, uint32_t DeadTime
)
2030 MODIFY_REG(TIMx
->BDTR
, TIM_BDTR_DTG
, DeadTime
);
2034 * @brief Set compare value for output channel 1 (TIMx_CCR1).
2035 * @note In 32-bit timer implementations compare value can be between 0x00000000 and 0xFFFFFFFF.
2036 * @note Macro @ref IS_TIM_32B_COUNTER_INSTANCE(TIMx) can be used to check
2037 * whether or not a timer instance supports a 32 bits counter.
2038 * @note Macro @ref IS_TIM_CC1_INSTANCE(TIMx) can be used to check whether or not
2039 * output channel 1 is supported by a timer instance.
2040 * @rmtoll CCR1 CCR1 LL_TIM_OC_SetCompareCH1
2041 * @param TIMx Timer instance
2042 * @param CompareValue between Min_Data=0 and Max_Data=65535
2045 __STATIC_INLINE
void LL_TIM_OC_SetCompareCH1(TIM_TypeDef
*TIMx
, uint32_t CompareValue
)
2047 WRITE_REG(TIMx
->CCR1
, CompareValue
);
2051 * @brief Set compare value for output channel 2 (TIMx_CCR2).
2052 * @note In 32-bit timer implementations compare value can be between 0x00000000 and 0xFFFFFFFF.
2053 * @note Macro @ref IS_TIM_32B_COUNTER_INSTANCE(TIMx) can be used to check
2054 * whether or not a timer instance supports a 32 bits counter.
2055 * @note Macro @ref IS_TIM_CC2_INSTANCE(TIMx) can be used to check whether or not
2056 * output channel 2 is supported by a timer instance.
2057 * @rmtoll CCR2 CCR2 LL_TIM_OC_SetCompareCH2
2058 * @param TIMx Timer instance
2059 * @param CompareValue between Min_Data=0 and Max_Data=65535
2062 __STATIC_INLINE
void LL_TIM_OC_SetCompareCH2(TIM_TypeDef
*TIMx
, uint32_t CompareValue
)
2064 WRITE_REG(TIMx
->CCR2
, CompareValue
);
2068 * @brief Set compare value for output channel 3 (TIMx_CCR3).
2069 * @note In 32-bit timer implementations compare value can be between 0x00000000 and 0xFFFFFFFF.
2070 * @note Macro @ref IS_TIM_32B_COUNTER_INSTANCE(TIMx) can be used to check
2071 * whether or not a timer instance supports a 32 bits counter.
2072 * @note Macro @ref IS_TIM_CC3_INSTANCE(TIMx) can be used to check whether or not
2073 * output channel is supported by a timer instance.
2074 * @rmtoll CCR3 CCR3 LL_TIM_OC_SetCompareCH3
2075 * @param TIMx Timer instance
2076 * @param CompareValue between Min_Data=0 and Max_Data=65535
2079 __STATIC_INLINE
void LL_TIM_OC_SetCompareCH3(TIM_TypeDef
*TIMx
, uint32_t CompareValue
)
2081 WRITE_REG(TIMx
->CCR3
, CompareValue
);
2085 * @brief Set compare value for output channel 4 (TIMx_CCR4).
2086 * @note In 32-bit timer implementations compare value can be between 0x00000000 and 0xFFFFFFFF.
2087 * @note Macro @ref IS_TIM_32B_COUNTER_INSTANCE(TIMx) can be used to check
2088 * whether or not a timer instance supports a 32 bits counter.
2089 * @note Macro @ref IS_TIM_CC4_INSTANCE(TIMx) can be used to check whether or not
2090 * output channel 4 is supported by a timer instance.
2091 * @rmtoll CCR4 CCR4 LL_TIM_OC_SetCompareCH4
2092 * @param TIMx Timer instance
2093 * @param CompareValue between Min_Data=0 and Max_Data=65535
2096 __STATIC_INLINE
void LL_TIM_OC_SetCompareCH4(TIM_TypeDef
*TIMx
, uint32_t CompareValue
)
2098 WRITE_REG(TIMx
->CCR4
, CompareValue
);
2102 * @brief Get compare value (TIMx_CCR1) set for output channel 1.
2103 * @note In 32-bit timer implementations returned compare value can be between 0x00000000 and 0xFFFFFFFF.
2104 * @note Macro @ref IS_TIM_32B_COUNTER_INSTANCE(TIMx) can be used to check
2105 * whether or not a timer instance supports a 32 bits counter.
2106 * @note Macro @ref IS_TIM_CC1_INSTANCE(TIMx) can be used to check whether or not
2107 * output channel 1 is supported by a timer instance.
2108 * @rmtoll CCR1 CCR1 LL_TIM_OC_GetCompareCH1
2109 * @param TIMx Timer instance
2110 * @retval CompareValue (between Min_Data=0 and Max_Data=65535)
2112 __STATIC_INLINE
uint32_t LL_TIM_OC_GetCompareCH1(TIM_TypeDef
*TIMx
)
2114 return (uint32_t)(READ_REG(TIMx
->CCR1
));
2118 * @brief Get compare value (TIMx_CCR2) set for output channel 2.
2119 * @note In 32-bit timer implementations returned compare value can be between 0x00000000 and 0xFFFFFFFF.
2120 * @note Macro @ref IS_TIM_32B_COUNTER_INSTANCE(TIMx) can be used to check
2121 * whether or not a timer instance supports a 32 bits counter.
2122 * @note Macro @ref IS_TIM_CC2_INSTANCE(TIMx) can be used to check whether or not
2123 * output channel 2 is supported by a timer instance.
2124 * @rmtoll CCR2 CCR2 LL_TIM_OC_GetCompareCH2
2125 * @param TIMx Timer instance
2126 * @retval CompareValue (between Min_Data=0 and Max_Data=65535)
2128 __STATIC_INLINE
uint32_t LL_TIM_OC_GetCompareCH2(TIM_TypeDef
*TIMx
)
2130 return (uint32_t)(READ_REG(TIMx
->CCR2
));
2134 * @brief Get compare value (TIMx_CCR3) set for output channel 3.
2135 * @note In 32-bit timer implementations returned compare value can be between 0x00000000 and 0xFFFFFFFF.
2136 * @note Macro @ref IS_TIM_32B_COUNTER_INSTANCE(TIMx) can be used to check
2137 * whether or not a timer instance supports a 32 bits counter.
2138 * @note Macro @ref IS_TIM_CC3_INSTANCE(TIMx) can be used to check whether or not
2139 * output channel 3 is supported by a timer instance.
2140 * @rmtoll CCR3 CCR3 LL_TIM_OC_GetCompareCH3
2141 * @param TIMx Timer instance
2142 * @retval CompareValue (between Min_Data=0 and Max_Data=65535)
2144 __STATIC_INLINE
uint32_t LL_TIM_OC_GetCompareCH3(TIM_TypeDef
*TIMx
)
2146 return (uint32_t)(READ_REG(TIMx
->CCR3
));
2150 * @brief Get compare value (TIMx_CCR4) set for output channel 4.
2151 * @note In 32-bit timer implementations returned compare value can be between 0x00000000 and 0xFFFFFFFF.
2152 * @note Macro @ref IS_TIM_32B_COUNTER_INSTANCE(TIMx) can be used to check
2153 * whether or not a timer instance supports a 32 bits counter.
2154 * @note Macro @ref IS_TIM_CC4_INSTANCE(TIMx) can be used to check whether or not
2155 * output channel 4 is supported by a timer instance.
2156 * @rmtoll CCR4 CCR4 LL_TIM_OC_GetCompareCH4
2157 * @param TIMx Timer instance
2158 * @retval CompareValue (between Min_Data=0 and Max_Data=65535)
2160 __STATIC_INLINE
uint32_t LL_TIM_OC_GetCompareCH4(TIM_TypeDef
*TIMx
)
2162 return (uint32_t)(READ_REG(TIMx
->CCR4
));
2169 /** @defgroup TIM_LL_EF_Input_Channel Input channel configuration
2173 * @brief Configure input channel.
2174 * @rmtoll CCMR1 CC1S LL_TIM_IC_Config\n
2175 * CCMR1 IC1PSC LL_TIM_IC_Config\n
2176 * CCMR1 IC1F LL_TIM_IC_Config\n
2177 * CCMR1 CC2S LL_TIM_IC_Config\n
2178 * CCMR1 IC2PSC LL_TIM_IC_Config\n
2179 * CCMR1 IC2F LL_TIM_IC_Config\n
2180 * CCMR2 CC3S LL_TIM_IC_Config\n
2181 * CCMR2 IC3PSC LL_TIM_IC_Config\n
2182 * CCMR2 IC3F LL_TIM_IC_Config\n
2183 * CCMR2 CC4S LL_TIM_IC_Config\n
2184 * CCMR2 IC4PSC LL_TIM_IC_Config\n
2185 * CCMR2 IC4F LL_TIM_IC_Config\n
2186 * CCER CC1P LL_TIM_IC_Config\n
2187 * CCER CC1NP LL_TIM_IC_Config\n
2188 * CCER CC2P LL_TIM_IC_Config\n
2189 * CCER CC2NP LL_TIM_IC_Config\n
2190 * CCER CC3P LL_TIM_IC_Config\n
2191 * CCER CC3NP LL_TIM_IC_Config\n
2192 * CCER CC4P LL_TIM_IC_Config\n
2193 * CCER CC4NP LL_TIM_IC_Config
2194 * @param TIMx Timer instance
2195 * @param Channel This parameter can be one of the following values:
2196 * @arg @ref LL_TIM_CHANNEL_CH1
2197 * @arg @ref LL_TIM_CHANNEL_CH2
2198 * @arg @ref LL_TIM_CHANNEL_CH3
2199 * @arg @ref LL_TIM_CHANNEL_CH4
2200 * @param Configuration This parameter must be a combination of all the following values:
2201 * @arg @ref LL_TIM_ACTIVEINPUT_DIRECTTI or @ref LL_TIM_ACTIVEINPUT_INDIRECTTI or @ref LL_TIM_ACTIVEINPUT_TRC
2202 * @arg @ref LL_TIM_ICPSC_DIV1 or ... or @ref LL_TIM_ICPSC_DIV8
2203 * @arg @ref LL_TIM_IC_FILTER_FDIV1 or ... or @ref LL_TIM_IC_FILTER_FDIV32_N8
2204 * @arg @ref LL_TIM_IC_POLARITY_RISING or @ref LL_TIM_IC_POLARITY_FALLING or @ref LL_TIM_IC_POLARITY_BOTHEDGE
2207 __STATIC_INLINE
void LL_TIM_IC_Config(TIM_TypeDef
*TIMx
, uint32_t Channel
, uint32_t Configuration
)
2209 register uint8_t iChannel
= TIM_GET_CHANNEL_INDEX(Channel
);
2210 register uint32_t *pReg
= (uint32_t *)((uint32_t)((uint32_t)(&TIMx
->CCMR1
) + OFFSET_TAB_CCMRx
[iChannel
]));
2211 MODIFY_REG(*pReg
, ((TIM_CCMR1_IC1F
| TIM_CCMR1_IC1PSC
| TIM_CCMR1_CC1S
) << SHIFT_TAB_ICxx
[iChannel
]),
2212 ((Configuration
>> 16U) & (TIM_CCMR1_IC1F
| TIM_CCMR1_IC1PSC
| TIM_CCMR1_CC1S
)) << SHIFT_TAB_ICxx
[iChannel
]);
2213 MODIFY_REG(TIMx
->CCER
, ((TIM_CCER_CC1NP
| TIM_CCER_CC1P
) << SHIFT_TAB_CCxP
[iChannel
]),
2214 (Configuration
& (TIM_CCER_CC1NP
| TIM_CCER_CC1P
)) << SHIFT_TAB_CCxP
[iChannel
]);
2218 * @brief Set the active input.
2219 * @rmtoll CCMR1 CC1S LL_TIM_IC_SetActiveInput\n
2220 * CCMR1 CC2S LL_TIM_IC_SetActiveInput\n
2221 * CCMR2 CC3S LL_TIM_IC_SetActiveInput\n
2222 * CCMR2 CC4S LL_TIM_IC_SetActiveInput
2223 * @param TIMx Timer instance
2224 * @param Channel This parameter can be one of the following values:
2225 * @arg @ref LL_TIM_CHANNEL_CH1
2226 * @arg @ref LL_TIM_CHANNEL_CH2
2227 * @arg @ref LL_TIM_CHANNEL_CH3
2228 * @arg @ref LL_TIM_CHANNEL_CH4
2229 * @param ICActiveInput This parameter can be one of the following values:
2230 * @arg @ref LL_TIM_ACTIVEINPUT_DIRECTTI
2231 * @arg @ref LL_TIM_ACTIVEINPUT_INDIRECTTI
2232 * @arg @ref LL_TIM_ACTIVEINPUT_TRC
2235 __STATIC_INLINE
void LL_TIM_IC_SetActiveInput(TIM_TypeDef
*TIMx
, uint32_t Channel
, uint32_t ICActiveInput
)
2237 register uint8_t iChannel
= TIM_GET_CHANNEL_INDEX(Channel
);
2238 register uint32_t *pReg
= (uint32_t *)((uint32_t)((uint32_t)(&TIMx
->CCMR1
) + OFFSET_TAB_CCMRx
[iChannel
]));
2239 MODIFY_REG(*pReg
, ((TIM_CCMR1_CC1S
) << SHIFT_TAB_ICxx
[iChannel
]), (ICActiveInput
>> 16U) << SHIFT_TAB_ICxx
[iChannel
]);
2243 * @brief Get the current active input.
2244 * @rmtoll CCMR1 CC1S LL_TIM_IC_GetActiveInput\n
2245 * CCMR1 CC2S LL_TIM_IC_GetActiveInput\n
2246 * CCMR2 CC3S LL_TIM_IC_GetActiveInput\n
2247 * CCMR2 CC4S LL_TIM_IC_GetActiveInput
2248 * @param TIMx Timer instance
2249 * @param Channel This parameter can be one of the following values:
2250 * @arg @ref LL_TIM_CHANNEL_CH1
2251 * @arg @ref LL_TIM_CHANNEL_CH2
2252 * @arg @ref LL_TIM_CHANNEL_CH3
2253 * @arg @ref LL_TIM_CHANNEL_CH4
2254 * @retval Returned value can be one of the following values:
2255 * @arg @ref LL_TIM_ACTIVEINPUT_DIRECTTI
2256 * @arg @ref LL_TIM_ACTIVEINPUT_INDIRECTTI
2257 * @arg @ref LL_TIM_ACTIVEINPUT_TRC
2259 __STATIC_INLINE
uint32_t LL_TIM_IC_GetActiveInput(TIM_TypeDef
*TIMx
, uint32_t Channel
)
2261 register uint8_t iChannel
= TIM_GET_CHANNEL_INDEX(Channel
);
2262 register uint32_t *pReg
= (uint32_t *)((uint32_t)((uint32_t)(&TIMx
->CCMR1
) + OFFSET_TAB_CCMRx
[iChannel
]));
2263 return ((READ_BIT(*pReg
, ((TIM_CCMR1_CC1S
) << SHIFT_TAB_ICxx
[iChannel
])) >> SHIFT_TAB_ICxx
[iChannel
]) << 16U);
2267 * @brief Set the prescaler of input channel.
2268 * @rmtoll CCMR1 IC1PSC LL_TIM_IC_SetPrescaler\n
2269 * CCMR1 IC2PSC LL_TIM_IC_SetPrescaler\n
2270 * CCMR2 IC3PSC LL_TIM_IC_SetPrescaler\n
2271 * CCMR2 IC4PSC LL_TIM_IC_SetPrescaler
2272 * @param TIMx Timer instance
2273 * @param Channel This parameter can be one of the following values:
2274 * @arg @ref LL_TIM_CHANNEL_CH1
2275 * @arg @ref LL_TIM_CHANNEL_CH2
2276 * @arg @ref LL_TIM_CHANNEL_CH3
2277 * @arg @ref LL_TIM_CHANNEL_CH4
2278 * @param ICPrescaler This parameter can be one of the following values:
2279 * @arg @ref LL_TIM_ICPSC_DIV1
2280 * @arg @ref LL_TIM_ICPSC_DIV2
2281 * @arg @ref LL_TIM_ICPSC_DIV4
2282 * @arg @ref LL_TIM_ICPSC_DIV8
2285 __STATIC_INLINE
void LL_TIM_IC_SetPrescaler(TIM_TypeDef
*TIMx
, uint32_t Channel
, uint32_t ICPrescaler
)
2287 register uint8_t iChannel
= TIM_GET_CHANNEL_INDEX(Channel
);
2288 register uint32_t *pReg
= (uint32_t *)((uint32_t)((uint32_t)(&TIMx
->CCMR1
) + OFFSET_TAB_CCMRx
[iChannel
]));
2289 MODIFY_REG(*pReg
, ((TIM_CCMR1_IC1PSC
) << SHIFT_TAB_ICxx
[iChannel
]), (ICPrescaler
>> 16U) << SHIFT_TAB_ICxx
[iChannel
]);
2293 * @brief Get the current prescaler value acting on an input channel.
2294 * @rmtoll CCMR1 IC1PSC LL_TIM_IC_GetPrescaler\n
2295 * CCMR1 IC2PSC LL_TIM_IC_GetPrescaler\n
2296 * CCMR2 IC3PSC LL_TIM_IC_GetPrescaler\n
2297 * CCMR2 IC4PSC LL_TIM_IC_GetPrescaler
2298 * @param TIMx Timer instance
2299 * @param Channel This parameter can be one of the following values:
2300 * @arg @ref LL_TIM_CHANNEL_CH1
2301 * @arg @ref LL_TIM_CHANNEL_CH2
2302 * @arg @ref LL_TIM_CHANNEL_CH3
2303 * @arg @ref LL_TIM_CHANNEL_CH4
2304 * @retval Returned value can be one of the following values:
2305 * @arg @ref LL_TIM_ICPSC_DIV1
2306 * @arg @ref LL_TIM_ICPSC_DIV2
2307 * @arg @ref LL_TIM_ICPSC_DIV4
2308 * @arg @ref LL_TIM_ICPSC_DIV8
2310 __STATIC_INLINE
uint32_t LL_TIM_IC_GetPrescaler(TIM_TypeDef
*TIMx
, uint32_t Channel
)
2312 register uint8_t iChannel
= TIM_GET_CHANNEL_INDEX(Channel
);
2313 register uint32_t *pReg
= (uint32_t *)((uint32_t)((uint32_t)(&TIMx
->CCMR1
) + OFFSET_TAB_CCMRx
[iChannel
]));
2314 return ((READ_BIT(*pReg
, ((TIM_CCMR1_IC1PSC
) << SHIFT_TAB_ICxx
[iChannel
])) >> SHIFT_TAB_ICxx
[iChannel
]) << 16U);
2318 * @brief Set the input filter duration.
2319 * @rmtoll CCMR1 IC1F LL_TIM_IC_SetFilter\n
2320 * CCMR1 IC2F LL_TIM_IC_SetFilter\n
2321 * CCMR2 IC3F LL_TIM_IC_SetFilter\n
2322 * CCMR2 IC4F LL_TIM_IC_SetFilter
2323 * @param TIMx Timer instance
2324 * @param Channel This parameter can be one of the following values:
2325 * @arg @ref LL_TIM_CHANNEL_CH1
2326 * @arg @ref LL_TIM_CHANNEL_CH2
2327 * @arg @ref LL_TIM_CHANNEL_CH3
2328 * @arg @ref LL_TIM_CHANNEL_CH4
2329 * @param ICFilter This parameter can be one of the following values:
2330 * @arg @ref LL_TIM_IC_FILTER_FDIV1
2331 * @arg @ref LL_TIM_IC_FILTER_FDIV1_N2
2332 * @arg @ref LL_TIM_IC_FILTER_FDIV1_N4
2333 * @arg @ref LL_TIM_IC_FILTER_FDIV1_N8
2334 * @arg @ref LL_TIM_IC_FILTER_FDIV2_N6
2335 * @arg @ref LL_TIM_IC_FILTER_FDIV2_N8
2336 * @arg @ref LL_TIM_IC_FILTER_FDIV4_N6
2337 * @arg @ref LL_TIM_IC_FILTER_FDIV4_N8
2338 * @arg @ref LL_TIM_IC_FILTER_FDIV8_N6
2339 * @arg @ref LL_TIM_IC_FILTER_FDIV8_N8
2340 * @arg @ref LL_TIM_IC_FILTER_FDIV16_N5
2341 * @arg @ref LL_TIM_IC_FILTER_FDIV16_N6
2342 * @arg @ref LL_TIM_IC_FILTER_FDIV16_N8
2343 * @arg @ref LL_TIM_IC_FILTER_FDIV32_N5
2344 * @arg @ref LL_TIM_IC_FILTER_FDIV32_N6
2345 * @arg @ref LL_TIM_IC_FILTER_FDIV32_N8
2348 __STATIC_INLINE
void LL_TIM_IC_SetFilter(TIM_TypeDef
*TIMx
, uint32_t Channel
, uint32_t ICFilter
)
2350 register uint8_t iChannel
= TIM_GET_CHANNEL_INDEX(Channel
);
2351 register uint32_t *pReg
= (uint32_t *)((uint32_t)((uint32_t)(&TIMx
->CCMR1
) + OFFSET_TAB_CCMRx
[iChannel
]));
2352 MODIFY_REG(*pReg
, ((TIM_CCMR1_IC1F
) << SHIFT_TAB_ICxx
[iChannel
]), (ICFilter
>> 16U) << SHIFT_TAB_ICxx
[iChannel
]);
2356 * @brief Get the input filter duration.
2357 * @rmtoll CCMR1 IC1F LL_TIM_IC_GetFilter\n
2358 * CCMR1 IC2F LL_TIM_IC_GetFilter\n
2359 * CCMR2 IC3F LL_TIM_IC_GetFilter\n
2360 * CCMR2 IC4F LL_TIM_IC_GetFilter
2361 * @param TIMx Timer instance
2362 * @param Channel This parameter can be one of the following values:
2363 * @arg @ref LL_TIM_CHANNEL_CH1
2364 * @arg @ref LL_TIM_CHANNEL_CH2
2365 * @arg @ref LL_TIM_CHANNEL_CH3
2366 * @arg @ref LL_TIM_CHANNEL_CH4
2367 * @retval Returned value can be one of the following values:
2368 * @arg @ref LL_TIM_IC_FILTER_FDIV1
2369 * @arg @ref LL_TIM_IC_FILTER_FDIV1_N2
2370 * @arg @ref LL_TIM_IC_FILTER_FDIV1_N4
2371 * @arg @ref LL_TIM_IC_FILTER_FDIV1_N8
2372 * @arg @ref LL_TIM_IC_FILTER_FDIV2_N6
2373 * @arg @ref LL_TIM_IC_FILTER_FDIV2_N8
2374 * @arg @ref LL_TIM_IC_FILTER_FDIV4_N6
2375 * @arg @ref LL_TIM_IC_FILTER_FDIV4_N8
2376 * @arg @ref LL_TIM_IC_FILTER_FDIV8_N6
2377 * @arg @ref LL_TIM_IC_FILTER_FDIV8_N8
2378 * @arg @ref LL_TIM_IC_FILTER_FDIV16_N5
2379 * @arg @ref LL_TIM_IC_FILTER_FDIV16_N6
2380 * @arg @ref LL_TIM_IC_FILTER_FDIV16_N8
2381 * @arg @ref LL_TIM_IC_FILTER_FDIV32_N5
2382 * @arg @ref LL_TIM_IC_FILTER_FDIV32_N6
2383 * @arg @ref LL_TIM_IC_FILTER_FDIV32_N8
2385 __STATIC_INLINE
uint32_t LL_TIM_IC_GetFilter(TIM_TypeDef
*TIMx
, uint32_t Channel
)
2387 register uint8_t iChannel
= TIM_GET_CHANNEL_INDEX(Channel
);
2388 register uint32_t *pReg
= (uint32_t *)((uint32_t)((uint32_t)(&TIMx
->CCMR1
) + OFFSET_TAB_CCMRx
[iChannel
]));
2389 return ((READ_BIT(*pReg
, ((TIM_CCMR1_IC1F
) << SHIFT_TAB_ICxx
[iChannel
])) >> SHIFT_TAB_ICxx
[iChannel
]) << 16U);
2393 * @brief Set the input channel polarity.
2394 * @rmtoll CCER CC1P LL_TIM_IC_SetPolarity\n
2395 * CCER CC1NP LL_TIM_IC_SetPolarity\n
2396 * CCER CC2P LL_TIM_IC_SetPolarity\n
2397 * CCER CC2NP LL_TIM_IC_SetPolarity\n
2398 * CCER CC3P LL_TIM_IC_SetPolarity\n
2399 * CCER CC3NP LL_TIM_IC_SetPolarity\n
2400 * CCER CC4P LL_TIM_IC_SetPolarity\n
2401 * CCER CC4NP LL_TIM_IC_SetPolarity
2402 * @param TIMx Timer instance
2403 * @param Channel This parameter can be one of the following values:
2404 * @arg @ref LL_TIM_CHANNEL_CH1
2405 * @arg @ref LL_TIM_CHANNEL_CH2
2406 * @arg @ref LL_TIM_CHANNEL_CH3
2407 * @arg @ref LL_TIM_CHANNEL_CH4
2408 * @param ICPolarity This parameter can be one of the following values:
2409 * @arg @ref LL_TIM_IC_POLARITY_RISING
2410 * @arg @ref LL_TIM_IC_POLARITY_FALLING
2411 * @arg @ref LL_TIM_IC_POLARITY_BOTHEDGE
2414 __STATIC_INLINE
void LL_TIM_IC_SetPolarity(TIM_TypeDef
*TIMx
, uint32_t Channel
, uint32_t ICPolarity
)
2416 register uint8_t iChannel
= TIM_GET_CHANNEL_INDEX(Channel
);
2417 MODIFY_REG(TIMx
->CCER
, ((TIM_CCER_CC1NP
| TIM_CCER_CC1P
) << SHIFT_TAB_CCxP
[iChannel
]),
2418 ICPolarity
<< SHIFT_TAB_CCxP
[iChannel
]);
2422 * @brief Get the current input channel polarity.
2423 * @rmtoll CCER CC1P LL_TIM_IC_GetPolarity\n
2424 * CCER CC1NP LL_TIM_IC_GetPolarity\n
2425 * CCER CC2P LL_TIM_IC_GetPolarity\n
2426 * CCER CC2NP LL_TIM_IC_GetPolarity\n
2427 * CCER CC3P LL_TIM_IC_GetPolarity\n
2428 * CCER CC3NP LL_TIM_IC_GetPolarity\n
2429 * CCER CC4P LL_TIM_IC_GetPolarity\n
2430 * CCER CC4NP LL_TIM_IC_GetPolarity
2431 * @param TIMx Timer instance
2432 * @param Channel This parameter can be one of the following values:
2433 * @arg @ref LL_TIM_CHANNEL_CH1
2434 * @arg @ref LL_TIM_CHANNEL_CH2
2435 * @arg @ref LL_TIM_CHANNEL_CH3
2436 * @arg @ref LL_TIM_CHANNEL_CH4
2437 * @retval Returned value can be one of the following values:
2438 * @arg @ref LL_TIM_IC_POLARITY_RISING
2439 * @arg @ref LL_TIM_IC_POLARITY_FALLING
2440 * @arg @ref LL_TIM_IC_POLARITY_BOTHEDGE
2442 __STATIC_INLINE
uint32_t LL_TIM_IC_GetPolarity(TIM_TypeDef
*TIMx
, uint32_t Channel
)
2444 register uint8_t iChannel
= TIM_GET_CHANNEL_INDEX(Channel
);
2445 return (READ_BIT(TIMx
->CCER
, ((TIM_CCER_CC1NP
| TIM_CCER_CC1P
) << SHIFT_TAB_CCxP
[iChannel
])) >>
2446 SHIFT_TAB_CCxP
[iChannel
]);
2450 * @brief Connect the TIMx_CH1, CH2 and CH3 pins to the TI1 input (XOR combination).
2451 * @note Macro @ref IS_TIM_XOR_INSTANCE(TIMx) can be used to check whether or not
2452 * a timer instance provides an XOR input.
2453 * @rmtoll CR2 TI1S LL_TIM_IC_EnableXORCombination
2454 * @param TIMx Timer instance
2457 __STATIC_INLINE
void LL_TIM_IC_EnableXORCombination(TIM_TypeDef
*TIMx
)
2459 SET_BIT(TIMx
->CR2
, TIM_CR2_TI1S
);
2463 * @brief Disconnect the TIMx_CH1, CH2 and CH3 pins from the TI1 input.
2464 * @note Macro @ref IS_TIM_XOR_INSTANCE(TIMx) can be used to check whether or not
2465 * a timer instance provides an XOR input.
2466 * @rmtoll CR2 TI1S LL_TIM_IC_DisableXORCombination
2467 * @param TIMx Timer instance
2470 __STATIC_INLINE
void LL_TIM_IC_DisableXORCombination(TIM_TypeDef
*TIMx
)
2472 CLEAR_BIT(TIMx
->CR2
, TIM_CR2_TI1S
);
2476 * @brief Indicates whether the TIMx_CH1, CH2 and CH3 pins are connectected to the TI1 input.
2477 * @note Macro @ref IS_TIM_XOR_INSTANCE(TIMx) can be used to check whether or not
2478 * a timer instance provides an XOR input.
2479 * @rmtoll CR2 TI1S LL_TIM_IC_IsEnabledXORCombination
2480 * @param TIMx Timer instance
2481 * @retval State of bit (1 or 0).
2483 __STATIC_INLINE
uint32_t LL_TIM_IC_IsEnabledXORCombination(TIM_TypeDef
*TIMx
)
2485 return (READ_BIT(TIMx
->CR2
, TIM_CR2_TI1S
) == (TIM_CR2_TI1S
));
2489 * @brief Get captured value for input channel 1.
2490 * @note In 32-bit timer implementations returned captured value can be between 0x00000000 and 0xFFFFFFFF.
2491 * @note Macro @ref IS_TIM_32B_COUNTER_INSTANCE(TIMx) can be used to check
2492 * whether or not a timer instance supports a 32 bits counter.
2493 * @note Macro @ref IS_TIM_CC1_INSTANCE(TIMx) can be used to check whether or not
2494 * input channel 1 is supported by a timer instance.
2495 * @rmtoll CCR1 CCR1 LL_TIM_IC_GetCaptureCH1
2496 * @param TIMx Timer instance
2497 * @retval CapturedValue (between Min_Data=0 and Max_Data=65535)
2499 __STATIC_INLINE
uint32_t LL_TIM_IC_GetCaptureCH1(TIM_TypeDef
*TIMx
)
2501 return (uint32_t)(READ_REG(TIMx
->CCR1
));
2505 * @brief Get captured value for input channel 2.
2506 * @note In 32-bit timer implementations returned captured value can be between 0x00000000 and 0xFFFFFFFF.
2507 * @note Macro @ref IS_TIM_32B_COUNTER_INSTANCE(TIMx) can be used to check
2508 * whether or not a timer instance supports a 32 bits counter.
2509 * @note Macro @ref IS_TIM_CC2_INSTANCE(TIMx) can be used to check whether or not
2510 * input channel 2 is supported by a timer instance.
2511 * @rmtoll CCR2 CCR2 LL_TIM_IC_GetCaptureCH2
2512 * @param TIMx Timer instance
2513 * @retval CapturedValue (between Min_Data=0 and Max_Data=65535)
2515 __STATIC_INLINE
uint32_t LL_TIM_IC_GetCaptureCH2(TIM_TypeDef
*TIMx
)
2517 return (uint32_t)(READ_REG(TIMx
->CCR2
));
2521 * @brief Get captured value for input channel 3.
2522 * @note In 32-bit timer implementations returned captured value can be between 0x00000000 and 0xFFFFFFFF.
2523 * @note Macro @ref IS_TIM_32B_COUNTER_INSTANCE(TIMx) can be used to check
2524 * whether or not a timer instance supports a 32 bits counter.
2525 * @note Macro @ref IS_TIM_CC3_INSTANCE(TIMx) can be used to check whether or not
2526 * input channel 3 is supported by a timer instance.
2527 * @rmtoll CCR3 CCR3 LL_TIM_IC_GetCaptureCH3
2528 * @param TIMx Timer instance
2529 * @retval CapturedValue (between Min_Data=0 and Max_Data=65535)
2531 __STATIC_INLINE
uint32_t LL_TIM_IC_GetCaptureCH3(TIM_TypeDef
*TIMx
)
2533 return (uint32_t)(READ_REG(TIMx
->CCR3
));
2537 * @brief Get captured value for input channel 4.
2538 * @note In 32-bit timer implementations returned captured value can be between 0x00000000 and 0xFFFFFFFF.
2539 * @note Macro @ref IS_TIM_32B_COUNTER_INSTANCE(TIMx) can be used to check
2540 * whether or not a timer instance supports a 32 bits counter.
2541 * @note Macro @ref IS_TIM_CC4_INSTANCE(TIMx) can be used to check whether or not
2542 * input channel 4 is supported by a timer instance.
2543 * @rmtoll CCR4 CCR4 LL_TIM_IC_GetCaptureCH4
2544 * @param TIMx Timer instance
2545 * @retval CapturedValue (between Min_Data=0 and Max_Data=65535)
2547 __STATIC_INLINE
uint32_t LL_TIM_IC_GetCaptureCH4(TIM_TypeDef
*TIMx
)
2549 return (uint32_t)(READ_REG(TIMx
->CCR4
));
2556 /** @defgroup TIM_LL_EF_Clock_Selection Counter clock selection
2560 * @brief Enable external clock mode 2.
2561 * @note When external clock mode 2 is enabled the counter is clocked by any active edge on the ETRF signal.
2562 * @note Macro @ref IS_TIM_CLOCKSOURCE_ETRMODE2_INSTANCE(TIMx) can be used to check
2563 * whether or not a timer instance supports external clock mode2.
2564 * @rmtoll SMCR ECE LL_TIM_EnableExternalClock
2565 * @param TIMx Timer instance
2568 __STATIC_INLINE
void LL_TIM_EnableExternalClock(TIM_TypeDef
*TIMx
)
2570 SET_BIT(TIMx
->SMCR
, TIM_SMCR_ECE
);
2574 * @brief Disable external clock mode 2.
2575 * @note Macro @ref IS_TIM_CLOCKSOURCE_ETRMODE2_INSTANCE(TIMx) can be used to check
2576 * whether or not a timer instance supports external clock mode2.
2577 * @rmtoll SMCR ECE LL_TIM_DisableExternalClock
2578 * @param TIMx Timer instance
2581 __STATIC_INLINE
void LL_TIM_DisableExternalClock(TIM_TypeDef
*TIMx
)
2583 CLEAR_BIT(TIMx
->SMCR
, TIM_SMCR_ECE
);
2587 * @brief Indicate whether external clock mode 2 is enabled.
2588 * @note Macro @ref IS_TIM_CLOCKSOURCE_ETRMODE2_INSTANCE(TIMx) can be used to check
2589 * whether or not a timer instance supports external clock mode2.
2590 * @rmtoll SMCR ECE LL_TIM_IsEnabledExternalClock
2591 * @param TIMx Timer instance
2592 * @retval State of bit (1 or 0).
2594 __STATIC_INLINE
uint32_t LL_TIM_IsEnabledExternalClock(TIM_TypeDef
*TIMx
)
2596 return (READ_BIT(TIMx
->SMCR
, TIM_SMCR_ECE
) == (TIM_SMCR_ECE
));
2600 * @brief Set the clock source of the counter clock.
2601 * @note when selected clock source is external clock mode 1, the timer input
2602 * the external clock is applied is selected by calling the @ref LL_TIM_SetTriggerInput()
2603 * function. This timer input must be configured by calling
2604 * the @ref LL_TIM_IC_Config() function.
2605 * @note Macro @ref IS_TIM_CLOCKSOURCE_ETRMODE1_INSTANCE(TIMx) can be used to check
2606 * whether or not a timer instance supports external clock mode1.
2607 * @note Macro @ref IS_TIM_CLOCKSOURCE_ETRMODE2_INSTANCE(TIMx) can be used to check
2608 * whether or not a timer instance supports external clock mode2.
2609 * @rmtoll SMCR SMS LL_TIM_SetClockSource\n
2610 * SMCR ECE LL_TIM_SetClockSource
2611 * @param TIMx Timer instance
2612 * @param ClockSource This parameter can be one of the following values:
2613 * @arg @ref LL_TIM_CLOCKSOURCE_INTERNAL
2614 * @arg @ref LL_TIM_CLOCKSOURCE_EXT_MODE1
2615 * @arg @ref LL_TIM_CLOCKSOURCE_EXT_MODE2
2618 __STATIC_INLINE
void LL_TIM_SetClockSource(TIM_TypeDef
*TIMx
, uint32_t ClockSource
)
2620 MODIFY_REG(TIMx
->SMCR
, TIM_SMCR_SMS
| TIM_SMCR_ECE
, ClockSource
);
2624 * @brief Set the encoder interface mode.
2625 * @note Macro @ref IS_TIM_ENCODER_INTERFACE_INSTANCE(TIMx) can be used to check
2626 * whether or not a timer instance supports the encoder mode.
2627 * @rmtoll SMCR SMS LL_TIM_SetEncoderMode
2628 * @param TIMx Timer instance
2629 * @param EncoderMode This parameter can be one of the following values:
2630 * @arg @ref LL_TIM_ENCODERMODE_X2_TI1
2631 * @arg @ref LL_TIM_ENCODERMODE_X2_TI2
2632 * @arg @ref LL_TIM_ENCODERMODE_X4_TI12
2635 __STATIC_INLINE
void LL_TIM_SetEncoderMode(TIM_TypeDef
*TIMx
, uint32_t EncoderMode
)
2637 MODIFY_REG(TIMx
->SMCR
, TIM_SMCR_SMS
, EncoderMode
);
2644 /** @defgroup TIM_LL_EF_Timer_Synchronization Timer synchronisation configuration
2648 * @brief Set the trigger output (TRGO) used for timer synchronization .
2649 * @note Macro @ref IS_TIM_MASTER_INSTANCE(TIMx) can be used to check
2650 * whether or not a timer instance can operate as a master timer.
2651 * @rmtoll CR2 MMS LL_TIM_SetTriggerOutput
2652 * @param TIMx Timer instance
2653 * @param TimerSynchronization This parameter can be one of the following values:
2654 * @arg @ref LL_TIM_TRGO_RESET
2655 * @arg @ref LL_TIM_TRGO_ENABLE
2656 * @arg @ref LL_TIM_TRGO_UPDATE
2657 * @arg @ref LL_TIM_TRGO_CC1IF
2658 * @arg @ref LL_TIM_TRGO_OC1REF
2659 * @arg @ref LL_TIM_TRGO_OC2REF
2660 * @arg @ref LL_TIM_TRGO_OC3REF
2661 * @arg @ref LL_TIM_TRGO_OC4REF
2664 __STATIC_INLINE
void LL_TIM_SetTriggerOutput(TIM_TypeDef
*TIMx
, uint32_t TimerSynchronization
)
2666 MODIFY_REG(TIMx
->CR2
, TIM_CR2_MMS
, TimerSynchronization
);
2670 * @brief Set the synchronization mode of a slave timer.
2671 * @note Macro @ref IS_TIM_SLAVE_INSTANCE(TIMx) can be used to check whether or not
2672 * a timer instance can operate as a slave timer.
2673 * @rmtoll SMCR SMS LL_TIM_SetSlaveMode
2674 * @param TIMx Timer instance
2675 * @param SlaveMode This parameter can be one of the following values:
2676 * @arg @ref LL_TIM_SLAVEMODE_DISABLED
2677 * @arg @ref LL_TIM_SLAVEMODE_RESET
2678 * @arg @ref LL_TIM_SLAVEMODE_GATED
2679 * @arg @ref LL_TIM_SLAVEMODE_TRIGGER
2682 __STATIC_INLINE
void LL_TIM_SetSlaveMode(TIM_TypeDef
*TIMx
, uint32_t SlaveMode
)
2684 MODIFY_REG(TIMx
->SMCR
, TIM_SMCR_SMS
, SlaveMode
);
2688 * @brief Set the selects the trigger input to be used to synchronize the counter.
2689 * @note Macro @ref IS_TIM_SLAVE_INSTANCE(TIMx) can be used to check whether or not
2690 * a timer instance can operate as a slave timer.
2691 * @rmtoll SMCR TS LL_TIM_SetTriggerInput
2692 * @param TIMx Timer instance
2693 * @param TriggerInput This parameter can be one of the following values:
2694 * @arg @ref LL_TIM_TS_ITR0
2695 * @arg @ref LL_TIM_TS_ITR1
2696 * @arg @ref LL_TIM_TS_ITR2
2697 * @arg @ref LL_TIM_TS_ITR3
2698 * @arg @ref LL_TIM_TS_TI1F_ED
2699 * @arg @ref LL_TIM_TS_TI1FP1
2700 * @arg @ref LL_TIM_TS_TI2FP2
2701 * @arg @ref LL_TIM_TS_ETRF
2704 __STATIC_INLINE
void LL_TIM_SetTriggerInput(TIM_TypeDef
*TIMx
, uint32_t TriggerInput
)
2706 MODIFY_REG(TIMx
->SMCR
, TIM_SMCR_TS
, TriggerInput
);
2710 * @brief Enable the Master/Slave mode.
2711 * @note Macro @ref IS_TIM_SLAVE_INSTANCE(TIMx) can be used to check whether or not
2712 * a timer instance can operate as a slave timer.
2713 * @rmtoll SMCR MSM LL_TIM_EnableMasterSlaveMode
2714 * @param TIMx Timer instance
2717 __STATIC_INLINE
void LL_TIM_EnableMasterSlaveMode(TIM_TypeDef
*TIMx
)
2719 SET_BIT(TIMx
->SMCR
, TIM_SMCR_MSM
);
2723 * @brief Disable the Master/Slave mode.
2724 * @note Macro @ref IS_TIM_SLAVE_INSTANCE(TIMx) can be used to check whether or not
2725 * a timer instance can operate as a slave timer.
2726 * @rmtoll SMCR MSM LL_TIM_DisableMasterSlaveMode
2727 * @param TIMx Timer instance
2730 __STATIC_INLINE
void LL_TIM_DisableMasterSlaveMode(TIM_TypeDef
*TIMx
)
2732 CLEAR_BIT(TIMx
->SMCR
, TIM_SMCR_MSM
);
2736 * @brief Indicates whether the Master/Slave mode is enabled.
2737 * @note Macro @ref IS_TIM_SLAVE_INSTANCE(TIMx) can be used to check whether or not
2738 * a timer instance can operate as a slave timer.
2739 * @rmtoll SMCR MSM LL_TIM_IsEnabledMasterSlaveMode
2740 * @param TIMx Timer instance
2741 * @retval State of bit (1 or 0).
2743 __STATIC_INLINE
uint32_t LL_TIM_IsEnabledMasterSlaveMode(TIM_TypeDef
*TIMx
)
2745 return (READ_BIT(TIMx
->SMCR
, TIM_SMCR_MSM
) == (TIM_SMCR_MSM
));
2749 * @brief Configure the external trigger (ETR) input.
2750 * @note Macro @ref IS_TIM_ETR_INSTANCE(TIMx) can be used to check whether or not
2751 * a timer instance provides an external trigger input.
2752 * @rmtoll SMCR ETP LL_TIM_ConfigETR\n
2753 * SMCR ETPS LL_TIM_ConfigETR\n
2754 * SMCR ETF LL_TIM_ConfigETR
2755 * @param TIMx Timer instance
2756 * @param ETRPolarity This parameter can be one of the following values:
2757 * @arg @ref LL_TIM_ETR_POLARITY_NONINVERTED
2758 * @arg @ref LL_TIM_ETR_POLARITY_INVERTED
2759 * @param ETRPrescaler This parameter can be one of the following values:
2760 * @arg @ref LL_TIM_ETR_PRESCALER_DIV1
2761 * @arg @ref LL_TIM_ETR_PRESCALER_DIV2
2762 * @arg @ref LL_TIM_ETR_PRESCALER_DIV4
2763 * @arg @ref LL_TIM_ETR_PRESCALER_DIV8
2764 * @param ETRFilter This parameter can be one of the following values:
2765 * @arg @ref LL_TIM_ETR_FILTER_FDIV1
2766 * @arg @ref LL_TIM_ETR_FILTER_FDIV1_N2
2767 * @arg @ref LL_TIM_ETR_FILTER_FDIV1_N4
2768 * @arg @ref LL_TIM_ETR_FILTER_FDIV1_N8
2769 * @arg @ref LL_TIM_ETR_FILTER_FDIV2_N6
2770 * @arg @ref LL_TIM_ETR_FILTER_FDIV2_N8
2771 * @arg @ref LL_TIM_ETR_FILTER_FDIV4_N6
2772 * @arg @ref LL_TIM_ETR_FILTER_FDIV4_N8
2773 * @arg @ref LL_TIM_ETR_FILTER_FDIV8_N6
2774 * @arg @ref LL_TIM_ETR_FILTER_FDIV8_N8
2775 * @arg @ref LL_TIM_ETR_FILTER_FDIV16_N5
2776 * @arg @ref LL_TIM_ETR_FILTER_FDIV16_N6
2777 * @arg @ref LL_TIM_ETR_FILTER_FDIV16_N8
2778 * @arg @ref LL_TIM_ETR_FILTER_FDIV32_N5
2779 * @arg @ref LL_TIM_ETR_FILTER_FDIV32_N6
2780 * @arg @ref LL_TIM_ETR_FILTER_FDIV32_N8
2783 __STATIC_INLINE
void LL_TIM_ConfigETR(TIM_TypeDef
*TIMx
, uint32_t ETRPolarity
, uint32_t ETRPrescaler
,
2786 MODIFY_REG(TIMx
->SMCR
, TIM_SMCR_ETP
| TIM_SMCR_ETPS
| TIM_SMCR_ETF
, ETRPolarity
| ETRPrescaler
| ETRFilter
);
2793 /** @defgroup TIM_LL_EF_Break_Function Break function configuration
2797 * @brief Enable the break function.
2798 * @note Macro @ref IS_TIM_BREAK_INSTANCE(TIMx) can be used to check whether or not
2799 * a timer instance provides a break input.
2800 * @rmtoll BDTR BKE LL_TIM_EnableBRK
2801 * @param TIMx Timer instance
2804 __STATIC_INLINE
void LL_TIM_EnableBRK(TIM_TypeDef
*TIMx
)
2806 SET_BIT(TIMx
->BDTR
, TIM_BDTR_BKE
);
2810 * @brief Disable the break function.
2811 * @rmtoll BDTR BKE LL_TIM_DisableBRK
2812 * @param TIMx Timer instance
2813 * @note Macro @ref IS_TIM_BREAK_INSTANCE(TIMx) can be used to check whether or not
2814 * a timer instance provides a break input.
2817 __STATIC_INLINE
void LL_TIM_DisableBRK(TIM_TypeDef
*TIMx
)
2819 CLEAR_BIT(TIMx
->BDTR
, TIM_BDTR_BKE
);
2823 * @brief Configure the break input.
2824 * @note Macro @ref IS_TIM_BREAK_INSTANCE(TIMx) can be used to check whether or not
2825 * a timer instance provides a break input.
2826 * @rmtoll BDTR BKP LL_TIM_ConfigBRK
2827 * @param TIMx Timer instance
2828 * @param BreakPolarity This parameter can be one of the following values:
2829 * @arg @ref LL_TIM_BREAK_POLARITY_LOW
2830 * @arg @ref LL_TIM_BREAK_POLARITY_HIGH
2833 __STATIC_INLINE
void LL_TIM_ConfigBRK(TIM_TypeDef
*TIMx
, uint32_t BreakPolarity
)
2835 MODIFY_REG(TIMx
->BDTR
, TIM_BDTR_BKP
, BreakPolarity
);
2839 * @brief Select the outputs off state (enabled v.s. disabled) in Idle and Run modes.
2840 * @note Macro @ref IS_TIM_BREAK_INSTANCE(TIMx) can be used to check whether or not
2841 * a timer instance provides a break input.
2842 * @rmtoll BDTR OSSI LL_TIM_SetOffStates\n
2843 * BDTR OSSR LL_TIM_SetOffStates
2844 * @param TIMx Timer instance
2845 * @param OffStateIdle This parameter can be one of the following values:
2846 * @arg @ref LL_TIM_OSSI_DISABLE
2847 * @arg @ref LL_TIM_OSSI_ENABLE
2848 * @param OffStateRun This parameter can be one of the following values:
2849 * @arg @ref LL_TIM_OSSR_DISABLE
2850 * @arg @ref LL_TIM_OSSR_ENABLE
2853 __STATIC_INLINE
void LL_TIM_SetOffStates(TIM_TypeDef
*TIMx
, uint32_t OffStateIdle
, uint32_t OffStateRun
)
2855 MODIFY_REG(TIMx
->BDTR
, TIM_BDTR_OSSI
| TIM_BDTR_OSSR
, OffStateIdle
| OffStateRun
);
2859 * @brief Enable automatic output (MOE can be set by software or automatically when a break input is active).
2860 * @note Macro @ref IS_TIM_BREAK_INSTANCE(TIMx) can be used to check whether or not
2861 * a timer instance provides a break input.
2862 * @rmtoll BDTR AOE LL_TIM_EnableAutomaticOutput
2863 * @param TIMx Timer instance
2866 __STATIC_INLINE
void LL_TIM_EnableAutomaticOutput(TIM_TypeDef
*TIMx
)
2868 SET_BIT(TIMx
->BDTR
, TIM_BDTR_AOE
);
2872 * @brief Disable automatic output (MOE can be set only by software).
2873 * @note Macro @ref IS_TIM_BREAK_INSTANCE(TIMx) can be used to check whether or not
2874 * a timer instance provides a break input.
2875 * @rmtoll BDTR AOE LL_TIM_DisableAutomaticOutput
2876 * @param TIMx Timer instance
2879 __STATIC_INLINE
void LL_TIM_DisableAutomaticOutput(TIM_TypeDef
*TIMx
)
2881 CLEAR_BIT(TIMx
->BDTR
, TIM_BDTR_AOE
);
2885 * @brief Indicate whether automatic output is enabled.
2886 * @note Macro @ref IS_TIM_BREAK_INSTANCE(TIMx) can be used to check whether or not
2887 * a timer instance provides a break input.
2888 * @rmtoll BDTR AOE LL_TIM_IsEnabledAutomaticOutput
2889 * @param TIMx Timer instance
2890 * @retval State of bit (1 or 0).
2892 __STATIC_INLINE
uint32_t LL_TIM_IsEnabledAutomaticOutput(TIM_TypeDef
*TIMx
)
2894 return (READ_BIT(TIMx
->BDTR
, TIM_BDTR_AOE
) == (TIM_BDTR_AOE
));
2898 * @brief Enable the outputs (set the MOE bit in TIMx_BDTR register).
2899 * @note The MOE bit in TIMx_BDTR register allows to enable /disable the outputs by
2900 * software and is reset in case of break or break2 event
2901 * @note Macro @ref IS_TIM_BREAK_INSTANCE(TIMx) can be used to check whether or not
2902 * a timer instance provides a break input.
2903 * @rmtoll BDTR MOE LL_TIM_EnableAllOutputs
2904 * @param TIMx Timer instance
2907 __STATIC_INLINE
void LL_TIM_EnableAllOutputs(TIM_TypeDef
*TIMx
)
2909 SET_BIT(TIMx
->BDTR
, TIM_BDTR_MOE
);
2913 * @brief Disable the outputs (reset the MOE bit in TIMx_BDTR register).
2914 * @note The MOE bit in TIMx_BDTR register allows to enable /disable the outputs by
2915 * software and is reset in case of break or break2 event.
2916 * @note Macro @ref IS_TIM_BREAK_INSTANCE(TIMx) can be used to check whether or not
2917 * a timer instance provides a break input.
2918 * @rmtoll BDTR MOE LL_TIM_DisableAllOutputs
2919 * @param TIMx Timer instance
2922 __STATIC_INLINE
void LL_TIM_DisableAllOutputs(TIM_TypeDef
*TIMx
)
2924 CLEAR_BIT(TIMx
->BDTR
, TIM_BDTR_MOE
);
2928 * @brief Indicates whether outputs are enabled.
2929 * @note Macro @ref IS_TIM_BREAK_INSTANCE(TIMx) can be used to check whether or not
2930 * a timer instance provides a break input.
2931 * @rmtoll BDTR MOE LL_TIM_IsEnabledAllOutputs
2932 * @param TIMx Timer instance
2933 * @retval State of bit (1 or 0).
2935 __STATIC_INLINE
uint32_t LL_TIM_IsEnabledAllOutputs(TIM_TypeDef
*TIMx
)
2937 return (READ_BIT(TIMx
->BDTR
, TIM_BDTR_MOE
) == (TIM_BDTR_MOE
));
2944 /** @defgroup TIM_LL_EF_DMA_Burst_Mode DMA burst mode configuration
2948 * @brief Configures the timer DMA burst feature.
2949 * @note Macro @ref IS_TIM_DMABURST_INSTANCE(TIMx) can be used to check whether or
2950 * not a timer instance supports the DMA burst mode.
2951 * @rmtoll DCR DBL LL_TIM_ConfigDMABurst\n
2952 * DCR DBA LL_TIM_ConfigDMABurst
2953 * @param TIMx Timer instance
2954 * @param DMABurstBaseAddress This parameter can be one of the following values:
2955 * @arg @ref LL_TIM_DMABURST_BASEADDR_CR1
2956 * @arg @ref LL_TIM_DMABURST_BASEADDR_CR2
2957 * @arg @ref LL_TIM_DMABURST_BASEADDR_SMCR
2958 * @arg @ref LL_TIM_DMABURST_BASEADDR_DIER
2959 * @arg @ref LL_TIM_DMABURST_BASEADDR_SR
2960 * @arg @ref LL_TIM_DMABURST_BASEADDR_EGR
2961 * @arg @ref LL_TIM_DMABURST_BASEADDR_CCMR1
2962 * @arg @ref LL_TIM_DMABURST_BASEADDR_CCMR2
2963 * @arg @ref LL_TIM_DMABURST_BASEADDR_CCER
2964 * @arg @ref LL_TIM_DMABURST_BASEADDR_CNT
2965 * @arg @ref LL_TIM_DMABURST_BASEADDR_PSC
2966 * @arg @ref LL_TIM_DMABURST_BASEADDR_ARR
2967 * @arg @ref LL_TIM_DMABURST_BASEADDR_RCR
2968 * @arg @ref LL_TIM_DMABURST_BASEADDR_CCR1
2969 * @arg @ref LL_TIM_DMABURST_BASEADDR_CCR2
2970 * @arg @ref LL_TIM_DMABURST_BASEADDR_CCR3
2971 * @arg @ref LL_TIM_DMABURST_BASEADDR_CCR4
2972 * @arg @ref LL_TIM_DMABURST_BASEADDR_BDTR
2973 * @arg @ref LL_TIM_DMABURST_BASEADDR_OR
2974 * @param DMABurstLength This parameter can be one of the following values:
2975 * @arg @ref LL_TIM_DMABURST_LENGTH_1TRANSFER
2976 * @arg @ref LL_TIM_DMABURST_LENGTH_2TRANSFERS
2977 * @arg @ref LL_TIM_DMABURST_LENGTH_3TRANSFERS
2978 * @arg @ref LL_TIM_DMABURST_LENGTH_4TRANSFERS
2979 * @arg @ref LL_TIM_DMABURST_LENGTH_5TRANSFERS
2980 * @arg @ref LL_TIM_DMABURST_LENGTH_6TRANSFERS
2981 * @arg @ref LL_TIM_DMABURST_LENGTH_7TRANSFERS
2982 * @arg @ref LL_TIM_DMABURST_LENGTH_8TRANSFERS
2983 * @arg @ref LL_TIM_DMABURST_LENGTH_9TRANSFERS
2984 * @arg @ref LL_TIM_DMABURST_LENGTH_10TRANSFERS
2985 * @arg @ref LL_TIM_DMABURST_LENGTH_11TRANSFERS
2986 * @arg @ref LL_TIM_DMABURST_LENGTH_12TRANSFERS
2987 * @arg @ref LL_TIM_DMABURST_LENGTH_13TRANSFERS
2988 * @arg @ref LL_TIM_DMABURST_LENGTH_14TRANSFERS
2989 * @arg @ref LL_TIM_DMABURST_LENGTH_15TRANSFERS
2990 * @arg @ref LL_TIM_DMABURST_LENGTH_16TRANSFERS
2991 * @arg @ref LL_TIM_DMABURST_LENGTH_17TRANSFERS
2992 * @arg @ref LL_TIM_DMABURST_LENGTH_18TRANSFERS
2995 __STATIC_INLINE
void LL_TIM_ConfigDMABurst(TIM_TypeDef
*TIMx
, uint32_t DMABurstBaseAddress
, uint32_t DMABurstLength
)
2997 MODIFY_REG(TIMx
->DCR
, TIM_DCR_DBL
| TIM_DCR_DBA
, DMABurstBaseAddress
| DMABurstLength
);
3004 /** @defgroup TIM_LL_EF_Timer_Inputs_Remapping Timer input remapping
3008 * @brief Remap TIM inputs (input channel, internal/external triggers).
3009 * @note Macro @ref IS_TIM_REMAP_INSTANCE(TIMx) can be used to check whether or not
3010 * a some timer inputs can be remapped.
3011 * @rmtoll TIM2_OR ITR1_RMP LL_TIM_SetRemap\n
3012 * TIM5_OR TI4_RMP LL_TIM_SetRemap\n
3013 * TIM11_OR TI1_RMP LL_TIM_SetRemap
3014 * @param TIMx Timer instance
3015 * @param Remap Remap param depends on the TIMx. Description available only
3016 * in CHM version of the User Manual (not in .pdf).
3017 * Otherwise see Reference Manual description of OR registers.
3019 * Below description summarizes "Timer Instance" and "Remap" param combinations:
3021 * TIM2: one of the following values
3023 * ITR1_RMP can be one of the following values
3024 * @arg @ref LL_TIM_TIM2_ITR1_RMP_TIM8_TRGO
3025 * @arg @ref LL_TIM_TIM2_ITR1_RMP_OTG_FS_SOF
3026 * @arg @ref LL_TIM_TIM2_ITR1_RMP_OTG_HS_SOF
3028 * TIM5: one of the following values
3030 * @arg @ref LL_TIM_TIM5_TI4_RMP_GPIO
3031 * @arg @ref LL_TIM_TIM5_TI4_RMP_LSI
3032 * @arg @ref LL_TIM_TIM5_TI4_RMP_LSE
3033 * @arg @ref LL_TIM_TIM5_TI4_RMP_RTC
3035 * TIM11: one of the following values
3037 * @arg @ref LL_TIM_TIM11_TI1_RMP_GPIO
3038 * @arg @ref LL_TIM_TIM11_TI1_RMP_GPIO1
3039 * @arg @ref LL_TIM_TIM11_TI1_RMP_HSE_RTC
3040 * @arg @ref LL_TIM_TIM11_TI1_RMP_GPIO2
3044 __STATIC_INLINE
void LL_TIM_SetRemap(TIM_TypeDef
*TIMx
, uint32_t Remap
)
3046 MODIFY_REG(TIMx
->OR
, (Remap
>> TIMx_OR_RMP_SHIFT
), (Remap
& TIMx_OR_RMP_MASK
));
3054 /** @defgroup TIM_LL_EF_FLAG_Management FLAG-Management
3058 * @brief Clear the update interrupt flag (UIF).
3059 * @rmtoll SR UIF LL_TIM_ClearFlag_UPDATE
3060 * @param TIMx Timer instance
3063 __STATIC_INLINE
void LL_TIM_ClearFlag_UPDATE(TIM_TypeDef
*TIMx
)
3065 WRITE_REG(TIMx
->SR
, ~(TIM_SR_UIF
));
3069 * @brief Indicate whether update interrupt flag (UIF) is set (update interrupt is pending).
3070 * @rmtoll SR UIF LL_TIM_IsActiveFlag_UPDATE
3071 * @param TIMx Timer instance
3072 * @retval State of bit (1 or 0).
3074 __STATIC_INLINE
uint32_t LL_TIM_IsActiveFlag_UPDATE(TIM_TypeDef
*TIMx
)
3076 return (READ_BIT(TIMx
->SR
, TIM_SR_UIF
) == (TIM_SR_UIF
));
3080 * @brief Clear the Capture/Compare 1 interrupt flag (CC1F).
3081 * @rmtoll SR CC1IF LL_TIM_ClearFlag_CC1
3082 * @param TIMx Timer instance
3085 __STATIC_INLINE
void LL_TIM_ClearFlag_CC1(TIM_TypeDef
*TIMx
)
3087 WRITE_REG(TIMx
->SR
, ~(TIM_SR_CC1IF
));
3091 * @brief Indicate whether Capture/Compare 1 interrupt flag (CC1F) is set (Capture/Compare 1 interrupt is pending).
3092 * @rmtoll SR CC1IF LL_TIM_IsActiveFlag_CC1
3093 * @param TIMx Timer instance
3094 * @retval State of bit (1 or 0).
3096 __STATIC_INLINE
uint32_t LL_TIM_IsActiveFlag_CC1(TIM_TypeDef
*TIMx
)
3098 return (READ_BIT(TIMx
->SR
, TIM_SR_CC1IF
) == (TIM_SR_CC1IF
));
3102 * @brief Clear the Capture/Compare 2 interrupt flag (CC2F).
3103 * @rmtoll SR CC2IF LL_TIM_ClearFlag_CC2
3104 * @param TIMx Timer instance
3107 __STATIC_INLINE
void LL_TIM_ClearFlag_CC2(TIM_TypeDef
*TIMx
)
3109 WRITE_REG(TIMx
->SR
, ~(TIM_SR_CC2IF
));
3113 * @brief Indicate whether Capture/Compare 2 interrupt flag (CC2F) is set (Capture/Compare 2 interrupt is pending).
3114 * @rmtoll SR CC2IF LL_TIM_IsActiveFlag_CC2
3115 * @param TIMx Timer instance
3116 * @retval State of bit (1 or 0).
3118 __STATIC_INLINE
uint32_t LL_TIM_IsActiveFlag_CC2(TIM_TypeDef
*TIMx
)
3120 return (READ_BIT(TIMx
->SR
, TIM_SR_CC2IF
) == (TIM_SR_CC2IF
));
3124 * @brief Clear the Capture/Compare 3 interrupt flag (CC3F).
3125 * @rmtoll SR CC3IF LL_TIM_ClearFlag_CC3
3126 * @param TIMx Timer instance
3129 __STATIC_INLINE
void LL_TIM_ClearFlag_CC3(TIM_TypeDef
*TIMx
)
3131 WRITE_REG(TIMx
->SR
, ~(TIM_SR_CC3IF
));
3135 * @brief Indicate whether Capture/Compare 3 interrupt flag (CC3F) is set (Capture/Compare 3 interrupt is pending).
3136 * @rmtoll SR CC3IF LL_TIM_IsActiveFlag_CC3
3137 * @param TIMx Timer instance
3138 * @retval State of bit (1 or 0).
3140 __STATIC_INLINE
uint32_t LL_TIM_IsActiveFlag_CC3(TIM_TypeDef
*TIMx
)
3142 return (READ_BIT(TIMx
->SR
, TIM_SR_CC3IF
) == (TIM_SR_CC3IF
));
3146 * @brief Clear the Capture/Compare 4 interrupt flag (CC4F).
3147 * @rmtoll SR CC4IF LL_TIM_ClearFlag_CC4
3148 * @param TIMx Timer instance
3151 __STATIC_INLINE
void LL_TIM_ClearFlag_CC4(TIM_TypeDef
*TIMx
)
3153 WRITE_REG(TIMx
->SR
, ~(TIM_SR_CC4IF
));
3157 * @brief Indicate whether Capture/Compare 4 interrupt flag (CC4F) is set (Capture/Compare 4 interrupt is pending).
3158 * @rmtoll SR CC4IF LL_TIM_IsActiveFlag_CC4
3159 * @param TIMx Timer instance
3160 * @retval State of bit (1 or 0).
3162 __STATIC_INLINE
uint32_t LL_TIM_IsActiveFlag_CC4(TIM_TypeDef
*TIMx
)
3164 return (READ_BIT(TIMx
->SR
, TIM_SR_CC4IF
) == (TIM_SR_CC4IF
));
3168 * @brief Clear the commutation interrupt flag (COMIF).
3169 * @rmtoll SR COMIF LL_TIM_ClearFlag_COM
3170 * @param TIMx Timer instance
3173 __STATIC_INLINE
void LL_TIM_ClearFlag_COM(TIM_TypeDef
*TIMx
)
3175 WRITE_REG(TIMx
->SR
, ~(TIM_SR_COMIF
));
3179 * @brief Indicate whether commutation interrupt flag (COMIF) is set (commutation interrupt is pending).
3180 * @rmtoll SR COMIF LL_TIM_IsActiveFlag_COM
3181 * @param TIMx Timer instance
3182 * @retval State of bit (1 or 0).
3184 __STATIC_INLINE
uint32_t LL_TIM_IsActiveFlag_COM(TIM_TypeDef
*TIMx
)
3186 return (READ_BIT(TIMx
->SR
, TIM_SR_COMIF
) == (TIM_SR_COMIF
));
3190 * @brief Clear the trigger interrupt flag (TIF).
3191 * @rmtoll SR TIF LL_TIM_ClearFlag_TRIG
3192 * @param TIMx Timer instance
3195 __STATIC_INLINE
void LL_TIM_ClearFlag_TRIG(TIM_TypeDef
*TIMx
)
3197 WRITE_REG(TIMx
->SR
, ~(TIM_SR_TIF
));
3201 * @brief Indicate whether trigger interrupt flag (TIF) is set (trigger interrupt is pending).
3202 * @rmtoll SR TIF LL_TIM_IsActiveFlag_TRIG
3203 * @param TIMx Timer instance
3204 * @retval State of bit (1 or 0).
3206 __STATIC_INLINE
uint32_t LL_TIM_IsActiveFlag_TRIG(TIM_TypeDef
*TIMx
)
3208 return (READ_BIT(TIMx
->SR
, TIM_SR_TIF
) == (TIM_SR_TIF
));
3212 * @brief Clear the break interrupt flag (BIF).
3213 * @rmtoll SR BIF LL_TIM_ClearFlag_BRK
3214 * @param TIMx Timer instance
3217 __STATIC_INLINE
void LL_TIM_ClearFlag_BRK(TIM_TypeDef
*TIMx
)
3219 WRITE_REG(TIMx
->SR
, ~(TIM_SR_BIF
));
3223 * @brief Indicate whether break interrupt flag (BIF) is set (break interrupt is pending).
3224 * @rmtoll SR BIF LL_TIM_IsActiveFlag_BRK
3225 * @param TIMx Timer instance
3226 * @retval State of bit (1 or 0).
3228 __STATIC_INLINE
uint32_t LL_TIM_IsActiveFlag_BRK(TIM_TypeDef
*TIMx
)
3230 return (READ_BIT(TIMx
->SR
, TIM_SR_BIF
) == (TIM_SR_BIF
));
3234 * @brief Clear the Capture/Compare 1 over-capture interrupt flag (CC1OF).
3235 * @rmtoll SR CC1OF LL_TIM_ClearFlag_CC1OVR
3236 * @param TIMx Timer instance
3239 __STATIC_INLINE
void LL_TIM_ClearFlag_CC1OVR(TIM_TypeDef
*TIMx
)
3241 WRITE_REG(TIMx
->SR
, ~(TIM_SR_CC1OF
));
3245 * @brief Indicate whether Capture/Compare 1 over-capture interrupt flag (CC1OF) is set (Capture/Compare 1 interrupt is pending).
3246 * @rmtoll SR CC1OF LL_TIM_IsActiveFlag_CC1OVR
3247 * @param TIMx Timer instance
3248 * @retval State of bit (1 or 0).
3250 __STATIC_INLINE
uint32_t LL_TIM_IsActiveFlag_CC1OVR(TIM_TypeDef
*TIMx
)
3252 return (READ_BIT(TIMx
->SR
, TIM_SR_CC1OF
) == (TIM_SR_CC1OF
));
3256 * @brief Clear the Capture/Compare 2 over-capture interrupt flag (CC2OF).
3257 * @rmtoll SR CC2OF LL_TIM_ClearFlag_CC2OVR
3258 * @param TIMx Timer instance
3261 __STATIC_INLINE
void LL_TIM_ClearFlag_CC2OVR(TIM_TypeDef
*TIMx
)
3263 WRITE_REG(TIMx
->SR
, ~(TIM_SR_CC2OF
));
3267 * @brief Indicate whether Capture/Compare 2 over-capture interrupt flag (CC2OF) is set (Capture/Compare 2 over-capture interrupt is pending).
3268 * @rmtoll SR CC2OF LL_TIM_IsActiveFlag_CC2OVR
3269 * @param TIMx Timer instance
3270 * @retval State of bit (1 or 0).
3272 __STATIC_INLINE
uint32_t LL_TIM_IsActiveFlag_CC2OVR(TIM_TypeDef
*TIMx
)
3274 return (READ_BIT(TIMx
->SR
, TIM_SR_CC2OF
) == (TIM_SR_CC2OF
));
3278 * @brief Clear the Capture/Compare 3 over-capture interrupt flag (CC3OF).
3279 * @rmtoll SR CC3OF LL_TIM_ClearFlag_CC3OVR
3280 * @param TIMx Timer instance
3283 __STATIC_INLINE
void LL_TIM_ClearFlag_CC3OVR(TIM_TypeDef
*TIMx
)
3285 WRITE_REG(TIMx
->SR
, ~(TIM_SR_CC3OF
));
3289 * @brief Indicate whether Capture/Compare 3 over-capture interrupt flag (CC3OF) is set (Capture/Compare 3 over-capture interrupt is pending).
3290 * @rmtoll SR CC3OF LL_TIM_IsActiveFlag_CC3OVR
3291 * @param TIMx Timer instance
3292 * @retval State of bit (1 or 0).
3294 __STATIC_INLINE
uint32_t LL_TIM_IsActiveFlag_CC3OVR(TIM_TypeDef
*TIMx
)
3296 return (READ_BIT(TIMx
->SR
, TIM_SR_CC3OF
) == (TIM_SR_CC3OF
));
3300 * @brief Clear the Capture/Compare 4 over-capture interrupt flag (CC4OF).
3301 * @rmtoll SR CC4OF LL_TIM_ClearFlag_CC4OVR
3302 * @param TIMx Timer instance
3305 __STATIC_INLINE
void LL_TIM_ClearFlag_CC4OVR(TIM_TypeDef
*TIMx
)
3307 WRITE_REG(TIMx
->SR
, ~(TIM_SR_CC4OF
));
3311 * @brief Indicate whether Capture/Compare 4 over-capture interrupt flag (CC4OF) is set (Capture/Compare 4 over-capture interrupt is pending).
3312 * @rmtoll SR CC4OF LL_TIM_IsActiveFlag_CC4OVR
3313 * @param TIMx Timer instance
3314 * @retval State of bit (1 or 0).
3316 __STATIC_INLINE
uint32_t LL_TIM_IsActiveFlag_CC4OVR(TIM_TypeDef
*TIMx
)
3318 return (READ_BIT(TIMx
->SR
, TIM_SR_CC4OF
) == (TIM_SR_CC4OF
));
3325 /** @defgroup TIM_LL_EF_IT_Management IT-Management
3329 * @brief Enable update interrupt (UIE).
3330 * @rmtoll DIER UIE LL_TIM_EnableIT_UPDATE
3331 * @param TIMx Timer instance
3334 __STATIC_INLINE
void LL_TIM_EnableIT_UPDATE(TIM_TypeDef
*TIMx
)
3336 SET_BIT(TIMx
->DIER
, TIM_DIER_UIE
);
3340 * @brief Disable update interrupt (UIE).
3341 * @rmtoll DIER UIE LL_TIM_DisableIT_UPDATE
3342 * @param TIMx Timer instance
3345 __STATIC_INLINE
void LL_TIM_DisableIT_UPDATE(TIM_TypeDef
*TIMx
)
3347 CLEAR_BIT(TIMx
->DIER
, TIM_DIER_UIE
);
3351 * @brief Indicates whether the update interrupt (UIE) is enabled.
3352 * @rmtoll DIER UIE LL_TIM_IsEnabledIT_UPDATE
3353 * @param TIMx Timer instance
3354 * @retval State of bit (1 or 0).
3356 __STATIC_INLINE
uint32_t LL_TIM_IsEnabledIT_UPDATE(TIM_TypeDef
*TIMx
)
3358 return (READ_BIT(TIMx
->DIER
, TIM_DIER_UIE
) == (TIM_DIER_UIE
));
3362 * @brief Enable capture/compare 1 interrupt (CC1IE).
3363 * @rmtoll DIER CC1IE LL_TIM_EnableIT_CC1
3364 * @param TIMx Timer instance
3367 __STATIC_INLINE
void LL_TIM_EnableIT_CC1(TIM_TypeDef
*TIMx
)
3369 SET_BIT(TIMx
->DIER
, TIM_DIER_CC1IE
);
3373 * @brief Disable capture/compare 1 interrupt (CC1IE).
3374 * @rmtoll DIER CC1IE LL_TIM_DisableIT_CC1
3375 * @param TIMx Timer instance
3378 __STATIC_INLINE
void LL_TIM_DisableIT_CC1(TIM_TypeDef
*TIMx
)
3380 CLEAR_BIT(TIMx
->DIER
, TIM_DIER_CC1IE
);
3384 * @brief Indicates whether the capture/compare 1 interrupt (CC1IE) is enabled.
3385 * @rmtoll DIER CC1IE LL_TIM_IsEnabledIT_CC1
3386 * @param TIMx Timer instance
3387 * @retval State of bit (1 or 0).
3389 __STATIC_INLINE
uint32_t LL_TIM_IsEnabledIT_CC1(TIM_TypeDef
*TIMx
)
3391 return (READ_BIT(TIMx
->DIER
, TIM_DIER_CC1IE
) == (TIM_DIER_CC1IE
));
3395 * @brief Enable capture/compare 2 interrupt (CC2IE).
3396 * @rmtoll DIER CC2IE LL_TIM_EnableIT_CC2
3397 * @param TIMx Timer instance
3400 __STATIC_INLINE
void LL_TIM_EnableIT_CC2(TIM_TypeDef
*TIMx
)
3402 SET_BIT(TIMx
->DIER
, TIM_DIER_CC2IE
);
3406 * @brief Disable capture/compare 2 interrupt (CC2IE).
3407 * @rmtoll DIER CC2IE LL_TIM_DisableIT_CC2
3408 * @param TIMx Timer instance
3411 __STATIC_INLINE
void LL_TIM_DisableIT_CC2(TIM_TypeDef
*TIMx
)
3413 CLEAR_BIT(TIMx
->DIER
, TIM_DIER_CC2IE
);
3417 * @brief Indicates whether the capture/compare 2 interrupt (CC2IE) is enabled.
3418 * @rmtoll DIER CC2IE LL_TIM_IsEnabledIT_CC2
3419 * @param TIMx Timer instance
3420 * @retval State of bit (1 or 0).
3422 __STATIC_INLINE
uint32_t LL_TIM_IsEnabledIT_CC2(TIM_TypeDef
*TIMx
)
3424 return (READ_BIT(TIMx
->DIER
, TIM_DIER_CC2IE
) == (TIM_DIER_CC2IE
));
3428 * @brief Enable capture/compare 3 interrupt (CC3IE).
3429 * @rmtoll DIER CC3IE LL_TIM_EnableIT_CC3
3430 * @param TIMx Timer instance
3433 __STATIC_INLINE
void LL_TIM_EnableIT_CC3(TIM_TypeDef
*TIMx
)
3435 SET_BIT(TIMx
->DIER
, TIM_DIER_CC3IE
);
3439 * @brief Disable capture/compare 3 interrupt (CC3IE).
3440 * @rmtoll DIER CC3IE LL_TIM_DisableIT_CC3
3441 * @param TIMx Timer instance
3444 __STATIC_INLINE
void LL_TIM_DisableIT_CC3(TIM_TypeDef
*TIMx
)
3446 CLEAR_BIT(TIMx
->DIER
, TIM_DIER_CC3IE
);
3450 * @brief Indicates whether the capture/compare 3 interrupt (CC3IE) is enabled.
3451 * @rmtoll DIER CC3IE LL_TIM_IsEnabledIT_CC3
3452 * @param TIMx Timer instance
3453 * @retval State of bit (1 or 0).
3455 __STATIC_INLINE
uint32_t LL_TIM_IsEnabledIT_CC3(TIM_TypeDef
*TIMx
)
3457 return (READ_BIT(TIMx
->DIER
, TIM_DIER_CC3IE
) == (TIM_DIER_CC3IE
));
3461 * @brief Enable capture/compare 4 interrupt (CC4IE).
3462 * @rmtoll DIER CC4IE LL_TIM_EnableIT_CC4
3463 * @param TIMx Timer instance
3466 __STATIC_INLINE
void LL_TIM_EnableIT_CC4(TIM_TypeDef
*TIMx
)
3468 SET_BIT(TIMx
->DIER
, TIM_DIER_CC4IE
);
3472 * @brief Disable capture/compare 4 interrupt (CC4IE).
3473 * @rmtoll DIER CC4IE LL_TIM_DisableIT_CC4
3474 * @param TIMx Timer instance
3477 __STATIC_INLINE
void LL_TIM_DisableIT_CC4(TIM_TypeDef
*TIMx
)
3479 CLEAR_BIT(TIMx
->DIER
, TIM_DIER_CC4IE
);
3483 * @brief Indicates whether the capture/compare 4 interrupt (CC4IE) is enabled.
3484 * @rmtoll DIER CC4IE LL_TIM_IsEnabledIT_CC4
3485 * @param TIMx Timer instance
3486 * @retval State of bit (1 or 0).
3488 __STATIC_INLINE
uint32_t LL_TIM_IsEnabledIT_CC4(TIM_TypeDef
*TIMx
)
3490 return (READ_BIT(TIMx
->DIER
, TIM_DIER_CC4IE
) == (TIM_DIER_CC4IE
));
3494 * @brief Enable commutation interrupt (COMIE).
3495 * @rmtoll DIER COMIE LL_TIM_EnableIT_COM
3496 * @param TIMx Timer instance
3499 __STATIC_INLINE
void LL_TIM_EnableIT_COM(TIM_TypeDef
*TIMx
)
3501 SET_BIT(TIMx
->DIER
, TIM_DIER_COMIE
);
3505 * @brief Disable commutation interrupt (COMIE).
3506 * @rmtoll DIER COMIE LL_TIM_DisableIT_COM
3507 * @param TIMx Timer instance
3510 __STATIC_INLINE
void LL_TIM_DisableIT_COM(TIM_TypeDef
*TIMx
)
3512 CLEAR_BIT(TIMx
->DIER
, TIM_DIER_COMIE
);
3516 * @brief Indicates whether the commutation interrupt (COMIE) is enabled.
3517 * @rmtoll DIER COMIE LL_TIM_IsEnabledIT_COM
3518 * @param TIMx Timer instance
3519 * @retval State of bit (1 or 0).
3521 __STATIC_INLINE
uint32_t LL_TIM_IsEnabledIT_COM(TIM_TypeDef
*TIMx
)
3523 return (READ_BIT(TIMx
->DIER
, TIM_DIER_COMIE
) == (TIM_DIER_COMIE
));
3527 * @brief Enable trigger interrupt (TIE).
3528 * @rmtoll DIER TIE LL_TIM_EnableIT_TRIG
3529 * @param TIMx Timer instance
3532 __STATIC_INLINE
void LL_TIM_EnableIT_TRIG(TIM_TypeDef
*TIMx
)
3534 SET_BIT(TIMx
->DIER
, TIM_DIER_TIE
);
3538 * @brief Disable trigger interrupt (TIE).
3539 * @rmtoll DIER TIE LL_TIM_DisableIT_TRIG
3540 * @param TIMx Timer instance
3543 __STATIC_INLINE
void LL_TIM_DisableIT_TRIG(TIM_TypeDef
*TIMx
)
3545 CLEAR_BIT(TIMx
->DIER
, TIM_DIER_TIE
);
3549 * @brief Indicates whether the trigger interrupt (TIE) is enabled.
3550 * @rmtoll DIER TIE LL_TIM_IsEnabledIT_TRIG
3551 * @param TIMx Timer instance
3552 * @retval State of bit (1 or 0).
3554 __STATIC_INLINE
uint32_t LL_TIM_IsEnabledIT_TRIG(TIM_TypeDef
*TIMx
)
3556 return (READ_BIT(TIMx
->DIER
, TIM_DIER_TIE
) == (TIM_DIER_TIE
));
3560 * @brief Enable break interrupt (BIE).
3561 * @rmtoll DIER BIE LL_TIM_EnableIT_BRK
3562 * @param TIMx Timer instance
3565 __STATIC_INLINE
void LL_TIM_EnableIT_BRK(TIM_TypeDef
*TIMx
)
3567 SET_BIT(TIMx
->DIER
, TIM_DIER_BIE
);
3571 * @brief Disable break interrupt (BIE).
3572 * @rmtoll DIER BIE LL_TIM_DisableIT_BRK
3573 * @param TIMx Timer instance
3576 __STATIC_INLINE
void LL_TIM_DisableIT_BRK(TIM_TypeDef
*TIMx
)
3578 CLEAR_BIT(TIMx
->DIER
, TIM_DIER_BIE
);
3582 * @brief Indicates whether the break interrupt (BIE) is enabled.
3583 * @rmtoll DIER BIE LL_TIM_IsEnabledIT_BRK
3584 * @param TIMx Timer instance
3585 * @retval State of bit (1 or 0).
3587 __STATIC_INLINE
uint32_t LL_TIM_IsEnabledIT_BRK(TIM_TypeDef
*TIMx
)
3589 return (READ_BIT(TIMx
->DIER
, TIM_DIER_BIE
) == (TIM_DIER_BIE
));
3596 /** @defgroup TIM_LL_EF_DMA_Management DMA-Management
3600 * @brief Enable update DMA request (UDE).
3601 * @rmtoll DIER UDE LL_TIM_EnableDMAReq_UPDATE
3602 * @param TIMx Timer instance
3605 __STATIC_INLINE
void LL_TIM_EnableDMAReq_UPDATE(TIM_TypeDef
*TIMx
)
3607 SET_BIT(TIMx
->DIER
, TIM_DIER_UDE
);
3611 * @brief Disable update DMA request (UDE).
3612 * @rmtoll DIER UDE LL_TIM_DisableDMAReq_UPDATE
3613 * @param TIMx Timer instance
3616 __STATIC_INLINE
void LL_TIM_DisableDMAReq_UPDATE(TIM_TypeDef
*TIMx
)
3618 CLEAR_BIT(TIMx
->DIER
, TIM_DIER_UDE
);
3622 * @brief Indicates whether the update DMA request (UDE) is enabled.
3623 * @rmtoll DIER UDE LL_TIM_IsEnabledDMAReq_UPDATE
3624 * @param TIMx Timer instance
3625 * @retval State of bit (1 or 0).
3627 __STATIC_INLINE
uint32_t LL_TIM_IsEnabledDMAReq_UPDATE(TIM_TypeDef
*TIMx
)
3629 return (READ_BIT(TIMx
->DIER
, TIM_DIER_UDE
) == (TIM_DIER_UDE
));
3633 * @brief Enable capture/compare 1 DMA request (CC1DE).
3634 * @rmtoll DIER CC1DE LL_TIM_EnableDMAReq_CC1
3635 * @param TIMx Timer instance
3638 __STATIC_INLINE
void LL_TIM_EnableDMAReq_CC1(TIM_TypeDef
*TIMx
)
3640 SET_BIT(TIMx
->DIER
, TIM_DIER_CC1DE
);
3644 * @brief Disable capture/compare 1 DMA request (CC1DE).
3645 * @rmtoll DIER CC1DE LL_TIM_DisableDMAReq_CC1
3646 * @param TIMx Timer instance
3649 __STATIC_INLINE
void LL_TIM_DisableDMAReq_CC1(TIM_TypeDef
*TIMx
)
3651 CLEAR_BIT(TIMx
->DIER
, TIM_DIER_CC1DE
);
3655 * @brief Indicates whether the capture/compare 1 DMA request (CC1DE) is enabled.
3656 * @rmtoll DIER CC1DE LL_TIM_IsEnabledDMAReq_CC1
3657 * @param TIMx Timer instance
3658 * @retval State of bit (1 or 0).
3660 __STATIC_INLINE
uint32_t LL_TIM_IsEnabledDMAReq_CC1(TIM_TypeDef
*TIMx
)
3662 return (READ_BIT(TIMx
->DIER
, TIM_DIER_CC1DE
) == (TIM_DIER_CC1DE
));
3666 * @brief Enable capture/compare 2 DMA request (CC2DE).
3667 * @rmtoll DIER CC2DE LL_TIM_EnableDMAReq_CC2
3668 * @param TIMx Timer instance
3671 __STATIC_INLINE
void LL_TIM_EnableDMAReq_CC2(TIM_TypeDef
*TIMx
)
3673 SET_BIT(TIMx
->DIER
, TIM_DIER_CC2DE
);
3677 * @brief Disable capture/compare 2 DMA request (CC2DE).
3678 * @rmtoll DIER CC2DE LL_TIM_DisableDMAReq_CC2
3679 * @param TIMx Timer instance
3682 __STATIC_INLINE
void LL_TIM_DisableDMAReq_CC2(TIM_TypeDef
*TIMx
)
3684 CLEAR_BIT(TIMx
->DIER
, TIM_DIER_CC2DE
);
3688 * @brief Indicates whether the capture/compare 2 DMA request (CC2DE) is enabled.
3689 * @rmtoll DIER CC2DE LL_TIM_IsEnabledDMAReq_CC2
3690 * @param TIMx Timer instance
3691 * @retval State of bit (1 or 0).
3693 __STATIC_INLINE
uint32_t LL_TIM_IsEnabledDMAReq_CC2(TIM_TypeDef
*TIMx
)
3695 return (READ_BIT(TIMx
->DIER
, TIM_DIER_CC2DE
) == (TIM_DIER_CC2DE
));
3699 * @brief Enable capture/compare 3 DMA request (CC3DE).
3700 * @rmtoll DIER CC3DE LL_TIM_EnableDMAReq_CC3
3701 * @param TIMx Timer instance
3704 __STATIC_INLINE
void LL_TIM_EnableDMAReq_CC3(TIM_TypeDef
*TIMx
)
3706 SET_BIT(TIMx
->DIER
, TIM_DIER_CC3DE
);
3710 * @brief Disable capture/compare 3 DMA request (CC3DE).
3711 * @rmtoll DIER CC3DE LL_TIM_DisableDMAReq_CC3
3712 * @param TIMx Timer instance
3715 __STATIC_INLINE
void LL_TIM_DisableDMAReq_CC3(TIM_TypeDef
*TIMx
)
3717 CLEAR_BIT(TIMx
->DIER
, TIM_DIER_CC3DE
);
3721 * @brief Indicates whether the capture/compare 3 DMA request (CC3DE) is enabled.
3722 * @rmtoll DIER CC3DE LL_TIM_IsEnabledDMAReq_CC3
3723 * @param TIMx Timer instance
3724 * @retval State of bit (1 or 0).
3726 __STATIC_INLINE
uint32_t LL_TIM_IsEnabledDMAReq_CC3(TIM_TypeDef
*TIMx
)
3728 return (READ_BIT(TIMx
->DIER
, TIM_DIER_CC3DE
) == (TIM_DIER_CC3DE
));
3732 * @brief Enable capture/compare 4 DMA request (CC4DE).
3733 * @rmtoll DIER CC4DE LL_TIM_EnableDMAReq_CC4
3734 * @param TIMx Timer instance
3737 __STATIC_INLINE
void LL_TIM_EnableDMAReq_CC4(TIM_TypeDef
*TIMx
)
3739 SET_BIT(TIMx
->DIER
, TIM_DIER_CC4DE
);
3743 * @brief Disable capture/compare 4 DMA request (CC4DE).
3744 * @rmtoll DIER CC4DE LL_TIM_DisableDMAReq_CC4
3745 * @param TIMx Timer instance
3748 __STATIC_INLINE
void LL_TIM_DisableDMAReq_CC4(TIM_TypeDef
*TIMx
)
3750 CLEAR_BIT(TIMx
->DIER
, TIM_DIER_CC4DE
);
3754 * @brief Indicates whether the capture/compare 4 DMA request (CC4DE) is enabled.
3755 * @rmtoll DIER CC4DE LL_TIM_IsEnabledDMAReq_CC4
3756 * @param TIMx Timer instance
3757 * @retval State of bit (1 or 0).
3759 __STATIC_INLINE
uint32_t LL_TIM_IsEnabledDMAReq_CC4(TIM_TypeDef
*TIMx
)
3761 return (READ_BIT(TIMx
->DIER
, TIM_DIER_CC4DE
) == (TIM_DIER_CC4DE
));
3765 * @brief Enable commutation DMA request (COMDE).
3766 * @rmtoll DIER COMDE LL_TIM_EnableDMAReq_COM
3767 * @param TIMx Timer instance
3770 __STATIC_INLINE
void LL_TIM_EnableDMAReq_COM(TIM_TypeDef
*TIMx
)
3772 SET_BIT(TIMx
->DIER
, TIM_DIER_COMDE
);
3776 * @brief Disable commutation DMA request (COMDE).
3777 * @rmtoll DIER COMDE LL_TIM_DisableDMAReq_COM
3778 * @param TIMx Timer instance
3781 __STATIC_INLINE
void LL_TIM_DisableDMAReq_COM(TIM_TypeDef
*TIMx
)
3783 CLEAR_BIT(TIMx
->DIER
, TIM_DIER_COMDE
);
3787 * @brief Indicates whether the commutation DMA request (COMDE) is enabled.
3788 * @rmtoll DIER COMDE LL_TIM_IsEnabledDMAReq_COM
3789 * @param TIMx Timer instance
3790 * @retval State of bit (1 or 0).
3792 __STATIC_INLINE
uint32_t LL_TIM_IsEnabledDMAReq_COM(TIM_TypeDef
*TIMx
)
3794 return (READ_BIT(TIMx
->DIER
, TIM_DIER_COMDE
) == (TIM_DIER_COMDE
));
3798 * @brief Enable trigger interrupt (TDE).
3799 * @rmtoll DIER TDE LL_TIM_EnableDMAReq_TRIG
3800 * @param TIMx Timer instance
3803 __STATIC_INLINE
void LL_TIM_EnableDMAReq_TRIG(TIM_TypeDef
*TIMx
)
3805 SET_BIT(TIMx
->DIER
, TIM_DIER_TDE
);
3809 * @brief Disable trigger interrupt (TDE).
3810 * @rmtoll DIER TDE LL_TIM_DisableDMAReq_TRIG
3811 * @param TIMx Timer instance
3814 __STATIC_INLINE
void LL_TIM_DisableDMAReq_TRIG(TIM_TypeDef
*TIMx
)
3816 CLEAR_BIT(TIMx
->DIER
, TIM_DIER_TDE
);
3820 * @brief Indicates whether the trigger interrupt (TDE) is enabled.
3821 * @rmtoll DIER TDE LL_TIM_IsEnabledDMAReq_TRIG
3822 * @param TIMx Timer instance
3823 * @retval State of bit (1 or 0).
3825 __STATIC_INLINE
uint32_t LL_TIM_IsEnabledDMAReq_TRIG(TIM_TypeDef
*TIMx
)
3827 return (READ_BIT(TIMx
->DIER
, TIM_DIER_TDE
) == (TIM_DIER_TDE
));
3834 /** @defgroup TIM_LL_EF_EVENT_Management EVENT-Management
3838 * @brief Generate an update event.
3839 * @rmtoll EGR UG LL_TIM_GenerateEvent_UPDATE
3840 * @param TIMx Timer instance
3843 __STATIC_INLINE
void LL_TIM_GenerateEvent_UPDATE(TIM_TypeDef
*TIMx
)
3845 SET_BIT(TIMx
->EGR
, TIM_EGR_UG
);
3849 * @brief Generate Capture/Compare 1 event.
3850 * @rmtoll EGR CC1G LL_TIM_GenerateEvent_CC1
3851 * @param TIMx Timer instance
3854 __STATIC_INLINE
void LL_TIM_GenerateEvent_CC1(TIM_TypeDef
*TIMx
)
3856 SET_BIT(TIMx
->EGR
, TIM_EGR_CC1G
);
3860 * @brief Generate Capture/Compare 2 event.
3861 * @rmtoll EGR CC2G LL_TIM_GenerateEvent_CC2
3862 * @param TIMx Timer instance
3865 __STATIC_INLINE
void LL_TIM_GenerateEvent_CC2(TIM_TypeDef
*TIMx
)
3867 SET_BIT(TIMx
->EGR
, TIM_EGR_CC2G
);
3871 * @brief Generate Capture/Compare 3 event.
3872 * @rmtoll EGR CC3G LL_TIM_GenerateEvent_CC3
3873 * @param TIMx Timer instance
3876 __STATIC_INLINE
void LL_TIM_GenerateEvent_CC3(TIM_TypeDef
*TIMx
)
3878 SET_BIT(TIMx
->EGR
, TIM_EGR_CC3G
);
3882 * @brief Generate Capture/Compare 4 event.
3883 * @rmtoll EGR CC4G LL_TIM_GenerateEvent_CC4
3884 * @param TIMx Timer instance
3887 __STATIC_INLINE
void LL_TIM_GenerateEvent_CC4(TIM_TypeDef
*TIMx
)
3889 SET_BIT(TIMx
->EGR
, TIM_EGR_CC4G
);
3893 * @brief Generate commutation event.
3894 * @rmtoll EGR COMG LL_TIM_GenerateEvent_COM
3895 * @param TIMx Timer instance
3898 __STATIC_INLINE
void LL_TIM_GenerateEvent_COM(TIM_TypeDef
*TIMx
)
3900 SET_BIT(TIMx
->EGR
, TIM_EGR_COMG
);
3904 * @brief Generate trigger event.
3905 * @rmtoll EGR TG LL_TIM_GenerateEvent_TRIG
3906 * @param TIMx Timer instance
3909 __STATIC_INLINE
void LL_TIM_GenerateEvent_TRIG(TIM_TypeDef
*TIMx
)
3911 SET_BIT(TIMx
->EGR
, TIM_EGR_TG
);
3915 * @brief Generate break event.
3916 * @rmtoll EGR BG LL_TIM_GenerateEvent_BRK
3917 * @param TIMx Timer instance
3920 __STATIC_INLINE
void LL_TIM_GenerateEvent_BRK(TIM_TypeDef
*TIMx
)
3922 SET_BIT(TIMx
->EGR
, TIM_EGR_BG
);
3929 #if defined(USE_FULL_LL_DRIVER)
3930 /** @defgroup TIM_LL_EF_Init Initialisation and deinitialisation functions
3934 ErrorStatus
LL_TIM_DeInit(TIM_TypeDef
*TIMx
);
3935 void LL_TIM_StructInit(LL_TIM_InitTypeDef
*TIM_InitStruct
);
3936 ErrorStatus
LL_TIM_Init(TIM_TypeDef
*TIMx
, LL_TIM_InitTypeDef
*TIM_InitStruct
);
3937 void LL_TIM_OC_StructInit(LL_TIM_OC_InitTypeDef
*TIM_OC_InitStruct
);
3938 ErrorStatus
LL_TIM_OC_Init(TIM_TypeDef
*TIMx
, uint32_t Channel
, LL_TIM_OC_InitTypeDef
*TIM_OC_InitStruct
);
3939 void LL_TIM_IC_StructInit(LL_TIM_IC_InitTypeDef
*TIM_ICInitStruct
);
3940 ErrorStatus
LL_TIM_IC_Init(TIM_TypeDef
*TIMx
, uint32_t Channel
, LL_TIM_IC_InitTypeDef
*TIM_IC_InitStruct
);
3941 void LL_TIM_ENCODER_StructInit(LL_TIM_ENCODER_InitTypeDef
*TIM_EncoderInitStruct
);
3942 ErrorStatus
LL_TIM_ENCODER_Init(TIM_TypeDef
*TIMx
, LL_TIM_ENCODER_InitTypeDef
*TIM_EncoderInitStruct
);
3943 void LL_TIM_HALLSENSOR_StructInit(LL_TIM_HALLSENSOR_InitTypeDef
*TIM_HallSensorInitStruct
);
3944 ErrorStatus
LL_TIM_HALLSENSOR_Init(TIM_TypeDef
*TIMx
, LL_TIM_HALLSENSOR_InitTypeDef
*TIM_HallSensorInitStruct
);
3945 void LL_TIM_BDTR_StructInit(LL_TIM_BDTR_InitTypeDef
*TIM_BDTRInitStruct
);
3946 ErrorStatus
LL_TIM_BDTR_Init(TIM_TypeDef
*TIMx
, LL_TIM_BDTR_InitTypeDef
*TIM_BDTRInitStruct
);
3950 #endif /* USE_FULL_LL_DRIVER */
3960 #endif /* TIM1 || TIM2 || TIM3 || TIM4 || TIM5 || TIM6 || TIM7 || TIM8 || TIM9 || TIM10 || TIM11 || TIM12 || TIM13 || TIM14 */
3970 #endif /* __STM32F4xx_LL_TIM_H */
3971 /************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/