2 ******************************************************************************
3 * @file stm32h7xx_hal_comp.c
4 * @author MCD Application Team
5 * @brief COMP HAL module driver.
6 * This file provides firmware functions to manage the following
7 * functionalities of the COMP peripheral:
8 * + Initialization and de-initialization functions
9 * + Start/Stop operation functions in polling mode
10 * + Start/Stop operation functions in interrupt mode
11 * + Peripheral control functions
12 * + Peripheral state functions
14 ================================================================================
15 ##### COMP Peripheral features #####
16 ================================================================================
19 The STM32H7xx device family integrates two analog comparators instances
21 (#) The COMP input minus (inverting input) and input plus (non inverting input)
22 can be set to internal references or to GPIO pins
23 (refer to GPIO list in reference manual).
25 (#) The COMP output level is available using HAL_COMP_GetOutputLevel()
26 and can be redirected to other peripherals: GPIO pins (in mode
27 alternate functions for comparator), timers.
28 (refer to GPIO list in reference manual).
30 (#) Pairs of comparators instances can be combined in window mode
31 (2 consecutive instances odd and even COMP<x> and COMP<x+1>).
33 (#) The comparators have interrupt capability through the EXTI controller
34 with wake-up from sleep and stop modes:
35 (++) COMP1 is internally connected to EXTI Line 20
36 (++) COMP2 is internally connected to EXTI Line 21
39 From the corresponding IRQ handler, the right interrupt source can be retrieved
40 using macro __HAL_COMP_COMP1_EXTI_GET_FLAG() and __HAL_COMP_COMP2_EXTI_GET_FLAG().
44 ##### How to use this driver #####
45 ================================================================================
47 This driver provides functions to configure and program the comparator instances of
50 To use the comparator, perform the following steps:
52 (#) Initialize the COMP low level resources by implementing the HAL_COMP_MspInit():
53 (++) Configure the GPIO connected to comparator inputs plus and minus in analog mode
54 using HAL_GPIO_Init().
55 (++) If needed, configure the GPIO connected to comparator output in alternate function mode
56 using HAL_GPIO_Init().
57 (++) If required enable the COMP interrupt by configuring and enabling EXTI line in Interrupt mode and
58 selecting the desired sensitivity level using HAL_GPIO_Init() function. After that enable the comparator
59 interrupt vector using HAL_NVIC_EnableIRQ() function.
61 (#) Configure the comparator using HAL_COMP_Init() function:
62 (++) Select the input minus (inverting input)
63 (++) Select the input plus (non-inverting input)
64 (++) Select the hysteresis
65 (++) Select the blanking source
66 (++) Select the output polarity
67 (++) Select the power mode
68 (++) Select the window mode
69 -@@- HAL_COMP_Init() calls internally __HAL_RCC_SYSCFG_CLK_ENABLE()
70 to enable internal control clock of the comparators.
71 However, this is a legacy strategy.
72 Therefore, for compatibility anticipation, it is recommended to
73 implement __HAL_RCC_SYSCFG_CLK_ENABLE() in "HAL_COMP_MspInit()".
74 In STM32H7,COMP clock enable __HAL_RCC_COMP12_CLK_ENABLE() must
75 be implemented by user in "HAL_COMP_MspInit()".
76 (#) Reconfiguration on-the-fly of comparator can be done by calling again
77 function HAL_COMP_Init() with new input structure parameters values.
79 (#) Enable the comparator using HAL_COMP_Start() or HAL_COMP_Start_IT()to be enabled
80 with the interrupt through NVIC of the CPU.
81 Note: HAL_COMP_Start_IT() must be called after each interrupt otherwise the interrupt
82 mode will stay disabled.
84 (#) Use HAL_COMP_GetOutputLevel() or HAL_COMP_TriggerCallback()
85 functions to manage comparator outputs(output level or events)
87 (#) Disable the comparator using HAL_COMP_Stop() or HAL_COMP_Stop_IT()
88 to disable the interrupt too.
90 (#) De-initialize the comparator using HAL_COMP_DeInit() function.
92 (#) For safety purpose, comparator configuration can be locked using HAL_COMP_Lock() function.
93 The only way to unlock the comparator is a device hardware reset.
95 *** Callback registration ***
96 =============================================
99 The compilation flag USE_HAL_COMP_REGISTER_CALLBACKS, when set to 1,
100 allows the user to configure dynamically the driver callbacks.
101 Use Functions @ref HAL_COMP_RegisterCallback()
102 to register an interrupt callback.
105 Function @ref HAL_COMP_RegisterCallback() allows to register following callbacks:
106 (+) TriggerCallback : callback for COMP trigger.
107 (+) MspInitCallback : callback for Msp Init.
108 (+) MspDeInitCallback : callback for Msp DeInit.
109 This function takes as parameters the HAL peripheral handle, the Callback ID
110 and a pointer to the user callback function.
113 Use function @ref HAL_COMP_UnRegisterCallback to reset a callback to the default
117 @ref HAL_COMP_UnRegisterCallback takes as parameters the HAL peripheral handle,
119 This function allows to reset following callbacks:
120 (+) TriggerCallback : callback for COMP trigger.
121 (+) MspInitCallback : callback for Msp Init.
122 (+) MspDeInitCallback : callback for Msp DeInit.
125 By default, after the @ref HAL_COMP_Init() and when the state is @ref HAL_COMP_STATE_RESET
126 all callbacks are set to the corresponding weak functions:
127 example @ref HAL_COMP_TriggerCallback().
128 Exception done for MspInit and MspDeInit functions that are
129 reset to the legacy weak functions in the @ref HAL_COMP_Init()/ @ref HAL_COMP_DeInit() only when
130 these callbacks are null (not registered beforehand).
133 If MspInit or MspDeInit are not null, the @ref HAL_COMP_Init()/ @ref HAL_COMP_DeInit()
134 keep and use the user MspInit/MspDeInit callbacks (registered beforehand) whatever the state.
137 Callbacks can be registered/unregistered in @ref HAL_COMP_STATE_READY state only.
138 Exception done MspInit/MspDeInit functions that can be registered/unregistered
139 in @ref HAL_COMP_STATE_READY or @ref HAL_COMP_STATE_RESET state,
140 thus registered (user) MspInit/DeInit callbacks can be used during the Init/DeInit.
143 Then, the user first registers the MspInit/MspDeInit user callbacks
144 using @ref HAL_COMP_RegisterCallback() before calling @ref HAL_COMP_DeInit()
145 or @ref HAL_COMP_Init() function.
148 When the compilation flag USE_HAL_COMP_REGISTER_CALLBACKS is set to 0 or
149 not defined, the callback registration feature is not available and all callbacks
150 are set to the corresponding weak functions.
153 ******************************************************************************
155 Table 1. COMP inputs and output for STM32H7xx devices
156 +---------------------------------------------------------+
157 | | | COMP1 | COMP2 |
158 |----------------|----------------|-----------|-----------|
159 | | IO1 | PB0 | PE9 |
160 | Input plus | IO2 | PB2 | PE11 |
162 |----------------|----------------|-----------------------|
163 | | 1/4 VrefInt | Available | Available |
164 | | 1/2 VrefInt | Available | Available |
165 | | 3/4 VrefInt | Available | Available |
166 | Input minus | VrefInt | Available | Available |
167 | | DAC1 channel 1 | Available | Available |
168 | | DAC1 channel 2 | Available | Available |
169 | | IO1 | PB1 | PE10 |
170 | | IO2 | PC4 | PE7 |
174 +---------------------------------------------------------+
175 | Output | | PC5 (1) | PE8 (1) |
176 | | | PE12 (1) | PE13 (1) |
177 | | | TIM (2) | TIM (2) |
178 +---------------------------------------------------------+
179 (1) GPIO must be set to alternate function for comparator
180 (2) Comparators output to timers is set in timers instances.
182 ******************************************************************************
185 * <h2><center>© Copyright (c) 2017 STMicroelectronics.
186 * All rights reserved.</center></h2>
188 * This software component is licensed by ST under BSD 3-Clause license,
189 * the "License"; You may not use this file except in compliance with the
190 * License. You may obtain a copy of the License at:
191 * opensource.org/licenses/BSD-3-Clause
193 ******************************************************************************
196 /* Includes ------------------------------------------------------------------*/
197 #include "stm32h7xx_hal.h"
199 /** @addtogroup STM32H7xx_HAL_Driver
203 /** @defgroup COMP COMP
204 * @brief COMP HAL module driver
208 #ifdef HAL_COMP_MODULE_ENABLED
210 /* Private typedef -----------------------------------------------------------*/
211 /* Private define ------------------------------------------------------------*/
212 /** @addtogroup COMP_Private_Constants
216 /* Delay for COMP startup time. */
217 /* Note: Delay required to reach propagation delay specification. */
218 /* Literal set to maximum value (refer to device datasheet, */
219 /* parameter "tSTART"). */
221 #define COMP_DELAY_STARTUP_US (80UL) /*!< Delay for COMP startup time */
223 /* Delay for COMP voltage scaler stabilization time. */
224 /* Literal set to maximum value (refer to device datasheet, */
225 /* parameter "tSTART_SCALER"). */
227 #define COMP_DELAY_VOLTAGE_SCALER_STAB_US (200UL) /*!< Delay for COMP voltage scaler stabilization time */
234 /* Private macro -------------------------------------------------------------*/
235 /* Private variables ---------------------------------------------------------*/
236 /* Private function prototypes -----------------------------------------------*/
237 /* Exported functions --------------------------------------------------------*/
239 /** @defgroup COMP_Exported_Functions COMP Exported Functions
243 /** @defgroup COMP_Exported_Functions_Group1 Initialization/de-initialization functions
244 * @brief Initialization and de-initialization functions.
247 ===============================================================================
248 ##### Initialization and de-initialization functions #####
249 ===============================================================================
250 [..] This section provides functions to initialize and de-initialize comparators
257 * @brief Initialize the COMP according to the specified
258 * parameters in the COMP_InitTypeDef and initialize the associated handle.
259 * @note If the selected comparator is locked, initialization can't be performed.
260 * To unlock the configuration, perform a system reset.
261 * @param hcomp COMP handle
264 HAL_StatusTypeDef
HAL_COMP_Init(COMP_HandleTypeDef
*hcomp
)
268 uint32_t comp_voltage_scaler_initialized
; /* Value "0" is comparator voltage scaler is not initialized */
269 __IO
uint32_t wait_loop_index
= 0UL;
271 HAL_StatusTypeDef status
= HAL_OK
;
273 /* Check the COMP handle allocation and lock status */
278 else if(__HAL_COMP_IS_LOCKED(hcomp
))
284 /* Check the parameters */
285 assert_param(IS_COMP_ALL_INSTANCE(hcomp
->Instance
));
286 assert_param(IS_COMP_INPUT_PLUS(hcomp
->Instance
, hcomp
->Init
.NonInvertingInput
));
287 assert_param(IS_COMP_INPUT_MINUS(hcomp
->Instance
, hcomp
->Init
.InvertingInput
));
288 assert_param(IS_COMP_OUTPUTPOL(hcomp
->Init
.OutputPol
));
289 assert_param(IS_COMP_POWERMODE(hcomp
->Init
.Mode
));
290 assert_param(IS_COMP_HYSTERESIS(hcomp
->Init
.Hysteresis
));
291 assert_param(IS_COMP_BLANKINGSRCE(hcomp
->Init
.BlankingSrce
));
292 assert_param(IS_COMP_TRIGGERMODE(hcomp
->Init
.TriggerMode
));
293 assert_param(IS_COMP_WINDOWMODE(hcomp
->Init
.WindowMode
));
295 if(hcomp
->State
== HAL_COMP_STATE_RESET
)
297 /* Allocate lock resource and initialize it */
298 hcomp
->Lock
= HAL_UNLOCKED
;
300 /* Set COMP error code to none */
301 COMP_CLEAR_ERRORCODE(hcomp
);
303 #if (USE_HAL_COMP_REGISTER_CALLBACKS == 1)
304 /* Init the COMP Callback settings */
305 hcomp
->TriggerCallback
= HAL_COMP_TriggerCallback
; /* Legacy weak callback */
307 if (hcomp
->MspInitCallback
== NULL
)
309 hcomp
->MspInitCallback
= HAL_COMP_MspInit
; /* Legacy weak MspInit */
312 /* Init the low level hardware */
313 hcomp
->MspInitCallback(hcomp
);
315 /* Init the low level hardware */
316 HAL_COMP_MspInit(hcomp
);
317 #endif /* USE_HAL_COMP_REGISTER_CALLBACKS */
319 /* Memorize voltage scaler state before initialization */
320 comp_voltage_scaler_initialized
= READ_BIT(hcomp
->Instance
->CFGR
, COMP_CFGRx_SCALEN
);
322 /* Set COMP parameters */
323 /* Set INMSEL bits according to hcomp->Init.InvertingInput value */
324 /* Set INPSEL bits according to hcomp->Init.NonInvertingInput value */
325 /* Set BLANKING bits according to hcomp->Init.BlankingSrce value */
326 /* Set HYST bits according to hcomp->Init.Hysteresis value */
327 /* Set POLARITY bit according to hcomp->Init.OutputPol value */
328 /* Set POWERMODE bits according to hcomp->Init.Mode value */
330 tmp_csr
= (hcomp
->Init
.InvertingInput
| \
331 hcomp
->Init
.NonInvertingInput
| \
332 hcomp
->Init
.BlankingSrce
| \
333 hcomp
->Init
.Hysteresis
| \
334 hcomp
->Init
.OutputPol
| \
337 /* Set parameters in COMP register */
338 /* Note: Update all bits except read-only, lock and enable bits */
339 #if defined (COMP_CFGRx_INP2SEL)
340 MODIFY_REG(hcomp
->Instance
->CFGR
,
341 COMP_CFGRx_PWRMODE
| COMP_CFGRx_INMSEL
| COMP_CFGRx_INPSEL
|
342 COMP_CFGRx_INP2SEL
| COMP_CFGRx_WINMODE
| COMP_CFGRx_POLARITY
| COMP_CFGRx_HYST
|
343 COMP_CFGRx_BLANKING
| COMP_CFGRx_BRGEN
| COMP_CFGRx_SCALEN
,
347 MODIFY_REG(hcomp
->Instance
->CFGR
,
348 COMP_CFGRx_PWRMODE
| COMP_CFGRx_INMSEL
| COMP_CFGRx_INPSEL
|
349 COMP_CFGRx_WINMODE
| COMP_CFGRx_POLARITY
| COMP_CFGRx_HYST
|
350 COMP_CFGRx_BLANKING
| COMP_CFGRx_BRGEN
| COMP_CFGRx_SCALEN
,
354 /* Set window mode */
355 /* Note: Window mode bit is located into 1 out of the 2 pairs of COMP */
356 /* instances. Therefore, this function can update another COMP */
357 /* instance that the one currently selected. */
358 if(hcomp
->Init
.WindowMode
== COMP_WINDOWMODE_COMP1_INPUT_PLUS_COMMON
)
360 SET_BIT(hcomp
->Instance
->CFGR
, COMP_CFGRx_WINMODE
);
364 CLEAR_BIT(hcomp
->Instance
->CFGR
, COMP_CFGRx_WINMODE
);
366 /* Delay for COMP scaler bridge voltage stabilization */
367 /* Apply the delay if voltage scaler bridge is enabled for the first time */
368 if ((READ_BIT(hcomp
->Instance
->CFGR
, COMP_CFGRx_SCALEN
) != 0UL) &&
369 (comp_voltage_scaler_initialized
!= 0UL) )
371 /* Wait loop initialization and execution */
372 /* Note: Variable divided by 2 to compensate partially */
373 /* CPU processing cycles.*/
375 wait_loop_index
= (COMP_DELAY_VOLTAGE_SCALER_STAB_US
* (SystemCoreClock
/ (1000000UL * 2UL)));
377 while(wait_loop_index
!= 0UL)
383 /* Get the EXTI line corresponding to the selected COMP instance */
384 exti_line
= COMP_GET_EXTI_LINE(hcomp
->Instance
);
386 /* Manage EXTI settings */
387 if((hcomp
->Init
.TriggerMode
& (COMP_EXTI_IT
| COMP_EXTI_EVENT
)) != 0UL)
389 /* Configure EXTI rising edge */
390 if((hcomp
->Init
.TriggerMode
& COMP_EXTI_RISING
) != 0UL)
392 SET_BIT(EXTI
->RTSR1
, exti_line
);
396 CLEAR_BIT(EXTI
->RTSR1
, exti_line
);
399 /* Configure EXTI falling edge */
400 if((hcomp
->Init
.TriggerMode
& COMP_EXTI_FALLING
) != 0UL)
402 SET_BIT(EXTI
->FTSR1
, exti_line
);
406 CLEAR_BIT(EXTI
->FTSR1
, exti_line
);
409 #if !defined (CORE_CM4)
410 /* Clear COMP EXTI pending bit (if any) */
411 WRITE_REG(EXTI
->PR1
, exti_line
);
413 /* Configure EXTI event mode */
414 if((hcomp
->Init
.TriggerMode
& COMP_EXTI_EVENT
) != 0UL)
416 SET_BIT(EXTI
->EMR1
, exti_line
);
420 CLEAR_BIT(EXTI
->EMR1
, exti_line
);
423 /* Configure EXTI interrupt mode */
424 if((hcomp
->Init
.TriggerMode
& COMP_EXTI_IT
) != 0UL)
426 SET_BIT(EXTI
->IMR1
, exti_line
);
430 CLEAR_BIT(EXTI
->IMR1
, exti_line
);
435 /* Disable EXTI event mode */
436 CLEAR_BIT(EXTI
->EMR1
, exti_line
);
438 /* Disable EXTI interrupt mode */
439 CLEAR_BIT(EXTI
->IMR1
, exti_line
);
442 /* Clear COMP EXTI pending bit (if any) */
443 WRITE_REG(EXTI
->C2PR1
, exti_line
);
445 /* Configure EXTI event mode */
446 if((hcomp
->Init
.TriggerMode
& COMP_EXTI_EVENT
) != 0UL)
448 SET_BIT(EXTI
->C2EMR1
, exti_line
);
452 CLEAR_BIT(EXTI
->C2EMR1
, exti_line
);
455 /* Configure EXTI interrupt mode */
456 if((hcomp
->Init
.TriggerMode
& COMP_EXTI_IT
) != 0UL)
458 SET_BIT(EXTI
->C2IMR1
, exti_line
);
462 CLEAR_BIT(EXTI
->C2IMR1
, exti_line
);
467 /* Disable EXTI event mode */
468 CLEAR_BIT(EXTI
->C2EMR1
, exti_line
);
470 /* Disable EXTI interrupt mode */
471 CLEAR_BIT(EXTI
->C2IMR1
, exti_line
);
474 /* Set HAL COMP handle state */
475 /* Note: Transition from state reset to state ready, */
476 /* otherwise (coming from state ready or busy) no state update. */
477 if (hcomp
->State
== HAL_COMP_STATE_RESET
)
480 hcomp
->State
= HAL_COMP_STATE_READY
;
489 * @brief DeInitialize the COMP peripheral.
490 * @note Deinitialization cannot be performed if the COMP configuration is locked.
491 * To unlock the configuration, perform a system reset.
492 * @param hcomp COMP handle
495 HAL_StatusTypeDef
HAL_COMP_DeInit(COMP_HandleTypeDef
*hcomp
)
497 HAL_StatusTypeDef status
= HAL_OK
;
499 /* Check the COMP handle allocation and lock status */
504 else if(__HAL_COMP_IS_LOCKED(hcomp
))
510 /* Check the parameter */
511 assert_param(IS_COMP_ALL_INSTANCE(hcomp
->Instance
));
513 /* Set COMP_CFGR register to reset value */
514 WRITE_REG(hcomp
->Instance
->CFGR
, 0x00000000UL
);
516 #if (USE_HAL_COMP_REGISTER_CALLBACKS == 1)
517 if (hcomp
->MspDeInitCallback
== NULL
)
519 hcomp
->MspDeInitCallback
= HAL_COMP_MspDeInit
; /* Legacy weak MspDeInit */
522 /* DeInit the low level hardware */
523 hcomp
->MspDeInitCallback(hcomp
);
525 /* DeInit the low level hardware */
526 HAL_COMP_MspDeInit(hcomp
);
527 #endif /* USE_HAL_COMP_REGISTER_CALLBACKS */
529 /* Set HAL COMP handle state */
530 hcomp
->State
= HAL_COMP_STATE_RESET
;
540 * @brief Initialize the COMP MSP.
541 * @param hcomp COMP handle
544 __weak
void HAL_COMP_MspInit(COMP_HandleTypeDef
*hcomp
)
546 /* Prevent unused argument(s) compilation warning */
548 /* NOTE : This function should not be modified, when the callback is needed,
549 the HAL_COMP_MspInit could be implemented in the user file
554 * @brief DeInitialize the COMP MSP.
555 * @param hcomp COMP handle
558 __weak
void HAL_COMP_MspDeInit(COMP_HandleTypeDef
*hcomp
)
560 /* Prevent unused argument(s) compilation warning */
562 /* NOTE : This function should not be modified, when the callback is needed,
563 the HAL_COMP_MspDeInit could be implemented in the user file
567 #if (USE_HAL_COMP_REGISTER_CALLBACKS == 1)
569 * @brief Register a User COMP Callback
570 * To be used instead of the weak predefined callback
571 * @param hcomp Pointer to a COMP_HandleTypeDef structure that contains
572 * the configuration information for the specified COMP.
573 * @param CallbackID ID of the callback to be registered
574 * This parameter can be one of the following values:
575 * @arg @ref HAL_COMP_TRIGGER_CB_ID Trigger callback ID
576 * @arg @ref HAL_COMP_MSPINIT_CB_ID MspInit callback ID
577 * @arg @ref HAL_COMP_MSPDEINIT_CB_ID MspDeInit callback ID
578 * @param pCallback pointer to the Callback function
581 HAL_StatusTypeDef
HAL_COMP_RegisterCallback(COMP_HandleTypeDef
*hcomp
, HAL_COMP_CallbackIDTypeDef CallbackID
, pCOMP_CallbackTypeDef pCallback
)
583 HAL_StatusTypeDef status
= HAL_OK
;
585 if (pCallback
== NULL
)
587 /* Update the error code */
588 hcomp
->ErrorCode
|= HAL_COMP_ERROR_INVALID_CALLBACK
;
593 if (HAL_COMP_STATE_READY
== hcomp
->State
)
597 case HAL_COMP_TRIGGER_CB_ID
:
598 hcomp
->TriggerCallback
= pCallback
;
601 case HAL_COMP_MSPINIT_CB_ID
:
602 hcomp
->MspInitCallback
= pCallback
;
605 case HAL_COMP_MSPDEINIT_CB_ID
:
606 hcomp
->MspDeInitCallback
= pCallback
;
610 /* Update the error code */
611 hcomp
->ErrorCode
|= HAL_COMP_ERROR_INVALID_CALLBACK
;
613 /* Return error status */
618 else if (HAL_COMP_STATE_RESET
== hcomp
->State
)
622 case HAL_COMP_MSPINIT_CB_ID
:
623 hcomp
->MspInitCallback
= pCallback
;
626 case HAL_COMP_MSPDEINIT_CB_ID
:
627 hcomp
->MspDeInitCallback
= pCallback
;
631 /* Update the error code */
632 hcomp
->ErrorCode
|= HAL_COMP_ERROR_INVALID_CALLBACK
;
634 /* Return error status */
641 /* Update the error code */
642 hcomp
->ErrorCode
|= HAL_COMP_ERROR_INVALID_CALLBACK
;
644 /* Return error status */
652 * @brief Unregister a COMP Callback
653 * COMP callback is redirected to the weak predefined callback
654 * @param hcomp Pointer to a COMP_HandleTypeDef structure that contains
655 * the configuration information for the specified COMP.
656 * @param CallbackID ID of the callback to be unregistered
657 * This parameter can be one of the following values:
658 * @arg @ref HAL_COMP_TRIGGER_CB_ID Trigger callback ID
659 * @arg @ref HAL_COMP_MSPINIT_CB_ID MspInit callback ID
660 * @arg @ref HAL_COMP_MSPDEINIT_CB_ID MspDeInit callback ID
663 HAL_StatusTypeDef
HAL_COMP_UnRegisterCallback(COMP_HandleTypeDef
*hcomp
, HAL_COMP_CallbackIDTypeDef CallbackID
)
665 HAL_StatusTypeDef status
= HAL_OK
;
667 if (HAL_COMP_STATE_READY
== hcomp
->State
)
671 case HAL_COMP_TRIGGER_CB_ID
:
672 hcomp
->TriggerCallback
= HAL_COMP_TriggerCallback
; /* Legacy weak callback */
675 case HAL_COMP_MSPINIT_CB_ID
:
676 hcomp
->MspInitCallback
= HAL_COMP_MspInit
; /* Legacy weak MspInit */
679 case HAL_COMP_MSPDEINIT_CB_ID
:
680 hcomp
->MspDeInitCallback
= HAL_COMP_MspDeInit
; /* Legacy weak MspDeInit */
684 /* Update the error code */
685 hcomp
->ErrorCode
|= HAL_COMP_ERROR_INVALID_CALLBACK
;
687 /* Return error status */
692 else if (HAL_COMP_STATE_RESET
== hcomp
->State
)
696 case HAL_COMP_MSPINIT_CB_ID
:
697 hcomp
->MspInitCallback
= HAL_COMP_MspInit
; /* Legacy weak MspInit */
700 case HAL_COMP_MSPDEINIT_CB_ID
:
701 hcomp
->MspDeInitCallback
= HAL_COMP_MspDeInit
; /* Legacy weak MspDeInit */
705 /* Update the error code */
706 hcomp
->ErrorCode
|= HAL_COMP_ERROR_INVALID_CALLBACK
;
708 /* Return error status */
715 /* Update the error code */
716 hcomp
->ErrorCode
|= HAL_COMP_ERROR_INVALID_CALLBACK
;
718 /* Return error status */
725 #endif /* USE_HAL_COMP_REGISTER_CALLBACKS */
730 /** @defgroup COMP_Exported_Functions_Group2 Start-Stop operation functions
731 * @brief Start-Stop operation functions.
734 ===============================================================================
735 ##### IO operation functions #####
736 ===============================================================================
737 [..] This section provides functions allowing to:
738 (+) Start a Comparator instance without interrupt.
739 (+) Stop a Comparator instance without interrupt.
740 (+) Start a Comparator instance with interrupt generation.
741 (+) Stop a Comparator instance with interrupt generation.
748 * @brief Start the comparator.
749 * @param hcomp COMP handle
752 HAL_StatusTypeDef
HAL_COMP_Start(COMP_HandleTypeDef
*hcomp
)
754 __IO
uint32_t wait_loop_index
= 0UL;
756 HAL_StatusTypeDef status
= HAL_OK
;
758 /* Check the COMP handle allocation and lock status */
763 else if(__HAL_COMP_IS_LOCKED(hcomp
))
769 /* Check the parameter */
770 assert_param(IS_COMP_ALL_INSTANCE(hcomp
->Instance
));
772 if(hcomp
->State
== HAL_COMP_STATE_READY
)
774 /* Enable the selected comparator */
775 SET_BIT(hcomp
->Instance
->CFGR
, COMP_CFGRx_EN
);
777 /* Set HAL COMP handle state */
778 hcomp
->State
= HAL_COMP_STATE_BUSY
;
780 /* Delay for COMP startup time */
781 /* Wait loop initialization and execution */
782 /* Note: Variable divided by 2 to compensate partially */
783 /* CPU processing cycles. */
785 wait_loop_index
= (COMP_DELAY_STARTUP_US
* (SystemCoreClock
/ (1000000UL * 2UL)));
786 while(wait_loop_index
!= 0UL)
801 * @brief Stop the comparator.
802 * @param hcomp COMP handle
805 HAL_StatusTypeDef
HAL_COMP_Stop(COMP_HandleTypeDef
*hcomp
)
807 HAL_StatusTypeDef status
= HAL_OK
;
809 /* Check the COMP handle allocation and lock status */
814 else if(__HAL_COMP_IS_LOCKED(hcomp
))
820 /* Check the parameter */
821 assert_param(IS_COMP_ALL_INSTANCE(hcomp
->Instance
));
823 /* Check compliant states: HAL_COMP_STATE_READY or HAL_COMP_STATE_BUSY */
824 /* (all states except HAL_COMP_STATE_RESET and except locked status. */
825 if(hcomp
->State
!= HAL_COMP_STATE_RESET
)
828 /* Disable the selected comparator */
829 CLEAR_BIT(hcomp
->Instance
->CFGR
, COMP_CFGRx_EN
);
831 /* Set HAL COMP handle state */
832 hcomp
->State
= HAL_COMP_STATE_READY
;
844 * @brief Enable the interrupt and start the comparator.
845 * @param hcomp COMP handle
848 HAL_StatusTypeDef
HAL_COMP_Start_IT(COMP_HandleTypeDef
*hcomp
)
851 __IO
uint32_t wait_loop_index
= 0UL;
852 HAL_StatusTypeDef status
= HAL_OK
;
854 /* Check the COMP handle allocation and lock status */
859 else if(__HAL_COMP_IS_LOCKED(hcomp
))
865 /* Check the parameter */
866 assert_param(IS_COMP_ALL_INSTANCE(hcomp
->Instance
));
867 /* Set HAL COMP handle state */
868 if(hcomp
->State
== HAL_COMP_STATE_READY
)
871 /* Enable the selected comparator */
872 SET_BIT(hcomp
->Instance
->CFGR
, COMP_CFGRx_EN
);
873 /* Enable the Interrupt comparator */
874 SET_BIT(hcomp
->Instance
->CFGR
, COMP_CFGRx_ITEN
);
876 hcomp
->State
= HAL_COMP_STATE_BUSY
;
877 /* Delay for COMP startup time */
878 /* Wait loop initialization and execution */
879 /* Note: Variable divided by 2 to compensate partially */
880 /* CPU processing cycles. */
882 wait_loop_index
= (COMP_DELAY_STARTUP_US
* (SystemCoreClock
/ (1000000UL * 2UL)));
883 while(wait_loop_index
!= 0UL)
899 * @brief Disable the interrupt and Stop the comparator.
900 * @param hcomp COMP handle
903 HAL_StatusTypeDef
HAL_COMP_Stop_IT(COMP_HandleTypeDef
*hcomp
)
905 HAL_StatusTypeDef status
;
906 /* Disable the EXTI Line interrupt mode */
907 #if !defined (CORE_CM4)
908 CLEAR_BIT(EXTI
->IMR1
, COMP_GET_EXTI_LINE(hcomp
->Instance
));
910 CLEAR_BIT(EXTI
->C2IMR1
, COMP_GET_EXTI_LINE(hcomp
->Instance
));
912 /* Disable the Interrupt comparator */
913 CLEAR_BIT(hcomp
->Instance
->CFGR
, COMP_CFGRx_ITEN
);
915 status
= HAL_COMP_Stop(hcomp
);
922 * @brief Comparator IRQ Handler.
923 * @param hcomp COMP handle
926 void HAL_COMP_IRQHandler(COMP_HandleTypeDef
*hcomp
)
928 /* Get the EXTI line corresponding to the selected COMP instance */
929 uint32_t exti_line
= COMP_GET_EXTI_LINE(hcomp
->Instance
);
932 #if defined(DUAL_CORE)
933 /* EXTI line interrupt detected */
934 if (HAL_GetCurrentCPUID() == CM7_CPUID
)
936 /* Check COMP EXTI flag */
937 if(READ_BIT(EXTI
->PR1
, exti_line
) != 0UL)
939 /* Check whether comparator is in independent or window mode */
940 if(READ_BIT(COMP12_COMMON
->CFGR
, COMP_CFGRx_WINMODE
) != 0UL)
942 /* Clear COMP EXTI line pending bit of the pair of comparators */
943 /* in window mode. */
944 /* Note: Pair of comparators in window mode can both trig IRQ when */
945 /* input voltage is changing from "out of window" area */
946 /* (low or high ) to the other "out of window" area (high or low).*/
947 /* Both flags must be cleared to call comparator trigger */
948 /* callback is called once. */
949 WRITE_REG(EXTI
->PR1
, (COMP_EXTI_LINE_COMP1
| COMP_EXTI_LINE_COMP2
));
953 /* Clear COMP EXTI line pending bit */
954 WRITE_REG(EXTI
->PR1
, exti_line
);
957 /* COMP trigger user callback */
958 #if (USE_HAL_COMP_REGISTER_CALLBACKS == 1)
959 hcomp
->TriggerCallback(hcomp
);
961 HAL_COMP_TriggerCallback(hcomp
);
962 #endif /* USE_HAL_COMP_REGISTER_CALLBACKS */
969 /* Check COMP EXTI flag */
970 if(READ_BIT(EXTI
->C2PR1
, exti_line
) != 0UL)
972 /* Check whether comparator is in independent or window mode */
973 if(READ_BIT(COMP12_COMMON
->CFGR
, COMP_CFGRx_WINMODE
) != 0UL)
975 /* Clear COMP EXTI line pending bit of the pair of comparators */
976 /* in window mode. */
977 /* Note: Pair of comparators in window mode can both trig IRQ when */
978 /* input voltage is changing from "out of window" area */
979 /* (low or high ) to the other "out of window" area (high or low).*/
980 /* Both flags must be cleared to call comparator trigger */
981 /* callback is called once. */
982 WRITE_REG(EXTI
->C2PR1
, (COMP_EXTI_LINE_COMP1
| COMP_EXTI_LINE_COMP2
));
986 /* Clear COMP EXTI line pending bit */
987 WRITE_REG(EXTI
->C2PR1
, exti_line
);
990 /* COMP trigger user callback */
991 #if (USE_HAL_COMP_REGISTER_CALLBACKS == 1)
992 hcomp
->TriggerCallback(hcomp
);
994 HAL_COMP_TriggerCallback(hcomp
);
995 #endif /* USE_HAL_COMP_REGISTER_CALLBACKS */
1001 /* Check COMP EXTI flag */
1002 if(READ_BIT(EXTI
->PR1
, exti_line
) != 0UL)
1004 /* Check whether comparator is in independent or window mode */
1005 if(READ_BIT(COMP12_COMMON
->CFGR
, COMP_CFGRx_WINMODE
) != 0UL)
1007 /* Clear COMP EXTI line pending bit of the pair of comparators */
1008 /* in window mode. */
1009 /* Note: Pair of comparators in window mode can both trig IRQ when */
1010 /* input voltage is changing from "out of window" area */
1011 /* (low or high ) to the other "out of window" area (high or low).*/
1012 /* Both flags must be cleared to call comparator trigger */
1013 /* callback is called once. */
1014 WRITE_REG(EXTI
->PR1
, (COMP_EXTI_LINE_COMP1
| COMP_EXTI_LINE_COMP2
));
1018 /* Clear COMP EXTI line pending bit */
1019 WRITE_REG(EXTI
->PR1
, exti_line
);
1022 /* COMP trigger user callback */
1023 #if (USE_HAL_COMP_REGISTER_CALLBACKS == 1)
1024 hcomp
->TriggerCallback(hcomp
);
1026 HAL_COMP_TriggerCallback(hcomp
);
1027 #endif /* USE_HAL_COMP_REGISTER_CALLBACKS */
1029 #endif /*DUAL_CORE*/
1031 /* Get COMP interrupt source */
1032 if (__HAL_COMP_GET_IT_SOURCE(hcomp
, COMP_IT_EN
) != RESET
)
1035 if((__HAL_COMP_GET_FLAG( COMP_FLAG_C1I
)) != 0UL)
1037 /* Clear the COMP channel 1 interrupt flag */
1038 __HAL_COMP_CLEAR_C1IFLAG();
1040 /* Disable COMP interrupt */
1041 __HAL_COMP_DISABLE_IT(hcomp
,COMP_IT_EN
);
1044 if((__HAL_COMP_GET_FLAG( COMP_FLAG_C2I
)) != 0UL)
1046 /* Clear the COMP channel 2 interrupt flag */
1047 __HAL_COMP_CLEAR_C2IFLAG();
1049 /* Disable COMP interrupt */
1050 __HAL_COMP_DISABLE_IT(hcomp
,COMP_IT_EN
);
1054 /* Change COMP state */
1055 hcomp
->State
= HAL_COMP_STATE_READY
;
1057 /* COMP trigger user callback */
1058 #if (USE_HAL_COMP_REGISTER_CALLBACKS == 1)
1059 hcomp
->TriggerCallback(hcomp
);
1061 HAL_COMP_TriggerCallback(hcomp
);
1062 #endif /* USE_HAL_COMP_REGISTER_CALLBACKS */
1072 /** @defgroup COMP_Exported_Functions_Group3 Peripheral Control functions
1073 * @brief Management functions.
1076 ===============================================================================
1077 ##### Peripheral Control functions #####
1078 ===============================================================================
1080 This subsection provides a set of functions allowing to control the comparators.
1087 * @brief Lock the selected comparator configuration.
1088 * @note A system reset is required to unlock the comparator configuration.
1089 * @param hcomp COMP handle
1090 * @retval HAL status
1092 HAL_StatusTypeDef
HAL_COMP_Lock(COMP_HandleTypeDef
*hcomp
)
1094 HAL_StatusTypeDef status
= HAL_OK
;
1096 /* Check the COMP handle allocation and lock status */
1101 else if(__HAL_COMP_IS_LOCKED(hcomp
))
1107 /* Check the parameter */
1108 assert_param(IS_COMP_ALL_INSTANCE(hcomp
->Instance
));
1110 /* Set HAL COMP handle state */
1111 switch(hcomp
->State
)
1113 case HAL_COMP_STATE_RESET
:
1114 hcomp
->State
= HAL_COMP_STATE_RESET_LOCKED
;
1116 case HAL_COMP_STATE_READY
:
1117 hcomp
->State
= HAL_COMP_STATE_READY_LOCKED
;
1119 default: /* HAL_COMP_STATE_BUSY */
1120 hcomp
->State
= HAL_COMP_STATE_BUSY_LOCKED
;
1125 if(status
== HAL_OK
)
1127 /* Set the lock bit corresponding to selected comparator */
1128 __HAL_COMP_LOCK(hcomp
);
1135 * @brief Return the output level (high or low) of the selected comparator.
1136 * @note The output level depends on the selected polarity.
1137 * If the polarity is not inverted:
1138 * - Comparator output is low when the input plus is at a lower
1139 * voltage than the input minus
1140 * - Comparator output is high when the input plus is at a higher
1141 * voltage than the input minus
1142 * If the polarity is inverted:
1143 * - Comparator output is high when the input plus is at a lower
1144 * voltage than the input minus
1145 * - Comparator output is low when the input plus is at a higher
1146 * voltage than the input minus
1147 * @param hcomp COMP handle
1148 * @retval Returns the selected comparator output level:
1149 * @arg @ref COMP_OUTPUT_LEVEL_LOW
1150 * @arg @ref COMP_OUTPUT_LEVEL_HIGH
1153 uint32_t HAL_COMP_GetOutputLevel(COMP_HandleTypeDef
*hcomp
)
1155 /* Check the parameter */
1156 assert_param(IS_COMP_ALL_INSTANCE(hcomp
->Instance
));
1158 if (hcomp
->Instance
== COMP1
)
1160 return (uint32_t)(READ_BIT(COMP12
->SR
, COMP_SR_C1VAL
));
1164 return (uint32_t)((READ_BIT(COMP12
->SR
, COMP_SR_C2VAL
))>> 1UL);
1169 * @brief Comparator trigger callback.
1170 * @param hcomp COMP handle
1173 __weak
void HAL_COMP_TriggerCallback(COMP_HandleTypeDef
*hcomp
)
1175 /* Prevent unused argument(s) compilation warning */
1177 /* NOTE : This function should not be modified, when the callback is needed,
1178 the HAL_COMP_TriggerCallback should be implemented in the user file
1187 /** @defgroup COMP_Exported_Functions_Group4 Peripheral State functions
1188 * @brief Peripheral State functions.
1191 ===============================================================================
1192 ##### Peripheral State functions #####
1193 ===============================================================================
1195 This subsection permit to get in run-time the status of the peripheral.
1202 * @brief Return the COMP handle state.
1203 * @param hcomp COMP handle
1206 HAL_COMP_StateTypeDef
HAL_COMP_GetState(COMP_HandleTypeDef
*hcomp
)
1208 /* Check the COMP handle allocation */
1211 return HAL_COMP_STATE_RESET
;
1214 /* Check the parameter */
1215 assert_param(IS_COMP_ALL_INSTANCE(hcomp
->Instance
));
1217 /* Return HAL COMP handle state */
1218 return hcomp
->State
;
1222 * @brief Return the COMP error code.
1223 * @param hcomp COMP handle
1224 * @retval COMP error code
1226 uint32_t HAL_COMP_GetError(COMP_HandleTypeDef
*hcomp
)
1228 /* Check the parameters */
1229 assert_param(IS_COMP_ALL_INSTANCE(hcomp
->Instance
));
1231 return hcomp
->ErrorCode
;
1241 #endif /* HAL_COMP_MODULE_ENABLED */
1250 /************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/