Merge pull request #10558 from iNavFlight/MrD_Correct-comments-on-OSD-symbols
[inav.git] / lib / main / STM32F7 / Drivers / STM32F7xx_HAL_Driver / Src / stm32f7xx_hal_lptim.c
bloba173d82d069f9e136817b57d752a0c1b0ab1d7ae
1 /**
2 ******************************************************************************
3 * @file stm32f7xx_hal_lptim.c
4 * @author MCD Application Team
5 * @version V1.2.2
6 * @date 14-April-2017
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.
16 @verbatim
17 ==============================================================================
18 ##### How to use this driver #####
19 ==============================================================================
20 [..]
21 The LPTIM HAL driver can be used as follows:
23 (#)Initialize the LPTIM low level resources by implementing the
24 HAL_LPTIM_MspInit():
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
32 configures mainly:
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, LSI or MSI).
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
43 filter.
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
48 glitch filter.
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
52 period.
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
58 mode.
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
68 interruption mode.
70 (##) Encoder Mode: To use the encoder interface call
71 HAL_LPTIM_Encoder_Start() or HAL_LPTIM_Encoder_Start_IT() for
72 interruption mode.
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.
86 (#) User can stop any process by calling the corresponding API:
87 HAL_LPTIM_Xxx_Stop() or HAL_LPTIM_Xxx_Stop_IT() if the process is
88 already started in interruption mode.
90 (#) Call HAL_LPTIM_DeInit() to deinitialize the LPTIM peripheral.
92 @endverbatim
93 ******************************************************************************
94 * @attention
96 * <h2><center>&copy; COPYRIGHT(c) 2017 STMicroelectronics</center></h2>
98 * Redistribution and use in source and binary forms, with or without modification,
99 * are permitted provided that the following conditions are met:
100 * 1. Redistributions of source code must retain the above copyright notice,
101 * this list of conditions and the following disclaimer.
102 * 2. Redistributions in binary form must reproduce the above copyright notice,
103 * this list of conditions and the following disclaimer in the documentation
104 * and/or other materials provided with the distribution.
105 * 3. Neither the name of STMicroelectronics nor the names of its contributors
106 * may be used to endorse or promote products derived from this software
107 * without specific prior written permission.
109 * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
110 * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
111 * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE
112 * DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE
113 * FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL
114 * DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR
115 * SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
116 * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY,
117 * OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE
118 * OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
120 ******************************************************************************
123 /* Includes ------------------------------------------------------------------*/
124 #include "stm32f7xx_hal.h"
126 /** @addtogroup STM32F7xx_HAL_Driver
127 * @{
130 /** @defgroup LPTIM LPTIM
131 * @brief LPTIM HAL module driver.
132 * @{
135 #ifdef HAL_LPTIM_MODULE_ENABLED
136 /* Private types -------------------------------------------------------------*/
137 /** @defgroup LPTIM_Private_Types LPTIM Private Types
138 * @{
142 * @}
145 /* Private defines -----------------------------------------------------------*/
146 /** @defgroup LPTIM_Private_Defines LPTIM Private Defines
147 * @{
151 * @}
154 /* Private variables ---------------------------------------------------------*/
155 /** @addtogroup LPTIM_Private_Variables LPTIM Private Variables
156 * @{
160 * @}
163 /* Private constants ---------------------------------------------------------*/
164 /** @addtogroup LPTIM_Private_Constants LPTIM Private Constants
165 * @{
169 * @}
172 /* Private macros ------------------------------------------------------------*/
173 /** @addtogroup LPTIM_Private_Macros LPTIM Private Macros
174 * @{
178 * @}
181 /* Private function prototypes -----------------------------------------------*/
182 /** @addtogroup LPTIM_Private_Functions_Prototypes LPTIM Private Functions Prototypes
183 * @{
187 * @}
190 /* Private functions ---------------------------------------------------------*/
191 /** @addtogroup LPTIM_Private_Functions LPTIM Private Functions
192 * @{
196 * @}
199 /* Exported functions ---------------------------------------------------------*/
200 /** @defgroup LPTIM_Exported_Functions LPTIM Exported Functions
201 * @{
204 /** @defgroup LPTIM_Group1 Initialization/de-initialization functions
205 * @brief Initialization and Configuration functions.
207 @verbatim
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.
218 @endverbatim
219 * @{
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
226 * @retval HAL status
228 HAL_StatusTypeDef HAL_LPTIM_Init(LPTIM_HandleTypeDef *hlptim)
230 uint32_t tmpcfgr = 0;
232 /* Check the LPTIM handle allocation */
233 if(hlptim == NULL)
235 return HAL_ERROR;
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 */
313 return HAL_OK;
317 * @brief DeInitializes the LPTIM peripheral.
318 * @param hlptim: LPTIM handle
319 * @retval HAL status
321 HAL_StatusTypeDef HAL_LPTIM_DeInit(LPTIM_HandleTypeDef *hlptim)
323 /* Check the LPTIM handle allocation */
324 if(hlptim == NULL)
326 return HAL_ERROR;
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;
341 /* Release Lock */
342 __HAL_UNLOCK(hlptim);
344 /* Return function status */
345 return HAL_OK;
349 * @brief Initializes the LPTIM MSP.
350 * @param hlptim: LPTIM handle
351 * @retval None
353 __weak void HAL_LPTIM_MspInit(LPTIM_HandleTypeDef *hlptim)
355 /* Prevent unused argument(s) compilation warning */
356 UNUSED(hlptim);
358 /* NOTE : This function Should not be modified, when the callback is needed,
359 the HAL_LPTIM_MspInit could be implemented in the user file
364 * @brief DeInitializes LPTIM MSP.
365 * @param hlptim: LPTIM handle
366 * @retval None
368 __weak void HAL_LPTIM_MspDeInit(LPTIM_HandleTypeDef *hlptim)
370 /* Prevent unused argument(s) compilation warning */
371 UNUSED(hlptim);
373 /* NOTE : This function Should not be modified, when the callback is needed,
374 the HAL_LPTIM_MspDeInit could be implemented in the user file
379 * @}
382 /** @defgroup LPTIM_Group2 LPTIM Start-Stop operation functions
383 * @brief Start-Stop operation functions.
385 @verbatim
386 ==============================================================================
387 ##### LPTIM Start Stop operation functions #####
388 ==============================================================================
389 [..] This section provides functions allowing to:
390 (+) Start the PWM mode.
391 (+) Stop the PWM mode.
392 (+) Start the One pulse mode.
393 (+) Stop the One pulse mode.
394 (+) Start the Set once mode.
395 (+) Stop the Set once mode.
396 (+) Start the Encoder mode.
397 (+) Stop the Encoder mode.
398 (+) Start the Timeout mode.
399 (+) Stop the Timeout mode.
400 (+) Start the Counter mode.
401 (+) Stop the Counter mode.
404 @endverbatim
405 * @{
409 * @brief Starts the LPTIM PWM generation.
410 * @param hlptim : LPTIM handle
411 * @param Period : Specifies the Autoreload value.
412 * This parameter must be a value between 0x0000 and 0xFFFF.
413 * @param Pulse : Specifies the compare value.
414 * This parameter must be a value between 0x0000 and 0xFFFF.
415 * @retval HAL status
417 HAL_StatusTypeDef HAL_LPTIM_PWM_Start(LPTIM_HandleTypeDef *hlptim, uint32_t Period, uint32_t Pulse)
419 /* Check the parameters */
420 assert_param(IS_LPTIM_INSTANCE(hlptim->Instance));
421 assert_param(IS_LPTIM_PERIOD(Period));
422 assert_param(IS_LPTIM_PULSE(Pulse));
424 /* Set the LPTIM state */
425 hlptim->State= HAL_LPTIM_STATE_BUSY;
427 /* Reset WAVE bit to set PWM mode */
428 hlptim->Instance->CFGR &= ~LPTIM_CFGR_WAVE;
430 /* Enable the Peripheral */
431 __HAL_LPTIM_ENABLE(hlptim);
433 /* Load the period value in the autoreload register */
434 __HAL_LPTIM_AUTORELOAD_SET(hlptim, Period);
436 /* Load the pulse value in the compare register */
437 __HAL_LPTIM_COMPARE_SET(hlptim, Pulse);
439 /* Start timer in continuous mode */
440 __HAL_LPTIM_START_CONTINUOUS(hlptim);
442 /* Change the TIM state*/
443 hlptim->State= HAL_LPTIM_STATE_READY;
445 /* Return function status */
446 return HAL_OK;
450 * @brief Stops the LPTIM PWM generation.
451 * @param hlptim : LPTIM handle
452 * @retval HAL status
454 HAL_StatusTypeDef HAL_LPTIM_PWM_Stop(LPTIM_HandleTypeDef *hlptim)
456 /* Check the parameters */
457 assert_param(IS_LPTIM_INSTANCE(hlptim->Instance));
459 /* Set the LPTIM state */
460 hlptim->State= HAL_LPTIM_STATE_BUSY;
462 /* Disable the Peripheral */
463 __HAL_LPTIM_DISABLE(hlptim);
465 /* Change the TIM state*/
466 hlptim->State= HAL_LPTIM_STATE_READY;
468 /* Return function status */
469 return HAL_OK;
473 * @brief Starts the LPTIM PWM generation in interrupt mode.
474 * @param hlptim : LPTIM handle
475 * @param Period : Specifies the Autoreload value.
476 * This parameter must be a value between 0x0000 and 0xFFFF
477 * @param Pulse : Specifies the compare value.
478 * This parameter must be a value between 0x0000 and 0xFFFF
479 * @retval HAL status
481 HAL_StatusTypeDef HAL_LPTIM_PWM_Start_IT(LPTIM_HandleTypeDef *hlptim, uint32_t Period, uint32_t Pulse)
483 /* Check the parameters */
484 assert_param(IS_LPTIM_INSTANCE(hlptim->Instance));
485 assert_param(IS_LPTIM_PERIOD(Period));
486 assert_param(IS_LPTIM_PULSE(Pulse));
488 /* Set the LPTIM state */
489 hlptim->State= HAL_LPTIM_STATE_BUSY;
491 /* Reset WAVE bit to set PWM mode */
492 hlptim->Instance->CFGR &= ~LPTIM_CFGR_WAVE;
494 /* Enable Autoreload write complete interrupt */
495 __HAL_LPTIM_ENABLE_IT(hlptim, LPTIM_IT_ARROK);
497 /* Enable Compare write complete interrupt */
498 __HAL_LPTIM_ENABLE_IT(hlptim, LPTIM_IT_CMPOK);
500 /* Enable Autoreload match interrupt */
501 __HAL_LPTIM_ENABLE_IT(hlptim, LPTIM_IT_ARRM);
503 /* Enable Compare match interrupt */
504 __HAL_LPTIM_ENABLE_IT(hlptim, LPTIM_IT_CMPM);
506 /* If external trigger source is used, then enable external trigger interrupt */
507 if ((hlptim->Init.Trigger.Source) != LPTIM_TRIGSOURCE_SOFTWARE)
509 /* Enable external trigger interrupt */
510 __HAL_LPTIM_ENABLE_IT(hlptim, LPTIM_IT_EXTTRIG);
513 /* Enable the Peripheral */
514 __HAL_LPTIM_ENABLE(hlptim);
516 /* Load the period value in the autoreload register */
517 __HAL_LPTIM_AUTORELOAD_SET(hlptim, Period);
519 /* Load the pulse value in the compare register */
520 __HAL_LPTIM_COMPARE_SET(hlptim, Pulse);
522 /* Start timer in continuous mode */
523 __HAL_LPTIM_START_CONTINUOUS(hlptim);
525 /* Change the TIM state*/
526 hlptim->State= HAL_LPTIM_STATE_READY;
528 /* Return function status */
529 return HAL_OK;
533 * @brief Stops the LPTIM PWM generation in interrupt mode.
534 * @param hlptim : LPTIM handle
535 * @retval HAL status
537 HAL_StatusTypeDef HAL_LPTIM_PWM_Stop_IT(LPTIM_HandleTypeDef *hlptim)
539 /* Check the parameters */
540 assert_param(IS_LPTIM_INSTANCE(hlptim->Instance));
542 /* Set the LPTIM state */
543 hlptim->State= HAL_LPTIM_STATE_BUSY;
545 /* Disable the Peripheral */
546 __HAL_LPTIM_DISABLE(hlptim);
548 /* Disable Autoreload write complete interrupt */
549 __HAL_LPTIM_DISABLE_IT(hlptim, LPTIM_IT_ARROK);
551 /* Disable Compare write complete interrupt */
552 __HAL_LPTIM_DISABLE_IT(hlptim, LPTIM_IT_CMPOK);
554 /* Disable Autoreload match interrupt */
555 __HAL_LPTIM_DISABLE_IT(hlptim, LPTIM_IT_ARRM);
557 /* Disable Compare match interrupt */
558 __HAL_LPTIM_DISABLE_IT(hlptim, LPTIM_IT_CMPM);
560 /* If external trigger source is used, then disable external trigger interrupt */
561 if ((hlptim->Init.Trigger.Source) != LPTIM_TRIGSOURCE_SOFTWARE)
563 /* Disable external trigger interrupt */
564 __HAL_LPTIM_DISABLE_IT(hlptim, LPTIM_IT_EXTTRIG);
567 /* Change the TIM state*/
568 hlptim->State= HAL_LPTIM_STATE_READY;
570 /* Return function status */
571 return HAL_OK;
575 * @brief Starts the LPTIM One pulse generation.
576 * @param hlptim : LPTIM handle
577 * @param Period : Specifies the Autoreload value.
578 * This parameter must be a value between 0x0000 and 0xFFFF.
579 * @param Pulse : Specifies the compare value.
580 * This parameter must be a value between 0x0000 and 0xFFFF.
581 * @retval HAL status
583 HAL_StatusTypeDef HAL_LPTIM_OnePulse_Start(LPTIM_HandleTypeDef *hlptim, uint32_t Period, uint32_t Pulse)
585 /* Check the parameters */
586 assert_param(IS_LPTIM_INSTANCE(hlptim->Instance));
587 assert_param(IS_LPTIM_PERIOD(Period));
588 assert_param(IS_LPTIM_PULSE(Pulse));
590 /* Set the LPTIM state */
591 hlptim->State= HAL_LPTIM_STATE_BUSY;
593 /* Reset WAVE bit to set one pulse mode */
594 hlptim->Instance->CFGR &= ~LPTIM_CFGR_WAVE;
596 /* Enable the Peripheral */
597 __HAL_LPTIM_ENABLE(hlptim);
599 /* Load the period value in the autoreload register */
600 __HAL_LPTIM_AUTORELOAD_SET(hlptim, Period);
602 /* Load the pulse value in the compare register */
603 __HAL_LPTIM_COMPARE_SET(hlptim, Pulse);
605 /* Start timer in continuous mode */
606 __HAL_LPTIM_START_SINGLE(hlptim);
608 /* Change the TIM state*/
609 hlptim->State= HAL_LPTIM_STATE_READY;
611 /* Return function status */
612 return HAL_OK;
616 * @brief Stops the LPTIM One pulse generation.
617 * @param hlptim : LPTIM handle
618 * @retval HAL status
620 HAL_StatusTypeDef HAL_LPTIM_OnePulse_Stop(LPTIM_HandleTypeDef *hlptim)
622 /* Check the parameters */
623 assert_param(IS_LPTIM_INSTANCE(hlptim->Instance));
625 /* Set the LPTIM state */
626 hlptim->State= HAL_LPTIM_STATE_BUSY;
628 /* Disable the Peripheral */
629 __HAL_LPTIM_DISABLE(hlptim);
631 /* Change the TIM state*/
632 hlptim->State= HAL_LPTIM_STATE_READY;
634 /* Return function status */
635 return HAL_OK;
639 * @brief Starts the LPTIM One pulse generation in interrupt mode.
640 * @param hlptim : LPTIM handle
641 * @param Period : Specifies the Autoreload value.
642 * This parameter must be a value between 0x0000 and 0xFFFF.
643 * @param Pulse : Specifies the compare value.
644 * This parameter must be a value between 0x0000 and 0xFFFF.
645 * @retval HAL status
647 HAL_StatusTypeDef HAL_LPTIM_OnePulse_Start_IT(LPTIM_HandleTypeDef *hlptim, uint32_t Period, uint32_t Pulse)
649 /* Check the parameters */
650 assert_param(IS_LPTIM_INSTANCE(hlptim->Instance));
651 assert_param(IS_LPTIM_PERIOD(Period));
652 assert_param(IS_LPTIM_PULSE(Pulse));
654 /* Set the LPTIM state */
655 hlptim->State= HAL_LPTIM_STATE_BUSY;
657 /* Reset WAVE bit to set one pulse mode */
658 hlptim->Instance->CFGR &= ~LPTIM_CFGR_WAVE;
660 /* Enable Autoreload write complete interrupt */
661 __HAL_LPTIM_ENABLE_IT(hlptim, LPTIM_IT_ARROK);
663 /* Enable Compare write complete interrupt */
664 __HAL_LPTIM_ENABLE_IT(hlptim, LPTIM_IT_CMPOK);
666 /* Enable Autoreload match interrupt */
667 __HAL_LPTIM_ENABLE_IT(hlptim, LPTIM_IT_ARRM);
669 /* Enable Compare match interrupt */
670 __HAL_LPTIM_ENABLE_IT(hlptim, LPTIM_IT_CMPM);
672 /* If external trigger source is used, then enable external trigger interrupt */
673 if ((hlptim->Init.Trigger.Source) != LPTIM_TRIGSOURCE_SOFTWARE)
675 /* Enable external trigger interrupt */
676 __HAL_LPTIM_ENABLE_IT(hlptim, LPTIM_IT_EXTTRIG);
679 /* Enable the Peripheral */
680 __HAL_LPTIM_ENABLE(hlptim);
682 /* Load the period value in the autoreload register */
683 __HAL_LPTIM_AUTORELOAD_SET(hlptim, Period);
685 /* Load the pulse value in the compare register */
686 __HAL_LPTIM_COMPARE_SET(hlptim, Pulse);
688 /* Start timer in continuous mode */
689 __HAL_LPTIM_START_SINGLE(hlptim);
691 /* Change the TIM state*/
692 hlptim->State= HAL_LPTIM_STATE_READY;
694 /* Return function status */
695 return HAL_OK;
699 * @brief Stops the LPTIM One pulse generation in interrupt mode.
700 * @param hlptim : LPTIM handle
701 * @retval HAL status
703 HAL_StatusTypeDef HAL_LPTIM_OnePulse_Stop_IT(LPTIM_HandleTypeDef *hlptim)
705 /* Check the parameters */
706 assert_param(IS_LPTIM_INSTANCE(hlptim->Instance));
708 /* Set the LPTIM state */
709 hlptim->State= HAL_LPTIM_STATE_BUSY;
711 /* Disable the Peripheral */
712 __HAL_LPTIM_DISABLE(hlptim);
714 /* Disable Autoreload write complete interrupt */
715 __HAL_LPTIM_DISABLE_IT(hlptim, LPTIM_IT_ARROK);
717 /* Disable Compare write complete interrupt */
718 __HAL_LPTIM_DISABLE_IT(hlptim, LPTIM_IT_CMPOK);
720 /* Disable Autoreload match interrupt */
721 __HAL_LPTIM_DISABLE_IT(hlptim, LPTIM_IT_ARRM);
723 /* Disable Compare match interrupt */
724 __HAL_LPTIM_DISABLE_IT(hlptim, LPTIM_IT_CMPM);
726 /* If external trigger source is used, then disable external trigger interrupt */
727 if ((hlptim->Init.Trigger.Source) != LPTIM_TRIGSOURCE_SOFTWARE)
729 /* Disable external trigger interrupt */
730 __HAL_LPTIM_DISABLE_IT(hlptim, LPTIM_IT_EXTTRIG);
733 /* Change the TIM state*/
734 hlptim->State= HAL_LPTIM_STATE_READY;
736 /* Return function status */
737 return HAL_OK;
741 * @brief Starts the LPTIM in Set once mode.
742 * @param hlptim : LPTIM handle
743 * @param Period : Specifies the Autoreload value.
744 * This parameter must be a value between 0x0000 and 0xFFFF.
745 * @param Pulse : Specifies the compare value.
746 * This parameter must be a value between 0x0000 and 0xFFFF.
747 * @retval HAL status
749 HAL_StatusTypeDef HAL_LPTIM_SetOnce_Start(LPTIM_HandleTypeDef *hlptim, uint32_t Period, uint32_t Pulse)
751 /* Check the parameters */
752 assert_param(IS_LPTIM_INSTANCE(hlptim->Instance));
753 assert_param(IS_LPTIM_PERIOD(Period));
754 assert_param(IS_LPTIM_PULSE(Pulse));
756 /* Set the LPTIM state */
757 hlptim->State= HAL_LPTIM_STATE_BUSY;
759 /* Set WAVE bit to enable the set once mode */
760 hlptim->Instance->CFGR |= LPTIM_CFGR_WAVE;
762 /* Enable the Peripheral */
763 __HAL_LPTIM_ENABLE(hlptim);
765 /* Load the period value in the autoreload register */
766 __HAL_LPTIM_AUTORELOAD_SET(hlptim, Period);
768 /* Load the pulse value in the compare register */
769 __HAL_LPTIM_COMPARE_SET(hlptim, Pulse);
771 /* Start timer in continuous mode */
772 __HAL_LPTIM_START_SINGLE(hlptim);
774 /* Change the TIM state*/
775 hlptim->State= HAL_LPTIM_STATE_READY;
777 /* Return function status */
778 return HAL_OK;
782 * @brief Stops the LPTIM Set once mode.
783 * @param hlptim : LPTIM handle
784 * @retval HAL status
786 HAL_StatusTypeDef HAL_LPTIM_SetOnce_Stop(LPTIM_HandleTypeDef *hlptim)
788 /* Check the parameters */
789 assert_param(IS_LPTIM_INSTANCE(hlptim->Instance));
791 /* Set the LPTIM state */
792 hlptim->State= HAL_LPTIM_STATE_BUSY;
794 /* Disable the Peripheral */
795 __HAL_LPTIM_DISABLE(hlptim);
797 /* Change the TIM state*/
798 hlptim->State= HAL_LPTIM_STATE_READY;
800 /* Return function status */
801 return HAL_OK;
805 * @brief Starts the LPTIM Set once mode in interrupt mode.
806 * @param hlptim : LPTIM handle
807 * @param Period : Specifies the Autoreload value.
808 * This parameter must be a value between 0x0000 and 0xFFFF.
809 * @param Pulse : Specifies the compare value.
810 * This parameter must be a value between 0x0000 and 0xFFFF.
811 * @retval HAL status
813 HAL_StatusTypeDef HAL_LPTIM_SetOnce_Start_IT(LPTIM_HandleTypeDef *hlptim, uint32_t Period, uint32_t Pulse)
815 /* Check the parameters */
816 assert_param(IS_LPTIM_INSTANCE(hlptim->Instance));
817 assert_param(IS_LPTIM_PERIOD(Period));
818 assert_param(IS_LPTIM_PULSE(Pulse));
820 /* Set the LPTIM state */
821 hlptim->State= HAL_LPTIM_STATE_BUSY;
823 /* Set WAVE bit to enable the set once mode */
824 hlptim->Instance->CFGR |= LPTIM_CFGR_WAVE;
826 /* Enable Autoreload write complete interrupt */
827 __HAL_LPTIM_ENABLE_IT(hlptim, LPTIM_IT_ARROK);
829 /* Enable Compare write complete interrupt */
830 __HAL_LPTIM_ENABLE_IT(hlptim, LPTIM_IT_CMPOK);
832 /* Enable Autoreload match interrupt */
833 __HAL_LPTIM_ENABLE_IT(hlptim, LPTIM_IT_ARRM);
835 /* Enable Compare match interrupt */
836 __HAL_LPTIM_ENABLE_IT(hlptim, LPTIM_IT_CMPM);
838 /* If external trigger source is used, then enable external trigger interrupt */
839 if ((hlptim->Init.Trigger.Source) != LPTIM_TRIGSOURCE_SOFTWARE)
841 /* Enable external trigger interrupt */
842 __HAL_LPTIM_ENABLE_IT(hlptim, LPTIM_IT_EXTTRIG);
845 /* Enable the Peripheral */
846 __HAL_LPTIM_ENABLE(hlptim);
848 /* Load the period value in the autoreload register */
849 __HAL_LPTIM_AUTORELOAD_SET(hlptim, Period);
851 /* Load the pulse value in the compare register */
852 __HAL_LPTIM_COMPARE_SET(hlptim, Pulse);
854 /* Start timer in continuous mode */
855 __HAL_LPTIM_START_SINGLE(hlptim);
857 /* Change the TIM state*/
858 hlptim->State= HAL_LPTIM_STATE_READY;
860 /* Return function status */
861 return HAL_OK;
865 * @brief Stops the LPTIM Set once mode in interrupt mode.
866 * @param hlptim : LPTIM handle
867 * @retval HAL status
869 HAL_StatusTypeDef HAL_LPTIM_SetOnce_Stop_IT(LPTIM_HandleTypeDef *hlptim)
871 /* Check the parameters */
872 assert_param(IS_LPTIM_INSTANCE(hlptim->Instance));
874 /* Set the LPTIM state */
875 hlptim->State= HAL_LPTIM_STATE_BUSY;
877 /* Disable the Peripheral */
878 __HAL_LPTIM_DISABLE(hlptim);
880 /* Disable Autoreload write complete interrupt */
881 __HAL_LPTIM_DISABLE_IT(hlptim, LPTIM_IT_ARROK);
883 /* Disable Compare write complete interrupt */
884 __HAL_LPTIM_DISABLE_IT(hlptim, LPTIM_IT_CMPOK);
886 /* Disable Autoreload match interrupt */
887 __HAL_LPTIM_DISABLE_IT(hlptim, LPTIM_IT_ARRM);
889 /* Disable Compare match interrupt */
890 __HAL_LPTIM_DISABLE_IT(hlptim, LPTIM_IT_CMPM);
892 /* If external trigger source is used, then disable external trigger interrupt */
893 if ((hlptim->Init.Trigger.Source) != LPTIM_TRIGSOURCE_SOFTWARE)
895 /* Disable external trigger interrupt */
896 __HAL_LPTIM_DISABLE_IT(hlptim, LPTIM_IT_EXTTRIG);
899 /* Change the TIM state*/
900 hlptim->State= HAL_LPTIM_STATE_READY;
902 /* Return function status */
903 return HAL_OK;
907 * @brief Starts the Encoder interface.
908 * @param hlptim : LPTIM handle
909 * @param Period : Specifies the Autoreload value.
910 * This parameter must be a value between 0x0000 and 0xFFFF.
911 * @retval HAL status
913 HAL_StatusTypeDef HAL_LPTIM_Encoder_Start(LPTIM_HandleTypeDef *hlptim, uint32_t Period)
915 uint32_t tmpcfgr = 0;
917 /* Check the parameters */
918 assert_param(IS_LPTIM_INSTANCE(hlptim->Instance));
919 assert_param(IS_LPTIM_PERIOD(Period));
920 assert_param(hlptim->Init.Clock.Source == LPTIM_CLOCKSOURCE_APBCLOCK_LPOSC);
921 assert_param(hlptim->Init.Clock.Prescaler == LPTIM_PRESCALER_DIV1);
922 assert_param(IS_LPTIM_CLOCK_POLARITY(hlptim->Init.UltraLowPowerClock.Polarity));
924 /* Set the LPTIM state */
925 hlptim->State= HAL_LPTIM_STATE_BUSY;
927 /* Get the LPTIMx CFGR value */
928 tmpcfgr = hlptim->Instance->CFGR;
930 /* Clear CKPOL bits */
931 tmpcfgr &= (uint32_t)(~LPTIM_CFGR_CKPOL);
933 /* Set Input polarity */
934 tmpcfgr |= hlptim->Init.UltraLowPowerClock.Polarity;
936 /* Write to LPTIMx CFGR */
937 hlptim->Instance->CFGR = tmpcfgr;
939 /* Set ENC bit to enable the encoder interface */
940 hlptim->Instance->CFGR |= LPTIM_CFGR_ENC;
942 /* Enable the Peripheral */
943 __HAL_LPTIM_ENABLE(hlptim);
945 /* Load the period value in the autoreload register */
946 __HAL_LPTIM_AUTORELOAD_SET(hlptim, Period);
948 /* Start timer in continuous mode */
949 __HAL_LPTIM_START_CONTINUOUS(hlptim);
951 /* Change the TIM state*/
952 hlptim->State= HAL_LPTIM_STATE_READY;
954 /* Return function status */
955 return HAL_OK;
959 * @brief Stops the Encoder interface.
960 * @param hlptim : LPTIM handle
961 * @retval HAL status
963 HAL_StatusTypeDef HAL_LPTIM_Encoder_Stop(LPTIM_HandleTypeDef *hlptim)
965 /* Check the parameters */
966 assert_param(IS_LPTIM_INSTANCE(hlptim->Instance));
968 /* Set the LPTIM state */
969 hlptim->State= HAL_LPTIM_STATE_BUSY;
971 /* Disable the Peripheral */
972 __HAL_LPTIM_DISABLE(hlptim);
974 /* Reset ENC bit to disable the encoder interface */
975 hlptim->Instance->CFGR &= ~LPTIM_CFGR_ENC;
977 /* Change the TIM state*/
978 hlptim->State= HAL_LPTIM_STATE_READY;
980 /* Return function status */
981 return HAL_OK;
985 * @brief Starts the Encoder interface in interrupt mode.
986 * @param hlptim : LPTIM handle
987 * @param Period : Specifies the Autoreload value.
988 * This parameter must be a value between 0x0000 and 0xFFFF.
989 * @retval HAL status
991 HAL_StatusTypeDef HAL_LPTIM_Encoder_Start_IT(LPTIM_HandleTypeDef *hlptim, uint32_t Period)
993 uint32_t tmpcfgr = 0;
995 /* Check the parameters */
996 assert_param(IS_LPTIM_INSTANCE(hlptim->Instance));
997 assert_param(IS_LPTIM_PERIOD(Period));
998 assert_param(hlptim->Init.Clock.Source == LPTIM_CLOCKSOURCE_APBCLOCK_LPOSC);
999 assert_param(hlptim->Init.Clock.Prescaler == LPTIM_PRESCALER_DIV1);
1000 assert_param(IS_LPTIM_CLOCK_POLARITY(hlptim->Init.UltraLowPowerClock.Polarity));
1002 /* Set the LPTIM state */
1003 hlptim->State= HAL_LPTIM_STATE_BUSY;
1005 /* Configure edge sensitivity for encoder mode */
1006 /* Get the LPTIMx CFGR value */
1007 tmpcfgr = hlptim->Instance->CFGR;
1009 /* Clear CKPOL bits */
1010 tmpcfgr &= (uint32_t)(~LPTIM_CFGR_CKPOL);
1012 /* Set Input polarity */
1013 tmpcfgr |= hlptim->Init.UltraLowPowerClock.Polarity;
1015 /* Write to LPTIMx CFGR */
1016 hlptim->Instance->CFGR = tmpcfgr;
1018 /* Set ENC bit to enable the encoder interface */
1019 hlptim->Instance->CFGR |= LPTIM_CFGR_ENC;
1021 /* Enable "switch to down direction" interrupt */
1022 __HAL_LPTIM_ENABLE_IT(hlptim, LPTIM_IT_DOWN);
1024 /* Enable "switch to up direction" interrupt */
1025 __HAL_LPTIM_ENABLE_IT(hlptim, LPTIM_IT_UP);
1027 /* Enable the Peripheral */
1028 __HAL_LPTIM_ENABLE(hlptim);
1030 /* Load the period value in the autoreload register */
1031 __HAL_LPTIM_AUTORELOAD_SET(hlptim, Period);
1033 /* Start timer in continuous mode */
1034 __HAL_LPTIM_START_CONTINUOUS(hlptim);
1036 /* Change the TIM state*/
1037 hlptim->State= HAL_LPTIM_STATE_READY;
1039 /* Return function status */
1040 return HAL_OK;
1044 * @brief Stops the Encoder interface in interrupt mode.
1045 * @param hlptim : LPTIM handle
1046 * @retval HAL status
1048 HAL_StatusTypeDef HAL_LPTIM_Encoder_Stop_IT(LPTIM_HandleTypeDef *hlptim)
1050 /* Check the parameters */
1051 assert_param(IS_LPTIM_INSTANCE(hlptim->Instance));
1053 /* Set the LPTIM state */
1054 hlptim->State= HAL_LPTIM_STATE_BUSY;
1056 /* Disable the Peripheral */
1057 __HAL_LPTIM_DISABLE(hlptim);
1059 /* Reset ENC bit to disable the encoder interface */
1060 hlptim->Instance->CFGR &= ~LPTIM_CFGR_ENC;
1062 /* Disable "switch to down direction" interrupt */
1063 __HAL_LPTIM_DISABLE_IT(hlptim, LPTIM_IT_DOWN);
1065 /* Disable "switch to up direction" interrupt */
1066 __HAL_LPTIM_DISABLE_IT(hlptim, LPTIM_IT_UP);
1068 /* Change the TIM state*/
1069 hlptim->State= HAL_LPTIM_STATE_READY;
1071 /* Return function status */
1072 return HAL_OK;
1076 * @brief Starts the Timeout function. The first trigger event will start the
1077 * timer, any successive trigger event will reset the counter and
1078 * the timer restarts.
1079 * @param hlptim : LPTIM handle
1080 * @param Period : Specifies the Autoreload value.
1081 * This parameter must be a value between 0x0000 and 0xFFFF.
1082 * @param Timeout : Specifies the TimeOut value to rest the counter.
1083 * This parameter must be a value between 0x0000 and 0xFFFF.
1084 * @retval HAL status
1086 HAL_StatusTypeDef HAL_LPTIM_TimeOut_Start(LPTIM_HandleTypeDef *hlptim, uint32_t Period, uint32_t Timeout)
1088 /* Check the parameters */
1089 assert_param(IS_LPTIM_INSTANCE(hlptim->Instance));
1090 assert_param(IS_LPTIM_PERIOD(Period));
1091 assert_param(IS_LPTIM_PULSE(Timeout));
1093 /* Set the LPTIM state */
1094 hlptim->State= HAL_LPTIM_STATE_BUSY;
1096 /* Set TIMOUT bit to enable the timeout function */
1097 hlptim->Instance->CFGR |= LPTIM_CFGR_TIMOUT;
1099 /* Enable the Peripheral */
1100 __HAL_LPTIM_ENABLE(hlptim);
1102 /* Load the period value in the autoreload register */
1103 __HAL_LPTIM_AUTORELOAD_SET(hlptim, Period);
1105 /* Load the Timeout value in the compare register */
1106 __HAL_LPTIM_COMPARE_SET(hlptim, Timeout);
1108 /* Start timer in continuous mode */
1109 __HAL_LPTIM_START_CONTINUOUS(hlptim);
1111 /* Change the TIM state*/
1112 hlptim->State= HAL_LPTIM_STATE_READY;
1114 /* Return function status */
1115 return HAL_OK;
1119 * @brief Stops the Timeout function.
1120 * @param hlptim : LPTIM handle
1121 * @retval HAL status
1123 HAL_StatusTypeDef HAL_LPTIM_TimeOut_Stop(LPTIM_HandleTypeDef *hlptim)
1125 /* Check the parameters */
1126 assert_param(IS_LPTIM_INSTANCE(hlptim->Instance));
1128 /* Set the LPTIM state */
1129 hlptim->State= HAL_LPTIM_STATE_BUSY;
1131 /* Disable the Peripheral */
1132 __HAL_LPTIM_DISABLE(hlptim);
1134 /* Reset TIMOUT bit to enable the timeout function */
1135 hlptim->Instance->CFGR &= ~LPTIM_CFGR_TIMOUT;
1137 /* Change the TIM state*/
1138 hlptim->State= HAL_LPTIM_STATE_READY;
1140 /* Return function status */
1141 return HAL_OK;
1145 * @brief Starts the Timeout function in interrupt mode. The first trigger
1146 * event will start the timer, any successive trigger event will reset
1147 * the counter and the timer restarts.
1148 * @param hlptim : LPTIM handle
1149 * @param Period : Specifies the Autoreload value.
1150 * This parameter must be a value between 0x0000 and 0xFFFF.
1151 * @param Timeout : Specifies the TimeOut value to rest the counter.
1152 * This parameter must be a value between 0x0000 and 0xFFFF.
1153 * @retval HAL status
1155 HAL_StatusTypeDef HAL_LPTIM_TimeOut_Start_IT(LPTIM_HandleTypeDef *hlptim, uint32_t Period, uint32_t Timeout)
1157 /* Check the parameters */
1158 assert_param(IS_LPTIM_INSTANCE(hlptim->Instance));
1159 assert_param(IS_LPTIM_PERIOD(Period));
1160 assert_param(IS_LPTIM_PULSE(Timeout));
1162 /* Set the LPTIM state */
1163 hlptim->State= HAL_LPTIM_STATE_BUSY;
1165 /* Enable EXTI Line interrupt on the LPTIM Wake-up Timer */
1166 __HAL_LPTIM_WAKEUPTIMER_EXTI_ENABLE_IT();
1168 /* Enable rising edge trigger on the LPTIM Wake-up Timer Exti line */
1169 __HAL_LPTIM_WAKEUPTIMER_EXTI_ENABLE_RISING_EDGE();
1171 /* Set TIMOUT bit to enable the timeout function */
1172 hlptim->Instance->CFGR |= LPTIM_CFGR_TIMOUT;
1174 /* Enable Compare match interrupt */
1175 __HAL_LPTIM_ENABLE_IT(hlptim, LPTIM_IT_CMPM);
1177 /* Enable the Peripheral */
1178 __HAL_LPTIM_ENABLE(hlptim);
1180 /* Load the period value in the autoreload register */
1181 __HAL_LPTIM_AUTORELOAD_SET(hlptim, Period);
1183 /* Load the Timeout value in the compare register */
1184 __HAL_LPTIM_COMPARE_SET(hlptim, Timeout);
1186 /* Start timer in continuous mode */
1187 __HAL_LPTIM_START_CONTINUOUS(hlptim);
1189 /* Change the TIM state*/
1190 hlptim->State= HAL_LPTIM_STATE_READY;
1192 /* Return function status */
1193 return HAL_OK;
1197 * @brief Stops the Timeout function in interrupt mode.
1198 * @param hlptim : LPTIM handle
1199 * @retval HAL status
1201 HAL_StatusTypeDef HAL_LPTIM_TimeOut_Stop_IT(LPTIM_HandleTypeDef *hlptim)
1203 /* Check the parameters */
1204 assert_param(IS_LPTIM_INSTANCE(hlptim->Instance));
1206 /* Set the LPTIM state */
1207 hlptim->State= HAL_LPTIM_STATE_BUSY;
1209 /* Disable rising edge trigger on the LPTIM Wake-up Timer Exti line */
1210 __HAL_LPTIM_WAKEUPTIMER_EXTI_DISABLE_RISING_EDGE();
1212 /* Disable EXTI Line interrupt on the LPTIM Wake-up Timer */
1213 __HAL_LPTIM_WAKEUPTIMER_EXTI_DISABLE_IT();
1215 /* Disable the Peripheral */
1216 __HAL_LPTIM_DISABLE(hlptim);
1218 /* Reset TIMOUT bit to enable the timeout function */
1219 hlptim->Instance->CFGR &= ~LPTIM_CFGR_TIMOUT;
1221 /* Disable Compare match interrupt */
1222 __HAL_LPTIM_DISABLE_IT(hlptim, LPTIM_IT_CMPM);
1224 /* Change the TIM state*/
1225 hlptim->State= HAL_LPTIM_STATE_READY;
1227 /* Return function status */
1228 return HAL_OK;
1232 * @brief Starts the Counter mode.
1233 * @param hlptim : LPTIM handle
1234 * @param Period : Specifies the Autoreload value.
1235 * This parameter must be a value between 0x0000 and 0xFFFF.
1236 * @retval HAL status
1238 HAL_StatusTypeDef HAL_LPTIM_Counter_Start(LPTIM_HandleTypeDef *hlptim, uint32_t Period)
1240 /* Check the parameters */
1241 assert_param(IS_LPTIM_INSTANCE(hlptim->Instance));
1242 assert_param(IS_LPTIM_PERIOD(Period));
1244 /* Set the LPTIM state */
1245 hlptim->State= HAL_LPTIM_STATE_BUSY;
1247 /* If clock source is not ULPTIM clock and counter source is external, then it must not be prescaled */
1248 if((hlptim->Init.Clock.Source != LPTIM_CLOCKSOURCE_ULPTIM) && (hlptim->Init.CounterSource == LPTIM_COUNTERSOURCE_EXTERNAL))
1250 /* Check if clock is prescaled */
1251 assert_param(IS_LPTIM_CLOCK_PRESCALERDIV1(hlptim->Init.Clock.Prescaler));
1252 /* Set clock prescaler to 0 */
1253 hlptim->Instance->CFGR &= ~LPTIM_CFGR_PRESC;
1256 /* Enable the Peripheral */
1257 __HAL_LPTIM_ENABLE(hlptim);
1259 /* Load the period value in the autoreload register */
1260 __HAL_LPTIM_AUTORELOAD_SET(hlptim, Period);
1262 /* Start timer in continuous mode */
1263 __HAL_LPTIM_START_CONTINUOUS(hlptim);
1265 /* Change the TIM state*/
1266 hlptim->State= HAL_LPTIM_STATE_READY;
1268 /* Return function status */
1269 return HAL_OK;
1273 * @brief Stops the Counter mode.
1274 * @param hlptim : LPTIM handle
1275 * @retval HAL status
1277 HAL_StatusTypeDef HAL_LPTIM_Counter_Stop(LPTIM_HandleTypeDef *hlptim)
1279 /* Check the parameters */
1280 assert_param(IS_LPTIM_INSTANCE(hlptim->Instance));
1282 /* Set the LPTIM state */
1283 hlptim->State= HAL_LPTIM_STATE_BUSY;
1285 /* Disable the Peripheral */
1286 __HAL_LPTIM_DISABLE(hlptim);
1288 /* Change the TIM state*/
1289 hlptim->State= HAL_LPTIM_STATE_READY;
1291 /* Return function status */
1292 return HAL_OK;
1296 * @brief Starts the Counter mode in interrupt mode.
1297 * @param hlptim : LPTIM handle
1298 * @param Period : Specifies the Autoreload value.
1299 * This parameter must be a value between 0x0000 and 0xFFFF.
1300 * @retval HAL status
1302 HAL_StatusTypeDef HAL_LPTIM_Counter_Start_IT(LPTIM_HandleTypeDef *hlptim, uint32_t Period)
1304 /* Check the parameters */
1305 assert_param(IS_LPTIM_INSTANCE(hlptim->Instance));
1306 assert_param(IS_LPTIM_PERIOD(Period));
1308 /* Set the LPTIM state */
1309 hlptim->State= HAL_LPTIM_STATE_BUSY;
1311 /* Enable EXTI Line interrupt on the LPTIM Wake-up Timer */
1312 __HAL_LPTIM_WAKEUPTIMER_EXTI_ENABLE_IT();
1314 /* Enable rising edge trigger on the LPTIM Wake-up Timer Exti line */
1315 __HAL_LPTIM_WAKEUPTIMER_EXTI_ENABLE_RISING_EDGE();
1317 /* If clock source is not ULPTIM clock and counter source is external, then it must not be prescaled */
1318 if((hlptim->Init.Clock.Source != LPTIM_CLOCKSOURCE_ULPTIM) && (hlptim->Init.CounterSource == LPTIM_COUNTERSOURCE_EXTERNAL))
1320 /* Check if clock is prescaled */
1321 assert_param(IS_LPTIM_CLOCK_PRESCALERDIV1(hlptim->Init.Clock.Prescaler));
1322 /* Set clock prescaler to 0 */
1323 hlptim->Instance->CFGR &= ~LPTIM_CFGR_PRESC;
1326 /* Enable Autoreload write complete interrupt */
1327 __HAL_LPTIM_ENABLE_IT(hlptim, LPTIM_IT_ARROK);
1329 /* Enable Autoreload match interrupt */
1330 __HAL_LPTIM_ENABLE_IT(hlptim, LPTIM_IT_ARRM);
1332 /* Enable the Peripheral */
1333 __HAL_LPTIM_ENABLE(hlptim);
1335 /* Load the period value in the autoreload register */
1336 __HAL_LPTIM_AUTORELOAD_SET(hlptim, Period);
1338 /* Start timer in continuous mode */
1339 __HAL_LPTIM_START_CONTINUOUS(hlptim);
1341 /* Change the TIM state*/
1342 hlptim->State= HAL_LPTIM_STATE_READY;
1344 /* Return function status */
1345 return HAL_OK;
1349 * @brief Stops the Counter mode in interrupt mode.
1350 * @param hlptim : LPTIM handle
1351 * @retval HAL status
1353 HAL_StatusTypeDef HAL_LPTIM_Counter_Stop_IT(LPTIM_HandleTypeDef *hlptim)
1355 /* Check the parameters */
1356 assert_param(IS_LPTIM_INSTANCE(hlptim->Instance));
1358 /* Set the LPTIM state */
1359 hlptim->State= HAL_LPTIM_STATE_BUSY;
1361 /* Disable rising edge trigger on the LPTIM Wake-up Timer Exti line */
1362 __HAL_LPTIM_WAKEUPTIMER_EXTI_DISABLE_RISING_EDGE();
1364 /* Disable EXTI Line interrupt on the LPTIM Wake-up Timer */
1365 __HAL_LPTIM_WAKEUPTIMER_EXTI_DISABLE_IT();
1367 /* Disable the Peripheral */
1368 __HAL_LPTIM_DISABLE(hlptim);
1370 /* Disable Autoreload write complete interrupt */
1371 __HAL_LPTIM_DISABLE_IT(hlptim, LPTIM_IT_ARROK);
1373 /* Disable Autoreload match interrupt */
1374 __HAL_LPTIM_DISABLE_IT(hlptim, LPTIM_IT_ARRM);
1376 /* Change the TIM state*/
1377 hlptim->State= HAL_LPTIM_STATE_READY;
1379 /* Return function status */
1380 return HAL_OK;
1384 * @}
1387 /** @defgroup LPTIM_Group3 LPTIM Read operation functions
1388 * @brief Read operation functions.
1390 @verbatim
1391 ==============================================================================
1392 ##### LPTIM Read operation functions #####
1393 ==============================================================================
1394 [..] This section provides LPTIM Reading functions.
1395 (+) Read the counter value.
1396 (+) Read the period (Auto-reload) value.
1397 (+) Read the pulse (Compare)value.
1398 @endverbatim
1399 * @{
1403 * @brief This function returns the current counter value.
1404 * @param hlptim: LPTIM handle
1405 * @retval Counter value.
1407 uint32_t HAL_LPTIM_ReadCounter(LPTIM_HandleTypeDef *hlptim)
1409 /* Check the parameters */
1410 assert_param(IS_LPTIM_INSTANCE(hlptim->Instance));
1412 return (hlptim->Instance->CNT);
1416 * @brief This function return the current Autoreload (Period) value.
1417 * @param hlptim: LPTIM handle
1418 * @retval Autoreload value.
1420 uint32_t HAL_LPTIM_ReadAutoReload(LPTIM_HandleTypeDef *hlptim)
1422 /* Check the parameters */
1423 assert_param(IS_LPTIM_INSTANCE(hlptim->Instance));
1425 return (hlptim->Instance->ARR);
1429 * @brief This function return the current Compare (Pulse) value.
1430 * @param hlptim: LPTIM handle
1431 * @retval Compare value.
1433 uint32_t HAL_LPTIM_ReadCompare(LPTIM_HandleTypeDef *hlptim)
1435 /* Check the parameters */
1436 assert_param(IS_LPTIM_INSTANCE(hlptim->Instance));
1438 return (hlptim->Instance->CMP);
1442 * @}
1447 /** @defgroup LPTIM_Group4 LPTIM IRQ handler
1448 * @brief LPTIM IRQ handler.
1450 @verbatim
1451 ==============================================================================
1452 ##### LPTIM IRQ handler #####
1453 ==============================================================================
1454 [..] This section provides LPTIM IRQ handler function.
1456 @endverbatim
1457 * @{
1461 * @brief This function handles LPTIM interrupt request.
1462 * @param hlptim: LPTIM handle
1463 * @retval None
1465 void HAL_LPTIM_IRQHandler(LPTIM_HandleTypeDef *hlptim)
1467 /* Compare match interrupt */
1468 if(__HAL_LPTIM_GET_FLAG(hlptim, LPTIM_FLAG_CMPM) != RESET)
1470 if(__HAL_LPTIM_GET_IT_SOURCE(hlptim, LPTIM_IT_CMPM) !=RESET)
1472 /* Clear Compare match flag */
1473 __HAL_LPTIM_CLEAR_FLAG(hlptim, LPTIM_FLAG_CMPM);
1474 /* Compare match Callback */
1475 HAL_LPTIM_CompareMatchCallback(hlptim);
1479 /* Autoreload match interrupt */
1480 if(__HAL_LPTIM_GET_FLAG(hlptim, LPTIM_FLAG_ARRM) != RESET)
1482 if(__HAL_LPTIM_GET_IT_SOURCE(hlptim, LPTIM_IT_ARRM) !=RESET)
1484 /* Clear Autoreload match flag */
1485 __HAL_LPTIM_CLEAR_FLAG(hlptim, LPTIM_FLAG_ARRM);
1486 /* Autoreload match Callback */
1487 HAL_LPTIM_AutoReloadMatchCallback(hlptim);
1491 /* Trigger detected interrupt */
1492 if(__HAL_LPTIM_GET_FLAG(hlptim, LPTIM_FLAG_EXTTRIG) != RESET)
1494 if(__HAL_LPTIM_GET_IT_SOURCE(hlptim, LPTIM_IT_EXTTRIG) !=RESET)
1496 /* Clear Trigger detected flag */
1497 __HAL_LPTIM_CLEAR_FLAG(hlptim, LPTIM_FLAG_EXTTRIG);
1498 /* Trigger detected callback */
1499 HAL_LPTIM_TriggerCallback(hlptim);
1503 /* Compare write interrupt */
1504 if(__HAL_LPTIM_GET_FLAG(hlptim, LPTIM_FLAG_CMPOK) != RESET)
1506 if(__HAL_LPTIM_GET_IT_SOURCE(hlptim, LPTIM_FLAG_CMPM) !=RESET)
1508 /* Clear Compare write flag */
1509 __HAL_LPTIM_CLEAR_FLAG(hlptim, LPTIM_FLAG_CMPOK);
1510 /* Compare write Callback */
1511 HAL_LPTIM_CompareWriteCallback(hlptim);
1515 /* Autoreload write interrupt */
1516 if(__HAL_LPTIM_GET_FLAG(hlptim, LPTIM_FLAG_ARROK) != RESET)
1518 if(__HAL_LPTIM_GET_IT_SOURCE(hlptim, LPTIM_IT_ARROK) !=RESET)
1520 /* Clear Autoreload write flag */
1521 __HAL_LPTIM_CLEAR_FLAG(hlptim, LPTIM_FLAG_ARROK);
1522 /* Autoreload write Callback */
1523 HAL_LPTIM_AutoReloadWriteCallback(hlptim);
1527 /* Direction counter changed from Down to Up interrupt */
1528 if(__HAL_LPTIM_GET_FLAG(hlptim, LPTIM_FLAG_UP) != RESET)
1530 if(__HAL_LPTIM_GET_IT_SOURCE(hlptim, LPTIM_IT_UP) !=RESET)
1532 /* Clear Direction counter changed from Down to Up flag */
1533 __HAL_LPTIM_CLEAR_FLAG(hlptim, LPTIM_FLAG_UP);
1534 /* Direction counter changed from Down to Up Callback */
1535 HAL_LPTIM_DirectionUpCallback(hlptim);
1539 /* Direction counter changed from Up to Down interrupt */
1540 if(__HAL_LPTIM_GET_FLAG(hlptim, LPTIM_FLAG_DOWN) != RESET)
1542 if(__HAL_LPTIM_GET_IT_SOURCE(hlptim, LPTIM_IT_DOWN) !=RESET)
1544 /* Clear Direction counter changed from Up to Down flag */
1545 __HAL_LPTIM_CLEAR_FLAG(hlptim, LPTIM_FLAG_DOWN);
1546 /* Direction counter changed from Up to Down Callback */
1547 HAL_LPTIM_DirectionDownCallback(hlptim);
1551 __HAL_LPTIM_WAKEUPTIMER_EXTI_CLEAR_FLAG();
1555 * @brief Compare match callback in non blocking mode
1556 * @param hlptim : LPTIM handle
1557 * @retval None
1559 __weak void HAL_LPTIM_CompareMatchCallback(LPTIM_HandleTypeDef *hlptim)
1561 /* Prevent unused argument(s) compilation warning */
1562 UNUSED(hlptim);
1564 /* NOTE : This function Should not be modified, when the callback is needed,
1565 the HAL_LPTIM_CompareMatchCallback could be implemented in the user file
1570 * @brief Autoreload match callback in non blocking mode
1571 * @param hlptim : LPTIM handle
1572 * @retval None
1574 __weak void HAL_LPTIM_AutoReloadMatchCallback(LPTIM_HandleTypeDef *hlptim)
1576 /* Prevent unused argument(s) compilation warning */
1577 UNUSED(hlptim);
1579 /* NOTE : This function Should not be modified, when the callback is needed,
1580 the HAL_LPTIM_AutoReloadMatchCallback could be implemented in the user file
1585 * @brief Trigger detected callback in non blocking mode
1586 * @param hlptim : LPTIM handle
1587 * @retval None
1589 __weak void HAL_LPTIM_TriggerCallback(LPTIM_HandleTypeDef *hlptim)
1591 /* Prevent unused argument(s) compilation warning */
1592 UNUSED(hlptim);
1594 /* NOTE : This function Should not be modified, when the callback is needed,
1595 the HAL_LPTIM_TriggerCallback could be implemented in the user file
1600 * @brief Compare write callback in non blocking mode
1601 * @param hlptim : LPTIM handle
1602 * @retval None
1604 __weak void HAL_LPTIM_CompareWriteCallback(LPTIM_HandleTypeDef *hlptim)
1606 /* Prevent unused argument(s) compilation warning */
1607 UNUSED(hlptim);
1609 /* NOTE : This function Should not be modified, when the callback is needed,
1610 the HAL_LPTIM_CompareWriteCallback could be implemented in the user file
1615 * @brief Autoreload write callback in non blocking mode
1616 * @param hlptim : LPTIM handle
1617 * @retval None
1619 __weak void HAL_LPTIM_AutoReloadWriteCallback(LPTIM_HandleTypeDef *hlptim)
1621 /* Prevent unused argument(s) compilation warning */
1622 UNUSED(hlptim);
1624 /* NOTE : This function Should not be modified, when the callback is needed,
1625 the HAL_LPTIM_AutoReloadWriteCallback could be implemented in the user file
1630 * @brief Direction counter changed from Down to Up callback in non blocking mode
1631 * @param hlptim : LPTIM handle
1632 * @retval None
1634 __weak void HAL_LPTIM_DirectionUpCallback(LPTIM_HandleTypeDef *hlptim)
1636 /* Prevent unused argument(s) compilation warning */
1637 UNUSED(hlptim);
1639 /* NOTE : This function Should not be modified, when the callback is needed,
1640 the HAL_LPTIM_DirectionUpCallback could be implemented in the user file
1645 * @brief Direction counter changed from Up to Down callback in non blocking mode
1646 * @param hlptim : LPTIM handle
1647 * @retval None
1649 __weak void HAL_LPTIM_DirectionDownCallback(LPTIM_HandleTypeDef *hlptim)
1651 /* Prevent unused argument(s) compilation warning */
1652 UNUSED(hlptim);
1654 /* NOTE : This function Should not be modified, when the callback is needed,
1655 the HAL_LPTIM_DirectionDownCallback could be implemented in the user file
1660 * @}
1663 /** @defgroup LPTIM_Group5 Peripheral State functions
1664 * @brief Peripheral State functions.
1666 @verbatim
1667 ==============================================================================
1668 ##### Peripheral State functions #####
1669 ==============================================================================
1670 [..]
1671 This subsection permits to get in run-time the status of the peripheral.
1673 @endverbatim
1674 * @{
1678 * @brief Returns the LPTIM state.
1679 * @param hlptim: LPTIM handle
1680 * @retval HAL state
1682 HAL_LPTIM_StateTypeDef HAL_LPTIM_GetState(LPTIM_HandleTypeDef *hlptim)
1684 return hlptim->State;
1688 * @}
1693 * @}
1696 #endif /* HAL_LPTIM_MODULE_ENABLED */
1698 * @}
1702 * @}
1705 /************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/