2 ******************************************************************************
3 * @file stm32f4xx_hal_lptim.c
4 * @author MCD Application Team
7 * @brief LPTIM HAL module driver.
8 * This file provides firmware functions to manage the following
9 * functionalities of the Low Power Timer (LPTIM) peripheral:
10 * + Initialization and de-initialization functions.
11 * + Start/Stop operation functions in polling mode.
12 * + Start/Stop operation functions in interrupt mode.
13 * + Reading operation functions.
14 * + Peripheral State functions.
17 ==============================================================================
18 ##### How to use this driver #####
19 ==============================================================================
21 The LPTIM HAL driver can be used as follows:
23 (#)Initialize the LPTIM low level resources by implementing the
25 (##) Enable the LPTIM interface clock using __LPTIMx_CLK_ENABLE().
26 (##) In case of using interrupts (e.g. HAL_LPTIM_PWM_Start_IT()):
27 (+++) Configure the LPTIM interrupt priority using HAL_NVIC_SetPriority().
28 (+++) Enable the LPTIM IRQ handler using HAL_NVIC_EnableIRQ().
29 (+++) In LPTIM IRQ handler, call HAL_LPTIM_IRQHandler().
31 (#)Initialize the LPTIM HAL using HAL_LPTIM_Init(). This function
33 (##) The instance: LPTIM1.
34 (##) Clock: the counter clock.
35 (+++) Source : it can be either the ULPTIM input (IN1) or one of
36 the internal clock; (APB, LSE or LSI).
37 (+++) Prescaler: select the clock divider.
38 (##) UltraLowPowerClock : To be used only if the ULPTIM is selected
39 as counter clock source.
40 (+++) Polarity: polarity of the active edge for the counter unit
41 if the ULPTIM input is selected.
42 (+++) SampleTime: clock sampling time to configure the clock glitch
44 (##) Trigger: How the counter start.
45 (+++) Source: trigger can be software or one of the hardware triggers.
46 (+++) ActiveEdge : only for hardware trigger.
47 (+++) SampleTime : trigger sampling time to configure the trigger
49 (##) OutputPolarity : 2 opposite polarities are possibles.
50 (##) UpdateMode: specifies whether the update of the autoreload and
51 the compare values is done immediately or after the end of current
54 (#)Six modes are available:
56 (##) PWM Mode: To generate a PWM signal with specified period and pulse,
57 call HAL_LPTIM_PWM_Start() or HAL_LPTIM_PWM_Start_IT() for interruption
60 (##) One Pulse Mode: To generate pulse with specified width in response
61 to a stimulus, call HAL_LPTIM_OnePulse_Start() or
62 HAL_LPTIM_OnePulse_Start_IT() for interruption mode.
64 (##) Set once Mode: In this mode, the output changes the level (from
65 low level to high level if the output polarity is configured high, else
66 the opposite) when a compare match occurs. To start this mode, call
67 HAL_LPTIM_SetOnce_Start() or HAL_LPTIM_SetOnce_Start_IT() for
70 (##) Encoder Mode: To use the encoder interface call
71 HAL_LPTIM_Encoder_Start() or HAL_LPTIM_Encoder_Start_IT() for
74 (##) Time out Mode: an active edge on one selected trigger input rests
75 the counter. The first trigger event will start the timer, any
76 successive trigger event will reset the counter and the timer will
77 restart. To start this mode call HAL_LPTIM_TimeOut_Start_IT() or
78 HAL_LPTIM_TimeOut_Start_IT() for interruption mode.
80 (##) Counter Mode: counter can be used to count external events on
81 the LPTIM Input1 or it can be used to count internal clock cycles.
82 To start this mode, call HAL_LPTIM_Counter_Start() or
83 HAL_LPTIM_Counter_Start_IT() for interruption mode.
85 (#) User can stop any process by calling the corresponding API:
86 HAL_LPTIM_Xxx_Stop() or HAL_LPTIM_Xxx_Stop_IT() if the process is
87 already started in interruption mode.
89 (#)Call HAL_LPTIM_DeInit() to deinitialize the LPTIM peripheral.
92 ******************************************************************************
95 * <h2><center>© COPYRIGHT(c) 2017 STMicroelectronics</center></h2>
97 * Redistribution and use in source and binary forms, with or without modification,
98 * are permitted provided that the following conditions are met:
99 * 1. Redistributions of source code must retain the above copyright notice,
100 * this list of conditions and the following disclaimer.
101 * 2. Redistributions in binary form must reproduce the above copyright notice,
102 * this list of conditions and the following disclaimer in the documentation
103 * and/or other materials provided with the distribution.
104 * 3. Neither the name of STMicroelectronics nor the names of its contributors
105 * may be used to endorse or promote products derived from this software
106 * without specific prior written permission.
108 * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
109 * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
110 * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE
111 * DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE
112 * FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL
113 * DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR
114 * SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
115 * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY,
116 * OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE
117 * OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
119 ******************************************************************************
122 /* Includes ------------------------------------------------------------------*/
123 #include "stm32f4xx_hal.h"
125 /** @addtogroup STM32F4xx_HAL_Driver
129 /** @defgroup LPTIM LPTIM
130 * @brief LPTIM HAL module driver.
134 #ifdef HAL_LPTIM_MODULE_ENABLED
135 #if defined(STM32F410Tx) || defined(STM32F410Cx) || defined(STM32F410Rx) || defined(STM32F413xx) || defined(STM32F423xx)
136 /* Private types -------------------------------------------------------------*/
137 /** @defgroup LPTIM_Private_Types LPTIM Private Types
145 /* Private defines -----------------------------------------------------------*/
146 /** @defgroup LPTIM_Private_Defines LPTIM Private Defines
154 /* Private variables ---------------------------------------------------------*/
155 /** @addtogroup LPTIM_Private_Variables LPTIM Private Variables
163 /* Private constants ---------------------------------------------------------*/
164 /** @addtogroup LPTIM_Private_Constants LPTIM Private Constants
172 /* Private macros ------------------------------------------------------------*/
173 /** @addtogroup LPTIM_Private_Macros LPTIM Private Macros
181 /* Private function prototypes -----------------------------------------------*/
182 /** @addtogroup LPTIM_Private_Functions_Prototypes LPTIM Private Functions Prototypes
190 /* Private functions ---------------------------------------------------------*/
191 /** @addtogroup LPTIM_Private_Functions LPTIM Private Functions
199 /* Exported functions ---------------------------------------------------------*/
200 /** @defgroup LPTIM_Exported_Functions LPTIM Exported Functions
204 /** @defgroup LPTIM_Group1 Initialization/de-initialization functions
205 * @brief Initialization and Configuration functions.
208 ==============================================================================
209 ##### Initialization and de-initialization functions #####
210 ==============================================================================
211 [..] This section provides functions allowing to:
212 (+) Initialize the LPTIM according to the specified parameters in the
213 LPTIM_InitTypeDef and creates the associated handle.
214 (+) DeInitialize the LPTIM peripheral.
215 (+) Initialize the LPTIM MSP.
216 (+) DeInitialize LPTIM MSP.
223 * @brief Initializes the LPTIM according to the specified parameters in the
224 * LPTIM_InitTypeDef and creates the associated handle.
225 * @param hlptim: LPTIM handle
228 HAL_StatusTypeDef
HAL_LPTIM_Init(LPTIM_HandleTypeDef
*hlptim
)
230 uint32_t tmpcfgr
= 0U;
232 /* Check the LPTIM handle allocation */
238 /* Check the parameters */
239 assert_param(IS_LPTIM_INSTANCE(hlptim
->Instance
));
241 assert_param(IS_LPTIM_CLOCK_SOURCE(hlptim
->Init
.Clock
.Source
));
242 assert_param(IS_LPTIM_CLOCK_PRESCALER(hlptim
->Init
.Clock
.Prescaler
));
243 if ((hlptim
->Init
.Clock
.Source
) == LPTIM_CLOCKSOURCE_ULPTIM
)
245 assert_param(IS_LPTIM_CLOCK_POLARITY(hlptim
->Init
.UltraLowPowerClock
.Polarity
));
246 assert_param(IS_LPTIM_CLOCK_SAMPLE_TIME(hlptim
->Init
.UltraLowPowerClock
.SampleTime
));
248 assert_param(IS_LPTIM_TRG_SOURCE(hlptim
->Init
.Trigger
.Source
));
249 if ((hlptim
->Init
.Trigger
.Source
) != LPTIM_TRIGSOURCE_SOFTWARE
)
251 assert_param(IS_LPTIM_TRIG_SAMPLE_TIME(hlptim
->Init
.Trigger
.SampleTime
));
252 assert_param(IS_LPTIM_EXT_TRG_POLARITY(hlptim
->Init
.Trigger
.ActiveEdge
));
254 assert_param(IS_LPTIM_OUTPUT_POLARITY(hlptim
->Init
.OutputPolarity
));
255 assert_param(IS_LPTIM_UPDATE_MODE(hlptim
->Init
.UpdateMode
));
256 assert_param(IS_LPTIM_COUNTER_SOURCE(hlptim
->Init
.CounterSource
));
258 if(hlptim
->State
== HAL_LPTIM_STATE_RESET
)
260 /* Allocate lock resource and initialize it */
261 hlptim
->Lock
= HAL_UNLOCKED
;
262 /* Init the low level hardware */
263 HAL_LPTIM_MspInit(hlptim
);
266 /* Change the LPTIM state */
267 hlptim
->State
= HAL_LPTIM_STATE_BUSY
;
269 /* Get the LPTIMx CFGR value */
270 tmpcfgr
= hlptim
->Instance
->CFGR
;
272 if ((hlptim
->Init
.Clock
.Source
) == LPTIM_CLOCKSOURCE_ULPTIM
)
274 tmpcfgr
&= (uint32_t)(~(LPTIM_CFGR_CKPOL
| LPTIM_CFGR_CKFLT
));
276 if ((hlptim
->Init
.Trigger
.Source
) != LPTIM_TRIGSOURCE_SOFTWARE
)
278 tmpcfgr
&= (uint32_t)(~ (LPTIM_CFGR_TRGFLT
| LPTIM_CFGR_TRIGSEL
));
281 /* Clear CKSEL, PRESC, TRIGEN, TRGFLT, WAVPOL, PRELOAD & COUNTMODE bits */
282 tmpcfgr
&= (uint32_t)(~(LPTIM_CFGR_CKSEL
| LPTIM_CFGR_TRIGEN
| LPTIM_CFGR_PRELOAD
|
283 LPTIM_CFGR_WAVPOL
| LPTIM_CFGR_PRESC
| LPTIM_CFGR_COUNTMODE
));
285 /* Set initialization parameters */
286 tmpcfgr
|= (hlptim
->Init
.Clock
.Source
|
287 hlptim
->Init
.Clock
.Prescaler
|
288 hlptim
->Init
.OutputPolarity
|
289 hlptim
->Init
.UpdateMode
|
290 hlptim
->Init
.CounterSource
);
292 if ((hlptim
->Init
.Clock
.Source
) == LPTIM_CLOCKSOURCE_ULPTIM
)
294 tmpcfgr
|= (hlptim
->Init
.UltraLowPowerClock
.Polarity
|
295 hlptim
->Init
.UltraLowPowerClock
.SampleTime
);
298 if ((hlptim
->Init
.Trigger
.Source
) != LPTIM_TRIGSOURCE_SOFTWARE
)
300 /* Enable External trigger and set the trigger source */
301 tmpcfgr
|= (hlptim
->Init
.Trigger
.Source
|
302 hlptim
->Init
.Trigger
.ActiveEdge
|
303 hlptim
->Init
.Trigger
.SampleTime
);
306 /* Write to LPTIMx CFGR */
307 hlptim
->Instance
->CFGR
= tmpcfgr
;
309 /* Change the LPTIM state */
310 hlptim
->State
= HAL_LPTIM_STATE_READY
;
312 /* Return function status */
317 * @brief DeInitializes the LPTIM peripheral.
318 * @param hlptim: LPTIM handle
321 HAL_StatusTypeDef
HAL_LPTIM_DeInit(LPTIM_HandleTypeDef
*hlptim
)
323 /* Check the LPTIM handle allocation */
329 /* Change the LPTIM state */
330 hlptim
->State
= HAL_LPTIM_STATE_BUSY
;
332 /* Disable the LPTIM Peripheral Clock */
333 __HAL_LPTIM_DISABLE(hlptim
);
335 /* DeInit the low level hardware: CLOCK, NVIC.*/
336 HAL_LPTIM_MspDeInit(hlptim
);
338 /* Change the LPTIM state */
339 hlptim
->State
= HAL_LPTIM_STATE_RESET
;
342 __HAL_UNLOCK(hlptim
);
344 /* Return function status */
349 * @brief Initializes the LPTIM MSP.
350 * @param hlptim: LPTIM handle
353 __weak
void HAL_LPTIM_MspInit(LPTIM_HandleTypeDef
*hlptim
)
355 /* Prevent unused argument(s) compilation warning */
357 /* NOTE : This function Should not be modified, when the callback is needed,
358 the HAL_LPTIM_MspInit could be implemented in the user file
363 * @brief DeInitializes LPTIM MSP.
364 * @param hlptim: LPTIM handle
367 __weak
void HAL_LPTIM_MspDeInit(LPTIM_HandleTypeDef
*hlptim
)
369 /* Prevent unused argument(s) compilation warning */
371 /* NOTE : This function Should not be modified, when the callback is needed,
372 the HAL_LPTIM_MspDeInit could be implemented in the user file
380 /** @defgroup LPTIM_Group2 LPTIM Start-Stop operation functions
381 * @brief Start-Stop operation functions.
384 ==============================================================================
385 ##### LPTIM Start Stop operation functions #####
386 ==============================================================================
387 [..] This section provides functions allowing to:
388 (+) Start the PWM mode.
389 (+) Stop the PWM mode.
390 (+) Start the One pulse mode.
391 (+) Stop the One pulse mode.
392 (+) Start the Set once mode.
393 (+) Stop the Set once mode.
394 (+) Start the Encoder mode.
395 (+) Stop the Encoder mode.
396 (+) Start the Timeout mode.
397 (+) Stop the Timeout mode.
398 (+) Start the Counter mode.
399 (+) Stop the Counter mode.
407 * @brief Starts the LPTIM PWM generation.
408 * @param hlptim : LPTIM handle
409 * @param Period : Specifies the Autoreload value.
410 * This parameter must be a value between 0x0000 and 0xFFFF.
411 * @param Pulse : Specifies the compare value.
412 * This parameter must be a value between 0x0000 and 0xFFFF.
415 HAL_StatusTypeDef
HAL_LPTIM_PWM_Start(LPTIM_HandleTypeDef
*hlptim
, uint32_t Period
, uint32_t Pulse
)
417 /* Check the parameters */
418 assert_param(IS_LPTIM_INSTANCE(hlptim
->Instance
));
419 assert_param(IS_LPTIM_PERIOD(Period
));
420 assert_param(IS_LPTIM_PULSE(Pulse
));
422 /* Set the LPTIM state */
423 hlptim
->State
= HAL_LPTIM_STATE_BUSY
;
425 /* Reset WAVE bit to set PWM mode */
426 hlptim
->Instance
->CFGR
&= ~LPTIM_CFGR_WAVE
;
428 /* Enable the Peripheral */
429 __HAL_LPTIM_ENABLE(hlptim
);
431 /* Load the period value in the autoreload register */
432 __HAL_LPTIM_AUTORELOAD_SET(hlptim
, Period
);
434 /* Load the pulse value in the compare register */
435 __HAL_LPTIM_COMPARE_SET(hlptim
, Pulse
);
437 /* Start timer in continuous mode */
438 __HAL_LPTIM_START_CONTINUOUS(hlptim
);
440 /* Change the TIM state*/
441 hlptim
->State
= HAL_LPTIM_STATE_READY
;
443 /* Return function status */
448 * @brief Stops the LPTIM PWM generation.
449 * @param hlptim : LPTIM handle
452 HAL_StatusTypeDef
HAL_LPTIM_PWM_Stop(LPTIM_HandleTypeDef
*hlptim
)
454 /* Check the parameters */
455 assert_param(IS_LPTIM_INSTANCE(hlptim
->Instance
));
457 /* Set the LPTIM state */
458 hlptim
->State
= HAL_LPTIM_STATE_BUSY
;
460 /* Disable the Peripheral */
461 __HAL_LPTIM_DISABLE(hlptim
);
463 /* Change the TIM state*/
464 hlptim
->State
= HAL_LPTIM_STATE_READY
;
466 /* Return function status */
471 * @brief Starts the LPTIM PWM generation in interrupt mode.
472 * @param hlptim : LPTIM handle
473 * @param Period : Specifies the Autoreload value.
474 * This parameter must be a value between 0x0000 and 0xFFFF
475 * @param Pulse : Specifies the compare value.
476 * This parameter must be a value between 0x0000 and 0xFFFF
479 HAL_StatusTypeDef
HAL_LPTIM_PWM_Start_IT(LPTIM_HandleTypeDef
*hlptim
, uint32_t Period
, uint32_t Pulse
)
481 /* Check the parameters */
482 assert_param(IS_LPTIM_INSTANCE(hlptim
->Instance
));
483 assert_param(IS_LPTIM_PERIOD(Period
));
484 assert_param(IS_LPTIM_PULSE(Pulse
));
486 /* Set the LPTIM state */
487 hlptim
->State
= HAL_LPTIM_STATE_BUSY
;
489 /* Reset WAVE bit to set PWM mode */
490 hlptim
->Instance
->CFGR
&= ~LPTIM_CFGR_WAVE
;
492 /* Enable Autoreload write complete interrupt */
493 __HAL_LPTIM_ENABLE_IT(hlptim
, LPTIM_IT_ARROK
);
495 /* Enable Compare write complete interrupt */
496 __HAL_LPTIM_ENABLE_IT(hlptim
, LPTIM_IT_CMPOK
);
498 /* Enable Autoreload match interrupt */
499 __HAL_LPTIM_ENABLE_IT(hlptim
, LPTIM_IT_ARRM
);
501 /* Enable Compare match interrupt */
502 __HAL_LPTIM_ENABLE_IT(hlptim
, LPTIM_IT_CMPM
);
504 /* If external trigger source is used, then enable external trigger interrupt */
505 if ((hlptim
->Init
.Trigger
.Source
) != LPTIM_TRIGSOURCE_SOFTWARE
)
507 /* Enable external trigger interrupt */
508 __HAL_LPTIM_ENABLE_IT(hlptim
, LPTIM_IT_EXTTRIG
);
511 /* Enable the Peripheral */
512 __HAL_LPTIM_ENABLE(hlptim
);
514 /* Load the period value in the autoreload register */
515 __HAL_LPTIM_AUTORELOAD_SET(hlptim
, Period
);
517 /* Load the pulse value in the compare register */
518 __HAL_LPTIM_COMPARE_SET(hlptim
, Pulse
);
520 /* Start timer in continuous mode */
521 __HAL_LPTIM_START_CONTINUOUS(hlptim
);
523 /* Change the TIM state*/
524 hlptim
->State
= HAL_LPTIM_STATE_READY
;
526 /* Return function status */
531 * @brief Stops the LPTIM PWM generation in interrupt mode.
532 * @param hlptim : LPTIM handle
535 HAL_StatusTypeDef
HAL_LPTIM_PWM_Stop_IT(LPTIM_HandleTypeDef
*hlptim
)
537 /* Check the parameters */
538 assert_param(IS_LPTIM_INSTANCE(hlptim
->Instance
));
540 /* Set the LPTIM state */
541 hlptim
->State
= HAL_LPTIM_STATE_BUSY
;
543 /* Disable the Peripheral */
544 __HAL_LPTIM_DISABLE(hlptim
);
546 /* Disable Autoreload write complete interrupt */
547 __HAL_LPTIM_DISABLE_IT(hlptim
, LPTIM_IT_ARROK
);
549 /* Disable Compare write complete interrupt */
550 __HAL_LPTIM_DISABLE_IT(hlptim
, LPTIM_IT_CMPOK
);
552 /* Disable Autoreload match interrupt */
553 __HAL_LPTIM_DISABLE_IT(hlptim
, LPTIM_IT_ARRM
);
555 /* Disable Compare match interrupt */
556 __HAL_LPTIM_DISABLE_IT(hlptim
, LPTIM_IT_CMPM
);
558 /* If external trigger source is used, then disable external trigger interrupt */
559 if ((hlptim
->Init
.Trigger
.Source
) != LPTIM_TRIGSOURCE_SOFTWARE
)
561 /* Disable external trigger interrupt */
562 __HAL_LPTIM_DISABLE_IT(hlptim
, LPTIM_IT_EXTTRIG
);
565 /* Change the TIM state*/
566 hlptim
->State
= HAL_LPTIM_STATE_READY
;
568 /* Return function status */
573 * @brief Starts the LPTIM One pulse generation.
574 * @param hlptim : LPTIM handle
575 * @param Period : Specifies the Autoreload value.
576 * This parameter must be a value between 0x0000 and 0xFFFF.
577 * @param Pulse : Specifies the compare value.
578 * This parameter must be a value between 0x0000 and 0xFFFF.
581 HAL_StatusTypeDef
HAL_LPTIM_OnePulse_Start(LPTIM_HandleTypeDef
*hlptim
, uint32_t Period
, uint32_t Pulse
)
583 /* Check the parameters */
584 assert_param(IS_LPTIM_INSTANCE(hlptim
->Instance
));
585 assert_param(IS_LPTIM_PERIOD(Period
));
586 assert_param(IS_LPTIM_PULSE(Pulse
));
588 /* Set the LPTIM state */
589 hlptim
->State
= HAL_LPTIM_STATE_BUSY
;
591 /* Reset WAVE bit to set one pulse mode */
592 hlptim
->Instance
->CFGR
&= ~LPTIM_CFGR_WAVE
;
594 /* Enable the Peripheral */
595 __HAL_LPTIM_ENABLE(hlptim
);
597 /* Load the period value in the autoreload register */
598 __HAL_LPTIM_AUTORELOAD_SET(hlptim
, Period
);
600 /* Load the pulse value in the compare register */
601 __HAL_LPTIM_COMPARE_SET(hlptim
, Pulse
);
603 /* Start timer in continuous mode */
604 __HAL_LPTIM_START_SINGLE(hlptim
);
606 /* Change the TIM state*/
607 hlptim
->State
= HAL_LPTIM_STATE_READY
;
609 /* Return function status */
614 * @brief Stops the LPTIM One pulse generation.
615 * @param hlptim : LPTIM handle
618 HAL_StatusTypeDef
HAL_LPTIM_OnePulse_Stop(LPTIM_HandleTypeDef
*hlptim
)
620 /* Check the parameters */
621 assert_param(IS_LPTIM_INSTANCE(hlptim
->Instance
));
623 /* Set the LPTIM state */
624 hlptim
->State
= HAL_LPTIM_STATE_BUSY
;
626 /* Disable the Peripheral */
627 __HAL_LPTIM_DISABLE(hlptim
);
629 /* Change the TIM state*/
630 hlptim
->State
= HAL_LPTIM_STATE_READY
;
632 /* Return function status */
637 * @brief Starts the LPTIM One pulse generation in interrupt mode.
638 * @param hlptim : LPTIM handle
639 * @param Period : Specifies the Autoreload value.
640 * This parameter must be a value between 0x0000 and 0xFFFF.
641 * @param Pulse : Specifies the compare value.
642 * This parameter must be a value between 0x0000 and 0xFFFF.
645 HAL_StatusTypeDef
HAL_LPTIM_OnePulse_Start_IT(LPTIM_HandleTypeDef
*hlptim
, uint32_t Period
, uint32_t Pulse
)
647 /* Check the parameters */
648 assert_param(IS_LPTIM_INSTANCE(hlptim
->Instance
));
649 assert_param(IS_LPTIM_PERIOD(Period
));
650 assert_param(IS_LPTIM_PULSE(Pulse
));
652 /* Set the LPTIM state */
653 hlptim
->State
= HAL_LPTIM_STATE_BUSY
;
655 /* Reset WAVE bit to set one pulse mode */
656 hlptim
->Instance
->CFGR
&= ~LPTIM_CFGR_WAVE
;
658 /* Enable Autoreload write complete interrupt */
659 __HAL_LPTIM_ENABLE_IT(hlptim
, LPTIM_IT_ARROK
);
661 /* Enable Compare write complete interrupt */
662 __HAL_LPTIM_ENABLE_IT(hlptim
, LPTIM_IT_CMPOK
);
664 /* Enable Autoreload match interrupt */
665 __HAL_LPTIM_ENABLE_IT(hlptim
, LPTIM_IT_ARRM
);
667 /* Enable Compare match interrupt */
668 __HAL_LPTIM_ENABLE_IT(hlptim
, LPTIM_IT_CMPM
);
670 /* If external trigger source is used, then enable external trigger interrupt */
671 if ((hlptim
->Init
.Trigger
.Source
) != LPTIM_TRIGSOURCE_SOFTWARE
)
673 /* Enable external trigger interrupt */
674 __HAL_LPTIM_ENABLE_IT(hlptim
, LPTIM_IT_EXTTRIG
);
677 /* Enable the Peripheral */
678 __HAL_LPTIM_ENABLE(hlptim
);
680 /* Load the period value in the autoreload register */
681 __HAL_LPTIM_AUTORELOAD_SET(hlptim
, Period
);
683 /* Load the pulse value in the compare register */
684 __HAL_LPTIM_COMPARE_SET(hlptim
, Pulse
);
686 /* Start timer in continuous mode */
687 __HAL_LPTIM_START_SINGLE(hlptim
);
689 /* Change the TIM state*/
690 hlptim
->State
= HAL_LPTIM_STATE_READY
;
692 /* Return function status */
697 * @brief Stops the LPTIM One pulse generation in interrupt mode.
698 * @param hlptim : LPTIM handle
701 HAL_StatusTypeDef
HAL_LPTIM_OnePulse_Stop_IT(LPTIM_HandleTypeDef
*hlptim
)
703 /* Check the parameters */
704 assert_param(IS_LPTIM_INSTANCE(hlptim
->Instance
));
706 /* Set the LPTIM state */
707 hlptim
->State
= HAL_LPTIM_STATE_BUSY
;
709 /* Disable the Peripheral */
710 __HAL_LPTIM_DISABLE(hlptim
);
712 /* Disable Autoreload write complete interrupt */
713 __HAL_LPTIM_DISABLE_IT(hlptim
, LPTIM_IT_ARROK
);
715 /* Disable Compare write complete interrupt */
716 __HAL_LPTIM_DISABLE_IT(hlptim
, LPTIM_IT_CMPOK
);
718 /* Disable Autoreload match interrupt */
719 __HAL_LPTIM_DISABLE_IT(hlptim
, LPTIM_IT_ARRM
);
721 /* Disable Compare match interrupt */
722 __HAL_LPTIM_DISABLE_IT(hlptim
, LPTIM_IT_CMPM
);
724 /* If external trigger source is used, then disable external trigger interrupt */
725 if ((hlptim
->Init
.Trigger
.Source
) != LPTIM_TRIGSOURCE_SOFTWARE
)
727 /* Disable external trigger interrupt */
728 __HAL_LPTIM_DISABLE_IT(hlptim
, LPTIM_IT_EXTTRIG
);
731 /* Change the TIM state*/
732 hlptim
->State
= HAL_LPTIM_STATE_READY
;
734 /* Return function status */
739 * @brief Starts the LPTIM in Set once mode.
740 * @param hlptim : LPTIM handle
741 * @param Period : Specifies the Autoreload value.
742 * This parameter must be a value between 0x0000 and 0xFFFF.
743 * @param Pulse : Specifies the compare value.
744 * This parameter must be a value between 0x0000 and 0xFFFF.
747 HAL_StatusTypeDef
HAL_LPTIM_SetOnce_Start(LPTIM_HandleTypeDef
*hlptim
, uint32_t Period
, uint32_t Pulse
)
749 /* Check the parameters */
750 assert_param(IS_LPTIM_INSTANCE(hlptim
->Instance
));
751 assert_param(IS_LPTIM_PERIOD(Period
));
752 assert_param(IS_LPTIM_PULSE(Pulse
));
754 /* Set the LPTIM state */
755 hlptim
->State
= HAL_LPTIM_STATE_BUSY
;
757 /* Set WAVE bit to enable the set once mode */
758 hlptim
->Instance
->CFGR
|= LPTIM_CFGR_WAVE
;
760 /* Enable the Peripheral */
761 __HAL_LPTIM_ENABLE(hlptim
);
763 /* Load the period value in the autoreload register */
764 __HAL_LPTIM_AUTORELOAD_SET(hlptim
, Period
);
766 /* Load the pulse value in the compare register */
767 __HAL_LPTIM_COMPARE_SET(hlptim
, Pulse
);
769 /* Start timer in single mode */
770 __HAL_LPTIM_START_SINGLE(hlptim
);
772 /* Change the TIM state*/
773 hlptim
->State
= HAL_LPTIM_STATE_READY
;
775 /* Return function status */
780 * @brief Stops the LPTIM Set once mode.
781 * @param hlptim : LPTIM handle
784 HAL_StatusTypeDef
HAL_LPTIM_SetOnce_Stop(LPTIM_HandleTypeDef
*hlptim
)
786 /* Check the parameters */
787 assert_param(IS_LPTIM_INSTANCE(hlptim
->Instance
));
789 /* Set the LPTIM state */
790 hlptim
->State
= HAL_LPTIM_STATE_BUSY
;
792 /* Disable the Peripheral */
793 __HAL_LPTIM_DISABLE(hlptim
);
795 /* Change the TIM state*/
796 hlptim
->State
= HAL_LPTIM_STATE_READY
;
798 /* Return function status */
803 * @brief Starts the LPTIM Set once mode in interrupt mode.
804 * @param hlptim : LPTIM handle
805 * @param Period : Specifies the Autoreload value.
806 * This parameter must be a value between 0x0000 and 0xFFFF.
807 * @param Pulse : Specifies the compare value.
808 * This parameter must be a value between 0x0000 and 0xFFFF.
811 HAL_StatusTypeDef
HAL_LPTIM_SetOnce_Start_IT(LPTIM_HandleTypeDef
*hlptim
, uint32_t Period
, uint32_t Pulse
)
813 /* Check the parameters */
814 assert_param(IS_LPTIM_INSTANCE(hlptim
->Instance
));
815 assert_param(IS_LPTIM_PERIOD(Period
));
816 assert_param(IS_LPTIM_PULSE(Pulse
));
818 /* Set the LPTIM state */
819 hlptim
->State
= HAL_LPTIM_STATE_BUSY
;
821 /* Set WAVE bit to enable the set once mode */
822 hlptim
->Instance
->CFGR
|= LPTIM_CFGR_WAVE
;
824 /* Enable Autoreload write complete interrupt */
825 __HAL_LPTIM_ENABLE_IT(hlptim
, LPTIM_IT_ARROK
);
827 /* Enable Compare write complete interrupt */
828 __HAL_LPTIM_ENABLE_IT(hlptim
, LPTIM_IT_CMPOK
);
830 /* Enable Autoreload match interrupt */
831 __HAL_LPTIM_ENABLE_IT(hlptim
, LPTIM_IT_ARRM
);
833 /* Enable Compare match interrupt */
834 __HAL_LPTIM_ENABLE_IT(hlptim
, LPTIM_IT_CMPM
);
836 /* If external trigger source is used, then enable external trigger interrupt */
837 if ((hlptim
->Init
.Trigger
.Source
) != LPTIM_TRIGSOURCE_SOFTWARE
)
839 /* Enable external trigger interrupt */
840 __HAL_LPTIM_ENABLE_IT(hlptim
, LPTIM_IT_EXTTRIG
);
843 /* Enable the Peripheral */
844 __HAL_LPTIM_ENABLE(hlptim
);
846 /* Load the period value in the autoreload register */
847 __HAL_LPTIM_AUTORELOAD_SET(hlptim
, Period
);
849 /* Load the pulse value in the compare register */
850 __HAL_LPTIM_COMPARE_SET(hlptim
, Pulse
);
852 /* Start timer in single mode */
853 __HAL_LPTIM_START_SINGLE(hlptim
);
855 /* Change the TIM state*/
856 hlptim
->State
= HAL_LPTIM_STATE_READY
;
858 /* Return function status */
863 * @brief Stops the LPTIM Set once mode in interrupt mode.
864 * @param hlptim : LPTIM handle
867 HAL_StatusTypeDef
HAL_LPTIM_SetOnce_Stop_IT(LPTIM_HandleTypeDef
*hlptim
)
869 /* Check the parameters */
870 assert_param(IS_LPTIM_INSTANCE(hlptim
->Instance
));
872 /* Set the LPTIM state */
873 hlptim
->State
= HAL_LPTIM_STATE_BUSY
;
875 /* Disable the Peripheral */
876 __HAL_LPTIM_DISABLE(hlptim
);
878 /* Disable Autoreload write complete interrupt */
879 __HAL_LPTIM_DISABLE_IT(hlptim
, LPTIM_IT_ARROK
);
881 /* Disable Compare write complete interrupt */
882 __HAL_LPTIM_DISABLE_IT(hlptim
, LPTIM_IT_CMPOK
);
884 /* Disable Autoreload match interrupt */
885 __HAL_LPTIM_DISABLE_IT(hlptim
, LPTIM_IT_ARRM
);
887 /* Disable Compare match interrupt */
888 __HAL_LPTIM_DISABLE_IT(hlptim
, LPTIM_IT_CMPM
);
890 /* If external trigger source is used, then disable external trigger interrupt */
891 if ((hlptim
->Init
.Trigger
.Source
) != LPTIM_TRIGSOURCE_SOFTWARE
)
893 /* Disable external trigger interrupt */
894 __HAL_LPTIM_DISABLE_IT(hlptim
, LPTIM_IT_EXTTRIG
);
897 /* Change the TIM state*/
898 hlptim
->State
= HAL_LPTIM_STATE_READY
;
900 /* Return function status */
905 * @brief Starts the Encoder interface.
906 * @param hlptim : LPTIM handle
907 * @param Period : Specifies the Autoreload value.
908 * This parameter must be a value between 0x0000 and 0xFFFF.
911 HAL_StatusTypeDef
HAL_LPTIM_Encoder_Start(LPTIM_HandleTypeDef
*hlptim
, uint32_t Period
)
913 uint32_t tmpcfgr
= 0U;
915 /* Check the parameters */
916 assert_param(IS_LPTIM_INSTANCE(hlptim
->Instance
));
917 assert_param(IS_LPTIM_PERIOD(Period
));
918 assert_param(hlptim
->Init
.Clock
.Source
== LPTIM_CLOCKSOURCE_APBCLOCK_LPOSC
);
919 assert_param(hlptim
->Init
.Clock
.Prescaler
== LPTIM_PRESCALER_DIV1
);
920 assert_param(IS_LPTIM_CLOCK_POLARITY(hlptim
->Init
.UltraLowPowerClock
.Polarity
));
922 /* Set the LPTIM state */
923 hlptim
->State
= HAL_LPTIM_STATE_BUSY
;
925 /* Get the LPTIMx CFGR value */
926 tmpcfgr
= hlptim
->Instance
->CFGR
;
928 /* Clear CKPOL bits */
929 tmpcfgr
&= (uint32_t)(~LPTIM_CFGR_CKPOL
);
931 /* Set Input polarity */
932 tmpcfgr
|= hlptim
->Init
.UltraLowPowerClock
.Polarity
;
934 /* Write to LPTIMx CFGR */
935 hlptim
->Instance
->CFGR
= tmpcfgr
;
937 /* Set ENC bit to enable the encoder interface */
938 hlptim
->Instance
->CFGR
|= LPTIM_CFGR_ENC
;
940 /* Enable the Peripheral */
941 __HAL_LPTIM_ENABLE(hlptim
);
943 /* Load the period value in the autoreload register */
944 __HAL_LPTIM_AUTORELOAD_SET(hlptim
, Period
);
946 /* Start timer in continuous mode */
947 __HAL_LPTIM_START_CONTINUOUS(hlptim
);
949 /* Change the TIM state*/
950 hlptim
->State
= HAL_LPTIM_STATE_READY
;
952 /* Return function status */
957 * @brief Stops the Encoder interface.
958 * @param hlptim : LPTIM handle
961 HAL_StatusTypeDef
HAL_LPTIM_Encoder_Stop(LPTIM_HandleTypeDef
*hlptim
)
963 /* Check the parameters */
964 assert_param(IS_LPTIM_INSTANCE(hlptim
->Instance
));
966 /* Set the LPTIM state */
967 hlptim
->State
= HAL_LPTIM_STATE_BUSY
;
969 /* Disable the Peripheral */
970 __HAL_LPTIM_DISABLE(hlptim
);
972 /* Reset ENC bit to disable the encoder interface */
973 hlptim
->Instance
->CFGR
&= ~LPTIM_CFGR_ENC
;
975 /* Change the TIM state*/
976 hlptim
->State
= HAL_LPTIM_STATE_READY
;
978 /* Return function status */
983 * @brief Starts the Encoder interface in interrupt mode.
984 * @param hlptim : LPTIM handle
985 * @param Period : Specifies the Autoreload value.
986 * This parameter must be a value between 0x0000 and 0xFFFF.
989 HAL_StatusTypeDef
HAL_LPTIM_Encoder_Start_IT(LPTIM_HandleTypeDef
*hlptim
, uint32_t Period
)
991 uint32_t tmpcfgr
= 0U;
993 /* Check the parameters */
994 assert_param(IS_LPTIM_INSTANCE(hlptim
->Instance
));
995 assert_param(IS_LPTIM_PERIOD(Period
));
996 assert_param(hlptim
->Init
.Clock
.Source
== LPTIM_CLOCKSOURCE_APBCLOCK_LPOSC
);
997 assert_param(hlptim
->Init
.Clock
.Prescaler
== LPTIM_PRESCALER_DIV1
);
998 assert_param(IS_LPTIM_CLOCK_POLARITY(hlptim
->Init
.UltraLowPowerClock
.Polarity
));
1000 /* Set the LPTIM state */
1001 hlptim
->State
= HAL_LPTIM_STATE_BUSY
;
1003 /* Configure edge sensitivity for encoder mode */
1004 /* Get the LPTIMx CFGR value */
1005 tmpcfgr
= hlptim
->Instance
->CFGR
;
1007 /* Clear CKPOL bits */
1008 tmpcfgr
&= (uint32_t)(~LPTIM_CFGR_CKPOL
);
1010 /* Set Input polarity */
1011 tmpcfgr
|= hlptim
->Init
.UltraLowPowerClock
.Polarity
;
1013 /* Write to LPTIMx CFGR */
1014 hlptim
->Instance
->CFGR
= tmpcfgr
;
1016 /* Set ENC bit to enable the encoder interface */
1017 hlptim
->Instance
->CFGR
|= LPTIM_CFGR_ENC
;
1019 /* Enable "switch to down direction" interrupt */
1020 __HAL_LPTIM_ENABLE_IT(hlptim
, LPTIM_IT_DOWN
);
1022 /* Enable "switch to up direction" interrupt */
1023 __HAL_LPTIM_ENABLE_IT(hlptim
, LPTIM_IT_UP
);
1025 /* Enable the Peripheral */
1026 __HAL_LPTIM_ENABLE(hlptim
);
1028 /* Load the period value in the autoreload register */
1029 __HAL_LPTIM_AUTORELOAD_SET(hlptim
, Period
);
1031 /* Start timer in continuous mode */
1032 __HAL_LPTIM_START_CONTINUOUS(hlptim
);
1034 /* Change the TIM state*/
1035 hlptim
->State
= HAL_LPTIM_STATE_READY
;
1037 /* Return function status */
1042 * @brief Stops the Encoder interface in interrupt mode.
1043 * @param hlptim : LPTIM handle
1044 * @retval HAL status
1046 HAL_StatusTypeDef
HAL_LPTIM_Encoder_Stop_IT(LPTIM_HandleTypeDef
*hlptim
)
1048 /* Check the parameters */
1049 assert_param(IS_LPTIM_INSTANCE(hlptim
->Instance
));
1051 /* Set the LPTIM state */
1052 hlptim
->State
= HAL_LPTIM_STATE_BUSY
;
1054 /* Disable the Peripheral */
1055 __HAL_LPTIM_DISABLE(hlptim
);
1057 /* Reset ENC bit to disable the encoder interface */
1058 hlptim
->Instance
->CFGR
&= ~LPTIM_CFGR_ENC
;
1060 /* Disable "switch to down direction" interrupt */
1061 __HAL_LPTIM_DISABLE_IT(hlptim
, LPTIM_IT_DOWN
);
1063 /* Disable "switch to up direction" interrupt */
1064 __HAL_LPTIM_DISABLE_IT(hlptim
, LPTIM_IT_UP
);
1066 /* Change the TIM state*/
1067 hlptim
->State
= HAL_LPTIM_STATE_READY
;
1069 /* Return function status */
1074 * @brief Starts the Timeout function. The first trigger event will start the
1075 * timer, any successive trigger event will reset the counter and
1076 * the timer restarts.
1077 * @param hlptim : LPTIM handle
1078 * @param Period : Specifies the Autoreload value.
1079 * This parameter must be a value between 0x0000 and 0xFFFF.
1080 * @param Timeout : Specifies the TimeOut value to rest the counter.
1081 * This parameter must be a value between 0x0000 and 0xFFFF.
1082 * @retval HAL status
1084 HAL_StatusTypeDef
HAL_LPTIM_TimeOut_Start(LPTIM_HandleTypeDef
*hlptim
, uint32_t Period
, uint32_t Timeout
)
1086 /* Check the parameters */
1087 assert_param(IS_LPTIM_INSTANCE(hlptim
->Instance
));
1088 assert_param(IS_LPTIM_PERIOD(Period
));
1089 assert_param(IS_LPTIM_PULSE(Timeout
));
1091 /* Set the LPTIM state */
1092 hlptim
->State
= HAL_LPTIM_STATE_BUSY
;
1094 /* Set TIMOUT bit to enable the timeout function */
1095 hlptim
->Instance
->CFGR
|= LPTIM_CFGR_TIMOUT
;
1097 /* Enable the Peripheral */
1098 __HAL_LPTIM_ENABLE(hlptim
);
1100 /* Load the period value in the autoreload register */
1101 __HAL_LPTIM_AUTORELOAD_SET(hlptim
, Period
);
1103 /* Load the Timeout value in the compare register */
1104 __HAL_LPTIM_COMPARE_SET(hlptim
, Timeout
);
1106 /* Start timer in continuous mode */
1107 __HAL_LPTIM_START_CONTINUOUS(hlptim
);
1109 /* Change the TIM state*/
1110 hlptim
->State
= HAL_LPTIM_STATE_READY
;
1112 /* Return function status */
1117 * @brief Stops the Timeout function.
1118 * @param hlptim : LPTIM handle
1119 * @retval HAL status
1121 HAL_StatusTypeDef
HAL_LPTIM_TimeOut_Stop(LPTIM_HandleTypeDef
*hlptim
)
1123 /* Check the parameters */
1124 assert_param(IS_LPTIM_INSTANCE(hlptim
->Instance
));
1126 /* Set the LPTIM state */
1127 hlptim
->State
= HAL_LPTIM_STATE_BUSY
;
1129 /* Disable the Peripheral */
1130 __HAL_LPTIM_DISABLE(hlptim
);
1132 /* Reset TIMOUT bit to enable the timeout function */
1133 hlptim
->Instance
->CFGR
&= ~LPTIM_CFGR_TIMOUT
;
1135 /* Change the TIM state*/
1136 hlptim
->State
= HAL_LPTIM_STATE_READY
;
1138 /* Return function status */
1143 * @brief Starts the Timeout function in interrupt mode. The first trigger
1144 * event will start the timer, any successive trigger event will reset
1145 * the counter and the timer restarts.
1146 * @param hlptim : LPTIM handle
1147 * @param Period : Specifies the Autoreload value.
1148 * This parameter must be a value between 0x0000 and 0xFFFF.
1149 * @param Timeout : Specifies the TimeOut value to rest the counter.
1150 * This parameter must be a value between 0x0000 and 0xFFFF.
1151 * @retval HAL status
1153 HAL_StatusTypeDef
HAL_LPTIM_TimeOut_Start_IT(LPTIM_HandleTypeDef
*hlptim
, uint32_t Period
, uint32_t Timeout
)
1155 /* Check the parameters */
1156 assert_param(IS_LPTIM_INSTANCE(hlptim
->Instance
));
1157 assert_param(IS_LPTIM_PERIOD(Period
));
1158 assert_param(IS_LPTIM_PULSE(Timeout
));
1160 /* Set the LPTIM state */
1161 hlptim
->State
= HAL_LPTIM_STATE_BUSY
;
1163 /* Enable EXTI Line interrupt on the LPTIM Wake-up Timer */
1164 __HAL_LPTIM_WAKEUPTIMER_EXTI_ENABLE_IT();
1166 /* Enable rising edge trigger on the LPTIM Wake-up Timer Exti line */
1167 __HAL_LPTIM_WAKEUPTIMER_EXTI_ENABLE_RISING_EDGE();
1169 /* Set TIMOUT bit to enable the timeout function */
1170 hlptim
->Instance
->CFGR
|= LPTIM_CFGR_TIMOUT
;
1172 /* Enable Compare match interrupt */
1173 __HAL_LPTIM_ENABLE_IT(hlptim
, LPTIM_IT_CMPM
);
1175 /* Enable the Peripheral */
1176 __HAL_LPTIM_ENABLE(hlptim
);
1178 /* Load the period value in the autoreload register */
1179 __HAL_LPTIM_AUTORELOAD_SET(hlptim
, Period
);
1181 /* Load the Timeout value in the compare register */
1182 __HAL_LPTIM_COMPARE_SET(hlptim
, Timeout
);
1184 /* Start timer in continuous mode */
1185 __HAL_LPTIM_START_CONTINUOUS(hlptim
);
1187 /* Change the TIM state*/
1188 hlptim
->State
= HAL_LPTIM_STATE_READY
;
1190 /* Return function status */
1195 * @brief Stops the Timeout function in interrupt mode.
1196 * @param hlptim : LPTIM handle
1197 * @retval HAL status
1199 HAL_StatusTypeDef
HAL_LPTIM_TimeOut_Stop_IT(LPTIM_HandleTypeDef
*hlptim
)
1201 /* Check the parameters */
1202 assert_param(IS_LPTIM_INSTANCE(hlptim
->Instance
));
1204 /* Set the LPTIM state */
1205 hlptim
->State
= HAL_LPTIM_STATE_BUSY
;
1207 /* Disable rising edge trigger on the LPTIM Wake-up Timer Exti line */
1208 __HAL_LPTIM_WAKEUPTIMER_EXTI_DISABLE_RISING_EDGE();
1210 /* Disable EXTI Line interrupt on the LPTIM Wake-up Timer */
1211 __HAL_LPTIM_WAKEUPTIMER_EXTI_DISABLE_IT();
1213 /* Disable the Peripheral */
1214 __HAL_LPTIM_DISABLE(hlptim
);
1216 /* Reset TIMOUT bit to enable the timeout function */
1217 hlptim
->Instance
->CFGR
&= ~LPTIM_CFGR_TIMOUT
;
1219 /* Disable Compare match interrupt */
1220 __HAL_LPTIM_DISABLE_IT(hlptim
, LPTIM_IT_CMPM
);
1222 /* Change the TIM state*/
1223 hlptim
->State
= HAL_LPTIM_STATE_READY
;
1225 /* Return function status */
1230 * @brief Starts the Counter mode.
1231 * @param hlptim : LPTIM handle
1232 * @param Period : Specifies the Autoreload value.
1233 * This parameter must be a value between 0x0000 and 0xFFFF.
1234 * @retval HAL status
1236 HAL_StatusTypeDef
HAL_LPTIM_Counter_Start(LPTIM_HandleTypeDef
*hlptim
, uint32_t Period
)
1238 /* Check the parameters */
1239 assert_param(IS_LPTIM_INSTANCE(hlptim
->Instance
));
1240 assert_param(IS_LPTIM_PERIOD(Period
));
1242 /* Set the LPTIM state */
1243 hlptim
->State
= HAL_LPTIM_STATE_BUSY
;
1245 /* If clock source is not ULPTIM clock and counter source is external, then it must not be prescaled */
1246 if((hlptim
->Init
.Clock
.Source
!= LPTIM_CLOCKSOURCE_ULPTIM
) && (hlptim
->Init
.CounterSource
== LPTIM_COUNTERSOURCE_EXTERNAL
))
1248 /* Check if clock is prescaled */
1249 assert_param(IS_LPTIM_CLOCK_PRESCALERDIV1(hlptim
->Init
.Clock
.Prescaler
));
1250 /* Set clock prescaler to 0 */
1251 hlptim
->Instance
->CFGR
&= ~LPTIM_CFGR_PRESC
;
1254 /* Enable the Peripheral */
1255 __HAL_LPTIM_ENABLE(hlptim
);
1257 /* Load the period value in the autoreload register */
1258 __HAL_LPTIM_AUTORELOAD_SET(hlptim
, Period
);
1260 /* Start timer in continuous mode */
1261 __HAL_LPTIM_START_CONTINUOUS(hlptim
);
1263 /* Change the TIM state*/
1264 hlptim
->State
= HAL_LPTIM_STATE_READY
;
1266 /* Return function status */
1271 * @brief Stops the Counter mode.
1272 * @param hlptim : LPTIM handle
1273 * @retval HAL status
1275 HAL_StatusTypeDef
HAL_LPTIM_Counter_Stop(LPTIM_HandleTypeDef
*hlptim
)
1277 /* Check the parameters */
1278 assert_param(IS_LPTIM_INSTANCE(hlptim
->Instance
));
1280 /* Set the LPTIM state */
1281 hlptim
->State
= HAL_LPTIM_STATE_BUSY
;
1283 /* Disable the Peripheral */
1284 __HAL_LPTIM_DISABLE(hlptim
);
1286 /* Change the TIM state*/
1287 hlptim
->State
= HAL_LPTIM_STATE_READY
;
1289 /* Return function status */
1294 * @brief Starts the Counter mode in interrupt mode.
1295 * @param hlptim : LPTIM handle
1296 * @param Period : Specifies the Autoreload value.
1297 * This parameter must be a value between 0x0000 and 0xFFFF.
1298 * @retval HAL status
1300 HAL_StatusTypeDef
HAL_LPTIM_Counter_Start_IT(LPTIM_HandleTypeDef
*hlptim
, uint32_t Period
)
1302 /* Check the parameters */
1303 assert_param(IS_LPTIM_INSTANCE(hlptim
->Instance
));
1304 assert_param(IS_LPTIM_PERIOD(Period
));
1306 /* Set the LPTIM state */
1307 hlptim
->State
= HAL_LPTIM_STATE_BUSY
;
1309 /* Enable EXTI Line interrupt on the LPTIM Wake-up Timer */
1310 __HAL_LPTIM_WAKEUPTIMER_EXTI_ENABLE_IT();
1312 /* Enable rising edge trigger on the LPTIM Wake-up Timer Exti line */
1313 __HAL_LPTIM_WAKEUPTIMER_EXTI_ENABLE_RISING_EDGE();
1315 /* If clock source is not ULPTIM clock and counter source is external, then it must not be prescaled */
1316 if((hlptim
->Init
.Clock
.Source
!= LPTIM_CLOCKSOURCE_ULPTIM
) && (hlptim
->Init
.CounterSource
== LPTIM_COUNTERSOURCE_EXTERNAL
))
1318 /* Check if clock is prescaled */
1319 assert_param(IS_LPTIM_CLOCK_PRESCALERDIV1(hlptim
->Init
.Clock
.Prescaler
));
1320 /* Set clock prescaler to 0 */
1321 hlptim
->Instance
->CFGR
&= ~LPTIM_CFGR_PRESC
;
1324 /* Enable Autoreload write complete interrupt */
1325 __HAL_LPTIM_ENABLE_IT(hlptim
, LPTIM_IT_ARROK
);
1327 /* Enable Autoreload match interrupt */
1328 __HAL_LPTIM_ENABLE_IT(hlptim
, LPTIM_IT_ARRM
);
1330 /* Enable the Peripheral */
1331 __HAL_LPTIM_ENABLE(hlptim
);
1333 /* Load the period value in the autoreload register */
1334 __HAL_LPTIM_AUTORELOAD_SET(hlptim
, Period
);
1336 /* Start timer in continuous mode */
1337 __HAL_LPTIM_START_CONTINUOUS(hlptim
);
1339 /* Change the TIM state*/
1340 hlptim
->State
= HAL_LPTIM_STATE_READY
;
1342 /* Return function status */
1347 * @brief Stops the Counter mode in interrupt mode.
1348 * @param hlptim : LPTIM handle
1349 * @retval HAL status
1351 HAL_StatusTypeDef
HAL_LPTIM_Counter_Stop_IT(LPTIM_HandleTypeDef
*hlptim
)
1353 /* Check the parameters */
1354 assert_param(IS_LPTIM_INSTANCE(hlptim
->Instance
));
1356 /* Set the LPTIM state */
1357 hlptim
->State
= HAL_LPTIM_STATE_BUSY
;
1359 /* Disable rising edge trigger on the LPTIM Wake-up Timer Exti line */
1360 __HAL_LPTIM_WAKEUPTIMER_EXTI_DISABLE_RISING_EDGE();
1362 /* Disable EXTI Line interrupt on the LPTIM Wake-up Timer */
1363 __HAL_LPTIM_WAKEUPTIMER_EXTI_DISABLE_IT();
1365 /* Disable the Peripheral */
1366 __HAL_LPTIM_DISABLE(hlptim
);
1368 /* Disable Autoreload write complete interrupt */
1369 __HAL_LPTIM_DISABLE_IT(hlptim
, LPTIM_IT_ARROK
);
1371 /* Disable Autoreload match interrupt */
1372 __HAL_LPTIM_DISABLE_IT(hlptim
, LPTIM_IT_ARRM
);
1374 /* Change the TIM state*/
1375 hlptim
->State
= HAL_LPTIM_STATE_READY
;
1377 /* Return function status */
1385 /** @defgroup LPTIM_Group3 LPTIM Read operation functions
1386 * @brief Read operation functions.
1389 ==============================================================================
1390 ##### LPTIM Read operation functions #####
1391 ==============================================================================
1392 [..] This section provides LPTIM Reading functions.
1393 (+) Read the counter value.
1394 (+) Read the period (Auto-reload) value.
1395 (+) Read the pulse (Compare)value.
1401 * @brief This function returns the current counter value.
1402 * @param hlptim: LPTIM handle
1403 * @retval Counter value.
1405 uint32_t HAL_LPTIM_ReadCounter(LPTIM_HandleTypeDef
*hlptim
)
1407 /* Check the parameters */
1408 assert_param(IS_LPTIM_INSTANCE(hlptim
->Instance
));
1410 return (hlptim
->Instance
->CNT
);
1414 * @brief This function return the current Autoreload (Period) value.
1415 * @param hlptim: LPTIM handle
1416 * @retval Autoreload value.
1418 uint32_t HAL_LPTIM_ReadAutoReload(LPTIM_HandleTypeDef
*hlptim
)
1420 /* Check the parameters */
1421 assert_param(IS_LPTIM_INSTANCE(hlptim
->Instance
));
1423 return (hlptim
->Instance
->ARR
);
1427 * @brief This function return the current Compare (Pulse) value.
1428 * @param hlptim: LPTIM handle
1429 * @retval Compare value.
1431 uint32_t HAL_LPTIM_ReadCompare(LPTIM_HandleTypeDef
*hlptim
)
1433 /* Check the parameters */
1434 assert_param(IS_LPTIM_INSTANCE(hlptim
->Instance
));
1436 return (hlptim
->Instance
->CMP
);
1445 /** @defgroup LPTIM_Group4 LPTIM IRQ handler
1446 * @brief LPTIM IRQ handler.
1449 ==============================================================================
1450 ##### LPTIM IRQ handler #####
1451 ==============================================================================
1452 [..] This section provides LPTIM IRQ handler function.
1459 * @brief This function handles LPTIM interrupt request.
1460 * @param hlptim: LPTIM handle
1463 void HAL_LPTIM_IRQHandler(LPTIM_HandleTypeDef
*hlptim
)
1465 /* Compare match interrupt */
1466 if(__HAL_LPTIM_GET_FLAG(hlptim
, LPTIM_FLAG_CMPM
) != RESET
)
1468 if(__HAL_LPTIM_GET_IT_SOURCE(hlptim
, LPTIM_IT_CMPM
) !=RESET
)
1470 /* Clear Compare match flag */
1471 __HAL_LPTIM_CLEAR_FLAG(hlptim
, LPTIM_FLAG_CMPM
);
1472 /* Compare match Callback */
1473 HAL_LPTIM_CompareMatchCallback(hlptim
);
1477 /* Autoreload match interrupt */
1478 if(__HAL_LPTIM_GET_FLAG(hlptim
, LPTIM_FLAG_ARRM
) != RESET
)
1480 if(__HAL_LPTIM_GET_IT_SOURCE(hlptim
, LPTIM_IT_ARRM
) !=RESET
)
1482 /* Clear Autoreload match flag */
1483 __HAL_LPTIM_CLEAR_FLAG(hlptim
, LPTIM_FLAG_ARRM
);
1484 /* Autoreload match Callback */
1485 HAL_LPTIM_AutoReloadMatchCallback(hlptim
);
1489 /* Trigger detected interrupt */
1490 if(__HAL_LPTIM_GET_FLAG(hlptim
, LPTIM_FLAG_EXTTRIG
) != RESET
)
1492 if(__HAL_LPTIM_GET_IT_SOURCE(hlptim
, LPTIM_IT_EXTTRIG
) !=RESET
)
1494 /* Clear Trigger detected flag */
1495 __HAL_LPTIM_CLEAR_FLAG(hlptim
, LPTIM_FLAG_EXTTRIG
);
1496 /* Trigger detected callback */
1497 HAL_LPTIM_TriggerCallback(hlptim
);
1501 /* Compare write interrupt */
1502 if(__HAL_LPTIM_GET_FLAG(hlptim
, LPTIM_FLAG_CMPOK
) != RESET
)
1504 if(__HAL_LPTIM_GET_IT_SOURCE(hlptim
, LPTIM_FLAG_CMPM
) !=RESET
)
1506 /* Clear Compare write flag */
1507 __HAL_LPTIM_CLEAR_FLAG(hlptim
, LPTIM_FLAG_CMPOK
);
1508 /* Compare write Callback */
1509 HAL_LPTIM_CompareWriteCallback(hlptim
);
1513 /* Autoreload write interrupt */
1514 if(__HAL_LPTIM_GET_FLAG(hlptim
, LPTIM_FLAG_ARROK
) != RESET
)
1516 if(__HAL_LPTIM_GET_IT_SOURCE(hlptim
, LPTIM_IT_ARROK
) !=RESET
)
1518 /* Clear Autoreload write flag */
1519 __HAL_LPTIM_CLEAR_FLAG(hlptim
, LPTIM_FLAG_ARROK
);
1520 /* Autoreload write Callback */
1521 HAL_LPTIM_AutoReloadWriteCallback(hlptim
);
1525 /* Direction counter changed from Down to Up interrupt */
1526 if(__HAL_LPTIM_GET_FLAG(hlptim
, LPTIM_FLAG_UP
) != RESET
)
1528 if(__HAL_LPTIM_GET_IT_SOURCE(hlptim
, LPTIM_IT_UP
) !=RESET
)
1530 /* Clear Direction counter changed from Down to Up flag */
1531 __HAL_LPTIM_CLEAR_FLAG(hlptim
, LPTIM_FLAG_UP
);
1532 /* Direction counter changed from Down to Up Callback */
1533 HAL_LPTIM_DirectionUpCallback(hlptim
);
1537 /* Direction counter changed from Up to Down interrupt */
1538 if(__HAL_LPTIM_GET_FLAG(hlptim
, LPTIM_FLAG_DOWN
) != RESET
)
1540 if(__HAL_LPTIM_GET_IT_SOURCE(hlptim
, LPTIM_IT_DOWN
) !=RESET
)
1542 /* Clear Direction counter changed from Up to Down flag */
1543 __HAL_LPTIM_CLEAR_FLAG(hlptim
, LPTIM_FLAG_DOWN
);
1544 /* Direction counter changed from Up to Down Callback */
1545 HAL_LPTIM_DirectionDownCallback(hlptim
);
1548 __HAL_LPTIM_WAKEUPTIMER_EXTI_CLEAR_FLAG();
1552 * @brief Compare match callback in non blocking mode
1553 * @param hlptim : LPTIM handle
1556 __weak
void HAL_LPTIM_CompareMatchCallback(LPTIM_HandleTypeDef
*hlptim
)
1558 /* Prevent unused argument(s) compilation warning */
1560 /* NOTE : This function Should not be modified, when the callback is needed,
1561 the HAL_LPTIM_CompareMatchCallback could be implemented in the user file
1566 * @brief Autoreload match callback in non blocking mode
1567 * @param hlptim : LPTIM handle
1570 __weak
void HAL_LPTIM_AutoReloadMatchCallback(LPTIM_HandleTypeDef
*hlptim
)
1572 /* Prevent unused argument(s) compilation warning */
1574 /* NOTE : This function Should not be modified, when the callback is needed,
1575 the HAL_LPTIM_AutoReloadMatchCallback could be implemented in the user file
1580 * @brief Trigger detected callback in non blocking mode
1581 * @param hlptim : LPTIM handle
1584 __weak
void HAL_LPTIM_TriggerCallback(LPTIM_HandleTypeDef
*hlptim
)
1586 /* Prevent unused argument(s) compilation warning */
1588 /* NOTE : This function Should not be modified, when the callback is needed,
1589 the HAL_LPTIM_TriggerCallback could be implemented in the user file
1594 * @brief Compare write callback in non blocking mode
1595 * @param hlptim : LPTIM handle
1598 __weak
void HAL_LPTIM_CompareWriteCallback(LPTIM_HandleTypeDef
*hlptim
)
1600 /* Prevent unused argument(s) compilation warning */
1602 /* NOTE : This function Should not be modified, when the callback is needed,
1603 the HAL_LPTIM_CompareWriteCallback could be implemented in the user file
1608 * @brief Autoreload write callback in non blocking mode
1609 * @param hlptim : LPTIM handle
1612 __weak
void HAL_LPTIM_AutoReloadWriteCallback(LPTIM_HandleTypeDef
*hlptim
)
1614 /* Prevent unused argument(s) compilation warning */
1616 /* NOTE : This function Should not be modified, when the callback is needed,
1617 the HAL_LPTIM_AutoReloadWriteCallback could be implemented in the user file
1622 * @brief Direction counter changed from Down to Up callback in non blocking mode
1623 * @param hlptim : LPTIM handle
1626 __weak
void HAL_LPTIM_DirectionUpCallback(LPTIM_HandleTypeDef
*hlptim
)
1628 /* Prevent unused argument(s) compilation warning */
1630 /* NOTE : This function Should not be modified, when the callback is needed,
1631 the HAL_LPTIM_DirectionUpCallback could be implemented in the user file
1636 * @brief Direction counter changed from Up to Down callback in non blocking mode
1637 * @param hlptim : LPTIM handle
1640 __weak
void HAL_LPTIM_DirectionDownCallback(LPTIM_HandleTypeDef
*hlptim
)
1642 /* Prevent unused argument(s) compilation warning */
1644 /* NOTE : This function Should not be modified, when the callback is needed,
1645 the HAL_LPTIM_DirectionDownCallback could be implemented in the user file
1653 /** @defgroup LPTIM_Group5 Peripheral State functions
1654 * @brief Peripheral State functions.
1657 ==============================================================================
1658 ##### Peripheral State functions #####
1659 ==============================================================================
1661 This subsection permits to get in run-time the status of the peripheral.
1668 * @brief Returns the LPTIM state.
1669 * @param hlptim: LPTIM handle
1672 HAL_LPTIM_StateTypeDef
HAL_LPTIM_GetState(LPTIM_HandleTypeDef
*hlptim
)
1674 return hlptim
->State
;
1686 #endif /* STM32F410Tx || STM32F410Cx || STM32F410Rx || STM32F413xx || STM32F423xx */
1687 #endif /* HAL_LPTIM_MODULE_ENABLED */
1696 /************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/