Create release.yml
[betaflight.git] / lib / main / STM32H7 / Drivers / STM32H7xx_HAL_Driver / Src / stm32h7xx_hal_dts.c
blobe2774d19beb2e88f65b8c4012cfa5e790f6e8c3c
1 /**
2 ******************************************************************************
3 * @file stm32h7xx_hal_dts.c
4 * @author MCD Application Team
5 * @brief DTS HAL module driver.
6 * This file provides firmware functions to manage the following
7 * functionalities of the DTS 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 @verbatim
15 ================================================================================
16 ##### DTS Peripheral features #####
17 ================================================================================
19 [..]
20 The STM32h7xx device family integrate one DTS sensor interface :
23 ##### How to use this driver #####
24 ================================================================================
25 [..]
28 @endverbatim
29 ******************************************************************************
30 * @attention
32 * <h2><center>&copy; Copyright (c) 2017 STMicroelectronics.
33 * All rights reserved.</center></h2>
35 * This software component is licensed by ST under BSD 3-Clause license,
36 * the "License"; You may not use this file except in compliance with the
37 * License. You may obtain a copy of the License at:
38 * opensource.org/licenses/BSD-3-Clause
40 ******************************************************************************
43 /* Includes ------------------------------------------------------------------*/
44 #include "stm32h7xx_hal.h"
46 /** @addtogroup STM32H7xx_HAL_Driver
47 * @{
50 #ifdef HAL_DTS_MODULE_ENABLED
52 #if defined(DTS)
54 /** @defgroup DTS DTS
55 * @brief DTS HAL module driver
56 * @{
59 /* Private typedef -----------------------------------------------------------*/
60 /* Private define ------------------------------------------------------------*/
61 /** @addtogroup DTS_Private_Constants
62 * @{
65 /* @brief Delay for DTS startup time
66 * @note Delay required to get ready for DTS Block.
67 * @note Unit: ms
69 #define DTS_DELAY_STARTUP (1UL)
71 /* @brief DTS measure ready flag time out value.
72 * @note Maximal measurement time is when LSE is selected as ref_clock and
73 * maximal sampling time is used, taking calibration into account this
74 * is equivalent to ~620 us. Use 5 ms as arbitrary timeout
75 * @note Unit: ms
77 #define TS_TIMEOUT_MS (5UL)
79 /**
80 * @}
83 /* Private macro -------------------------------------------------------------*/
84 /* Private variables ---------------------------------------------------------*/
85 /* Private function prototypes -----------------------------------------------*/
86 #if (USE_HAL_DTS_REGISTER_CALLBACKS == 1)
87 static void DTS_ResetCallback(DTS_HandleTypeDef *hdts);
88 #endif /* USE_HAL_DTS_REGISTER_CALLBACKS */
89 /* Exported functions --------------------------------------------------------*/
91 /** @defgroup DTS_Exported_Functions DTS Exported Functions
92 * @{
95 /** @defgroup DTS_Exported_Functions_Group1 Initialization/de-initialization functions
96 * @brief Initialization and de-initialization functions.
98 @verbatim
99 ===============================================================================
100 ##### Initialization and de-initialization functions #####
101 ===============================================================================
102 [..] This section provides functions to initialize and de-initialize comparators
104 @endverbatim
105 * @{
109 * @brief Initialize the DTS according to the specified
110 * parameters in the DTS_InitTypeDef and initialize the associated handle.
111 * @param hdts DTS handle
112 * @retval HAL status
114 HAL_StatusTypeDef HAL_DTS_Init(DTS_HandleTypeDef *hdts)
116 /* Check the DTS handle allocation */
117 if (hdts == NULL)
119 return HAL_ERROR;
122 /* Check the parameters */
123 assert_param(IS_DTS_ALL_INSTANCE(hdts->Instance));
124 assert_param(IS_DTS_QUICKMEAS(hdts->Init.QuickMeasure));
125 assert_param(IS_DTS_REFCLK(hdts->Init.RefClock));
126 assert_param(IS_DTS_TRIGGERINPUT(hdts->Init.TriggerInput));
127 assert_param(IS_DTS_SAMPLINGTIME(hdts->Init.SamplingTime));
128 assert_param(IS_DTS_THRESHOLD(hdts->Init.HighThreshold));
129 assert_param(IS_DTS_THRESHOLD(hdts->Init.LowThreshold));
131 if (hdts->State == HAL_DTS_STATE_RESET)
133 #if (USE_HAL_DTS_REGISTER_CALLBACKS == 1)
134 /* Reset interrupt callbacks to legacy weak callbacks */
135 DTS_ResetCallback(hdts);
137 if (hdts->MspInitCallback == NULL)
139 hdts->MspInitCallback = HAL_DTS_MspInit;
142 /* Init the low level hardware : GPIO, CLOCK, NVIC */
143 hdts->MspInitCallback(hdts);
144 #else
145 /* Init the low level hardware : GPIO, CLOCK, NVIC */
146 HAL_DTS_MspInit(hdts);
147 #endif /* USE_HAL_DTS_REGISTER_CALLBACKS */
150 /* Change the DTS state */
151 hdts->State = HAL_DTS_STATE_BUSY;
153 /* Check ramp coefficient */
154 if (hdts->Instance->RAMPVALR == 0UL)
156 return HAL_ERROR;
159 /* Check factory calibration temperature */
160 if (hdts->Instance->T0VALR1 == 0UL)
162 return HAL_ERROR;
165 /* Check Quick Measure option is enabled or disabled */
166 if (hdts->Init.QuickMeasure == DTS_QUICKMEAS_DISABLE)
168 /* Check Reference clock selection */
169 if (hdts->Init.RefClock == DTS_REFCLKSEL_PCLK)
171 assert_param(IS_DTS_DIVIDER_RATIO_NUMBER(hdts->Init.Divider));
173 /* Quick measurement mode disabled */
174 CLEAR_BIT(hdts->Instance->CFGR1, DTS_CFGR1_Q_MEAS_OPT);
176 else
178 /* DTS_QUICKMEAS_ENABLE shall be used only when the LSE clock is
179 selected as reference clock */
180 if (hdts->Init.RefClock != DTS_REFCLKSEL_LSE)
182 return HAL_ERROR;
185 /* Quick measurement mode enabled - no calibration needed */
186 SET_BIT(hdts->Instance->CFGR1, DTS_CFGR1_Q_MEAS_OPT);
189 /* set the DTS clk source */
190 if (hdts->Init.RefClock == DTS_REFCLKSEL_LSE)
192 SET_BIT(hdts->Instance->CFGR1, DTS_CFGR1_REFCLK_SEL);
194 else
196 CLEAR_BIT(hdts->Instance->CFGR1, DTS_CFGR1_REFCLK_SEL);
199 MODIFY_REG(hdts->Instance->CFGR1, DTS_CFGR1_HSREF_CLK_DIV, (hdts->Init.Divider << DTS_CFGR1_HSREF_CLK_DIV_Pos));
200 MODIFY_REG(hdts->Instance->CFGR1, DTS_CFGR1_TS1_SMP_TIME, hdts->Init.SamplingTime);
201 MODIFY_REG(hdts->Instance->CFGR1, DTS_CFGR1_TS1_INTRIG_SEL, hdts->Init.TriggerInput);
202 MODIFY_REG(hdts->Instance->ITR1, DTS_ITR1_TS1_HITTHD, (hdts->Init.HighThreshold << DTS_ITR1_TS1_HITTHD_Pos));
203 MODIFY_REG(hdts->Instance->ITR1, DTS_ITR1_TS1_LITTHD, hdts->Init.LowThreshold);
205 /* Change the DTS state */
206 hdts->State = HAL_DTS_STATE_READY;
208 return HAL_OK;
212 * @brief DeInitialize the DTS peripheral.
213 * @note Deinitialization cannot be performed if the DTS configuration is locked.
214 * To unlock the configuration, perform a system reset.
215 * @param hdts DTS handle
216 * @retval HAL status
218 HAL_StatusTypeDef HAL_DTS_DeInit(DTS_HandleTypeDef *hdts)
220 /* Check the DTS handle allocation */
221 if (hdts == NULL)
223 return HAL_ERROR;
226 /* Check the parameter */
227 assert_param(IS_DTS_ALL_INSTANCE(hdts->Instance));
229 /* Set DTS_CFGR register to reset value */
230 CLEAR_REG(hdts->Instance->CFGR1);
232 #if (USE_HAL_DTS_REGISTER_CALLBACKS == 1)
233 if (hdts->MspDeInitCallback == NULL)
235 hdts->MspDeInitCallback = HAL_DTS_MspDeInit;
238 /* DeInit the low level hardware: CLOCK, NVIC.*/
239 hdts->MspDeInitCallback(hdts);
240 #else
241 /* DeInit the low level hardware: CLOCK, NVIC.*/
242 HAL_DTS_MspDeInit(hdts);
243 #endif /* USE_HAL_DTS_REGISTER_CALLBACKS */
245 hdts->State = HAL_DTS_STATE_RESET;
247 return HAL_OK;
251 * @brief Initialize the DTS MSP.
252 * @param hdts DTS handle
253 * @retval None
255 __weak void HAL_DTS_MspInit(DTS_HandleTypeDef *hdts)
257 /* Prevent unused argument(s) compilation warning */
258 UNUSED(hdts);
260 /* NOTE : This function should not be modified, when the callback is needed,
261 the HAL_DTS_MspInit could be implemented in the user file
266 * @brief DeInitialize the DTS MSP.
267 * @param hdts DTS handle
268 * @retval None
270 __weak void HAL_DTS_MspDeInit(DTS_HandleTypeDef *hdts)
272 /* Prevent unused argument(s) compilation warning */
273 UNUSED(hdts);
275 /* NOTE : This function should not be modified, when the callback is needed,
276 the HAL_DTS_MspDeInit could be implemented in the user file
281 * @}
284 /** @defgroup DTS_Exported_Functions_Group2 Start-Stop operation functions
285 * @brief Start-Stop operation functions.
287 @verbatim
288 ===============================================================================
289 ##### DTS Start Stop operation functions #####
290 ===============================================================================
291 [..] This section provides functions allowing to:
292 (+) Start a DTS Sensor without interrupt.
293 (+) Stop a DTS Sensor without interrupt.
294 (+) Start a DTS Sensor with interrupt generation.
295 (+) Stop a DTS Sensor with interrupt generation.
297 @endverbatim
298 * @{
302 * @brief Start the DTS sensor.
303 * @param hdts DTS handle
304 * @retval HAL status
306 HAL_StatusTypeDef HAL_DTS_Start(DTS_HandleTypeDef *hdts)
308 uint32_t Ref_Time;
310 /* Check the DTS handle allocation */
311 if (hdts == NULL)
313 return HAL_ERROR;
316 if (hdts->State == HAL_DTS_STATE_READY)
318 hdts->State = HAL_DTS_STATE_BUSY;
320 /* Enable DTS sensor */
321 __HAL_DTS_ENABLE(hdts);
323 /* Get Start Tick*/
324 Ref_Time = HAL_GetTick();
326 /* Wait till TS1_RDY flag is set */
327 while (__HAL_DTS_GET_FLAG(hdts, DTS_FLAG_TS1_RDY) == RESET)
329 if ((HAL_GetTick() - Ref_Time) > DTS_DELAY_STARTUP)
331 return HAL_TIMEOUT;
335 if (__HAL_DTS_GET_TRIGGER(hdts) == DTS_TRIGGER_HW_NONE)
337 /* Start continuous measures */
338 SET_BIT(hdts->Instance->CFGR1, DTS_CFGR1_TS1_START);
340 /* Ensure start is taken into account */
341 HAL_Delay(TS_TIMEOUT_MS);
344 hdts->State = HAL_DTS_STATE_READY;
346 else
348 return HAL_BUSY;
351 return HAL_OK;
355 * @brief Stop the DTS Sensor.
356 * @param hdts DTS handle
357 * @retval HAL status
359 HAL_StatusTypeDef HAL_DTS_Stop(DTS_HandleTypeDef *hdts)
361 /* Check the DTS handle allocation */
362 if (hdts == NULL)
364 return HAL_ERROR;
367 if (hdts->State == HAL_DTS_STATE_READY)
369 hdts->State = HAL_DTS_STATE_BUSY;
371 if (__HAL_DTS_GET_TRIGGER(hdts) == DTS_TRIGGER_HW_NONE)
373 CLEAR_BIT(hdts->Instance->CFGR1, DTS_CFGR1_TS1_START);
376 /* Disable the selected DTS sensor */
377 __HAL_DTS_DISABLE(hdts);
379 hdts->State = HAL_DTS_STATE_READY;
381 else
383 return HAL_BUSY;
386 return HAL_OK;
390 * @brief Enable the interrupt(s) and start the DTS sensor
391 * @param hdts DTS handle
392 * @retval HAL status
394 HAL_StatusTypeDef HAL_DTS_Start_IT(DTS_HandleTypeDef *hdts)
396 uint32_t Ref_Time;
398 /* Check the DTS handle allocation */
399 if (hdts == NULL)
401 return HAL_ERROR;
404 if (hdts->State == HAL_DTS_STATE_READY)
406 hdts->State = HAL_DTS_STATE_BUSY;
408 /* On Asynchronous mode enable the asynchronous IT */
409 if (hdts->Init.RefClock == DTS_REFCLKSEL_LSE)
411 __HAL_DTS_ENABLE_IT(hdts, DTS_IT_TS1_AITE | DTS_IT_TS1_AITL | DTS_IT_TS1_AITH);
413 else
415 /* Enable the IT(s) */
416 __HAL_DTS_ENABLE_IT(hdts, DTS_IT_TS1_ITE | DTS_IT_TS1_ITL | DTS_IT_TS1_ITH);
419 /* Enable the selected DTS sensor */
420 __HAL_DTS_ENABLE(hdts);
422 /* Get Start Tick*/
423 Ref_Time = HAL_GetTick();
425 /* Wait till TS1_RDY flag is set */
426 while (__HAL_DTS_GET_FLAG(hdts, DTS_FLAG_TS1_RDY) == RESET)
428 if ((HAL_GetTick() - Ref_Time) > DTS_DELAY_STARTUP)
430 return HAL_TIMEOUT;
434 if (__HAL_DTS_GET_TRIGGER(hdts) == DTS_TRIGGER_HW_NONE)
436 /* Start continuous measures */
437 SET_BIT(hdts->Instance->CFGR1, DTS_CFGR1_TS1_START);
439 /* Ensure start is taken into account */
440 HAL_Delay(TS_TIMEOUT_MS);
443 hdts->State = HAL_DTS_STATE_READY;
445 else
447 return HAL_BUSY;
450 return HAL_OK;
454 * @brief Disable the interrupt(s) and stop the DTS sensor.
455 * @param hdts DTS handle
456 * @retval HAL status
458 HAL_StatusTypeDef HAL_DTS_Stop_IT(DTS_HandleTypeDef *hdts)
460 /* Check the DTS handle allocation */
461 if (hdts == NULL)
463 return HAL_ERROR;
466 if (hdts->State == HAL_DTS_STATE_READY)
468 hdts->State = HAL_DTS_STATE_BUSY;
470 /* On Asynchronous mode disable the asynchronous IT */
471 if (hdts->Init.RefClock == DTS_REFCLKSEL_LSE)
473 __HAL_DTS_DISABLE_IT(hdts, DTS_IT_TS1_AITE | DTS_IT_TS1_AITL | DTS_IT_TS1_AITH);
475 else
477 /* Disable the IT(s) */
478 __HAL_DTS_DISABLE_IT(hdts, DTS_IT_TS1_ITE | DTS_IT_TS1_ITL | DTS_IT_TS1_ITH);
481 if (__HAL_DTS_GET_TRIGGER(hdts) == DTS_TRIGGER_HW_NONE)
483 CLEAR_BIT(hdts->Instance->CFGR1, DTS_CFGR1_TS1_START);
486 /* Disable the selected DTS sensor */
487 __HAL_DTS_DISABLE(hdts);
489 hdts->State = HAL_DTS_STATE_READY;
491 else
493 return HAL_BUSY;
496 return HAL_OK;
500 * @brief Get temperature from DTS
501 * @param hdts DTS handle
502 * @param Temperature Temperature in deg C
503 * @note This function retrieves latest available measure
504 * @retval HAL status
506 HAL_StatusTypeDef HAL_DTS_GetTemperature(DTS_HandleTypeDef *hdts, int32_t *Temperature)
508 uint32_t freq_meas;
509 uint32_t samples;
510 uint32_t t0_temp;
511 uint32_t t0_freq;
512 uint32_t ramp_coeff;
514 if (hdts->State == HAL_DTS_STATE_READY)
516 hdts->State = HAL_DTS_STATE_BUSY;
518 /* Get the total number of samples */
519 samples = (hdts->Instance->DR & DTS_DR_TS1_MFREQ);
521 if ((hdts->Init.SamplingTime == 0UL) || (samples == 0UL))
523 hdts->State = HAL_DTS_STATE_READY;
524 return HAL_ERROR;
527 if ((hdts->Init.RefClock) == DTS_REFCLKSEL_LSE)
529 freq_meas = (LSE_VALUE * samples) / (hdts->Init.SamplingTime >> DTS_CFGR1_TS1_SMP_TIME_Pos); /* On Hz */
531 else
533 freq_meas = (HAL_RCCEx_GetD3PCLK1Freq() * (hdts->Init.SamplingTime >> DTS_CFGR1_TS1_SMP_TIME_Pos)) / samples; /* On Hz */
536 /* Read factory settings */
537 t0_temp = hdts->Instance->T0VALR1 >> DTS_T0VALR1_TS1_T0_Pos;
539 if (t0_temp == 0UL)
541 t0_temp = 30UL; /* 30 deg C */
543 else if (t0_temp == 1UL)
545 t0_temp = 110UL; /* 110 deg C */
547 else
549 hdts->State = HAL_DTS_STATE_READY;
550 return HAL_ERROR;
553 t0_freq = (hdts->Instance->T0VALR1 & DTS_T0VALR1_TS1_FMT0) * 100UL; /* Hz */
555 ramp_coeff = hdts->Instance->RAMPVALR & DTS_RAMPVALR_TS1_RAMP_COEFF; /* deg C/Hz */
557 if (ramp_coeff == 0UL)
559 hdts->State = HAL_DTS_STATE_READY;
560 return HAL_ERROR;
563 /* Figure out the temperature deg C */
564 *Temperature = (int32_t)t0_temp + (((int32_t)freq_meas - (int32_t)t0_freq) / (int32_t)ramp_coeff);
566 hdts->State = HAL_DTS_STATE_READY;
568 else
570 return HAL_BUSY;
573 return HAL_OK;
577 * @brief DTS sensor IRQ Handler.
578 * @param hdts DTS handle
579 * @retval None
581 void HAL_DTS_IRQHandler(DTS_HandleTypeDef *hdts)
583 /* Check end of measure Asynchronous IT */
584 if ((__HAL_DTS_GET_FLAG(hdts, DTS_FLAG_TS1_AITE)) != RESET)
586 __HAL_DTS_CLEAR_FLAG(hdts, DTS_FLAG_TS1_AITE);
588 #if (USE_HAL_DTS_REGISTER_CALLBACKS == 1)
589 hdts->AsyncEndCallback(hdts);
590 #else
591 HAL_DTS_AsyncEndCallback(hdts);
592 #endif /* USE_HAL_DTS_REGISTER_CALLBACKS */
595 /* Check low threshold Asynchronous IT */
596 if ((__HAL_DTS_GET_FLAG(hdts, DTS_FLAG_TS1_AITL)) != RESET)
598 __HAL_DTS_CLEAR_FLAG(hdts, DTS_FLAG_TS1_AITL);
600 #if (USE_HAL_DTS_REGISTER_CALLBACKS == 1)
601 hdts->AsyncLowCallback(hdts);
602 #else
603 HAL_DTS_AsyncLowCallback(hdts);
604 #endif /* USE_HAL_DTS_REGISTER_CALLBACKS */
607 /* Check high threshold Asynchronous IT */
608 if ((__HAL_DTS_GET_FLAG(hdts, DTS_FLAG_TS1_AITH)) != RESET)
610 __HAL_DTS_CLEAR_FLAG(hdts, DTS_FLAG_TS1_AITH);
612 #if (USE_HAL_DTS_REGISTER_CALLBACKS == 1)
613 hdts->AsyncHighCallback(hdts);
614 #else
615 HAL_DTS_AsyncHighCallback(hdts);
616 #endif /* USE_HAL_DTS_REGISTER_CALLBACKS */
619 /* Check end of measure IT */
620 if ((__HAL_DTS_GET_FLAG(hdts, DTS_FLAG_TS1_ITE)) != RESET)
622 __HAL_DTS_CLEAR_FLAG(hdts, DTS_FLAG_TS1_ITE);
624 #if (USE_HAL_DTS_REGISTER_CALLBACKS == 1)
625 hdts->EndCallback(hdts);
626 #else
627 HAL_DTS_EndCallback(hdts);
628 #endif /* USE_HAL_DTS_REGISTER_CALLBACKS */
631 /* Check low threshold IT */
632 if ((__HAL_DTS_GET_FLAG(hdts, DTS_FLAG_TS1_ITL)) != RESET)
634 __HAL_DTS_CLEAR_FLAG(hdts, DTS_FLAG_TS1_ITL);
636 #if (USE_HAL_DTS_REGISTER_CALLBACKS == 1)
637 hdts->LowCallback(hdts);
638 #else
639 HAL_DTS_LowCallback(hdts);
640 #endif /* USE_HAL_DTS_REGISTER_CALLBACKS */
643 /* Check high threshold IT */
644 if ((__HAL_DTS_GET_FLAG(hdts, DTS_FLAG_TS1_ITH)) != RESET)
646 __HAL_DTS_CLEAR_FLAG(hdts, DTS_FLAG_TS1_ITH);
648 #if (USE_HAL_DTS_REGISTER_CALLBACKS == 1)
649 hdts->HighCallback(hdts);
650 #else
651 HAL_DTS_HighCallback(hdts);
652 #endif /* USE_HAL_DTS_REGISTER_CALLBACKS */
657 * @brief DTS Sensor End measure callback.
658 * @param hdts DTS handle
659 * @retval None
661 __weak void HAL_DTS_EndCallback(DTS_HandleTypeDef *hdts)
663 /* Prevent unused argument(s) compilation warning */
664 UNUSED(hdts);
666 /* NOTE : This function should not be modified, when the callback is needed,
667 the HAL_DTS_EndCallback should be implemented in the user file
672 * @brief DTS Sensor low threshold measure callback.
673 * @param hdts DTS handle
674 * @retval None
676 __weak void HAL_DTS_LowCallback(DTS_HandleTypeDef *hdts)
678 /* Prevent unused argument(s) compilation warning */
679 UNUSED(hdts);
681 /* NOTE : This function should not be modified, when the callback is needed,
682 the HAL_DTS_LowCallback should be implemented in the user file
687 * @brief DTS Sensor high threshold measure callback.
688 * @param hdts DTS handle
689 * @retval None
691 __weak void HAL_DTS_HighCallback(DTS_HandleTypeDef *hdts)
693 /* Prevent unused argument(s) compilation warning */
694 UNUSED(hdts);
696 /* NOTE : This function should not be modified, when the callback is needed,
697 the HAL_DTS_HighCallback should be implemented in the user file
702 * @brief DTS Sensor asynchronous end measure callback.
703 * @param hdts DTS handle
704 * @retval None
706 __weak void HAL_DTS_AsyncEndCallback(DTS_HandleTypeDef *hdts)
708 /* Prevent unused argument(s) compilation warning */
709 UNUSED(hdts);
711 /* NOTE : This function should not be modified, when the callback is needed,
712 the HAL_DTS_AsyncEndCallback should be implemented in the user file
717 * @brief DTS Sensor asynchronous low threshold measure callback.
718 * @param hdts DTS handle
719 * @retval None
721 __weak void HAL_DTS_AsyncLowCallback(DTS_HandleTypeDef *hdts)
723 /* Prevent unused argument(s) compilation warning */
724 UNUSED(hdts);
726 /* NOTE : This function should not be modified, when the callback is needed,
727 the HAL_DTS_AsyncLowCallback should be implemented in the user file
732 * @brief DTS Sensor asynchronous high threshold measure callback.
733 * @param hdts DTS handle
734 * @retval None
736 __weak void HAL_DTS_AsyncHighCallback(DTS_HandleTypeDef *hdts)
738 /* Prevent unused argument(s) compilation warning */
739 UNUSED(hdts);
741 /* NOTE : This function should not be modified, when the callback is needed,
742 the HAL_DTS_AsyncHighCallback should be implemented in the user file
747 * @}
750 /** @defgroup DTS_Exported_Functions_Group3 Peripheral State functions
751 * @brief Peripheral State functions.
753 @verbatim
754 ===============================================================================
755 ##### Peripheral State functions #####
756 ===============================================================================
757 [..]
758 This subsection permits to get in run-time the status of the peripheral.
760 @endverbatim
761 * @{
765 * @brief Return the DTS handle state.
766 * @param hdts DTS handle
767 * @retval HAL state
769 HAL_DTS_StateTypeDef HAL_DTS_GetState(DTS_HandleTypeDef *hdts)
771 /* Check the DTS handle allocation */
772 if (hdts == NULL)
774 return HAL_DTS_STATE_RESET;
777 /* Return DTS handle state */
778 return hdts->State;
781 * @}
785 * @}
788 /* Private functions ---------------------------------------------------------*/
790 /** @defgroup DTS_Private_Functions DTS Private Functions
791 * @{
793 #if (USE_HAL_DTS_REGISTER_CALLBACKS == 1)
795 * @brief Reset interrupt callbacks to the legacy weak callbacks.
796 * @param hdts pointer to a DTS_HandleTypeDef structure that contains
797 * the configuration information for DTS module.
798 * @retval None
800 static void DTS_ResetCallback(DTS_HandleTypeDef *hdts)
802 /* Reset the DTS callback to the legacy weak callbacks */
803 hdts->DTS_EndCallback = HAL_DTS_EndCallback; /* End measure Callback */
804 hdts->DTS_LowCallback = HAL_DTS_LowCallback; /* low threshold Callback */
805 hdts->DTS_HighCallback = HAL_DTS_HighCallback; /* high threshold Callback */
806 hdts->DTS_AsyncEndCallback = HAL_DTS_AsyncEndCallback; /* Asynchronous end of measure Callback */
807 hdts->DTS_AsyncLowCallback = HAL_DTS_AsyncLowCallback; /* Asynchronous low threshold Callback */
808 hdts->DTS_AsyncHighCallback = HAL_DTS_AsyncHighCallback; /* Asynchronous high threshold Callback */
810 #endif /* USE_HAL_DTS_REGISTER_CALLBACKS */
812 * @}
816 * @}
819 #endif /* DTS */
821 #endif /* HAL_DTS_MODULE_ENABLED */
824 * @}
827 /************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/