Set blackbox file handler to NULL after closing file
[inav.git] / lib / main / STM32H7 / Drivers / STM32H7xx_HAL_Driver / Src / stm32h7xx_hal_dts.c
blob119631744374f717b8c929d9c5ff918205cd6e22
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 /* Private macro -------------------------------------------------------------*/
80 /* Private variables ---------------------------------------------------------*/
81 /* Private function prototypes -----------------------------------------------*/
82 #if (USE_HAL_DTS_REGISTER_CALLBACKS == 1)
83 static void DTS_ResetCallback(DTS_HandleTypeDef *hdts);
84 #endif /* USE_HAL_DTS_REGISTER_CALLBACKS */
85 /* Exported functions --------------------------------------------------------*/
87 /** @defgroup DTS_Exported_Functions DTS Exported Functions
88 * @{
91 /** @defgroup DTS_Exported_Functions_Group1 Initialization/de-initialization functions
92 * @brief Initialization and de-initialization functions.
94 @verbatim
95 ===============================================================================
96 ##### Initialization and de-initialization functions #####
97 ===============================================================================
98 [..] This section provides functions to initialize and de-initialize comparators
100 @endverbatim
101 * @{
105 * @brief Initialize the DTS according to the specified
106 * parameters in the DTS_InitTypeDef and initialize the associated handle.
107 * @param hdts DTS handle
108 * @retval HAL status
110 HAL_StatusTypeDef HAL_DTS_Init(DTS_HandleTypeDef *hdts)
112 /* Check the DTS handle allocation */
113 if (hdts == NULL)
115 return HAL_ERROR;
118 /* Check the parameters */
119 assert_param(IS_DTS_ALL_INSTANCE(hdts->Instance));
120 assert_param(IS_DTS_QUICKMEAS(hdts->Init.QuickMeasure));
121 assert_param(IS_DTS_REFCLK(hdts->Init.RefClock));
122 assert_param(IS_DTS_TRIGGERINPUT(hdts->Init.TriggerInput));
123 assert_param(IS_DTS_SAMPLINGTIME(hdts->Init.SamplingTime));
124 assert_param(IS_DTS_THRESHOLD(hdts->Init.HighThreshold));
125 assert_param(IS_DTS_THRESHOLD(hdts->Init.LowThreshold));
127 if (hdts->State == HAL_DTS_STATE_RESET)
129 #if (USE_HAL_DTS_REGISTER_CALLBACKS == 1)
130 /* Reset interrupt callbacks to legacy weak callbacks */
131 DTS_ResetCallback(hdts);
133 if (hdts->MspInitCallback == NULL)
135 hdts->MspInitCallback = HAL_DTS_MspInit;
138 /* Init the low level hardware : GPIO, CLOCK, NVIC */
139 hdts->MspInitCallback(hdts);
140 #else
141 /* Init the low level hardware : GPIO, CLOCK, NVIC */
142 HAL_DTS_MspInit(hdts);
143 #endif /* USE_HAL_DTS_REGISTER_CALLBACKS */
146 /* Change the DTS state */
147 hdts->State = HAL_DTS_STATE_BUSY;
149 /* Check ramp coefficient */
150 if (hdts->Instance->RAMPVALR == 0UL)
152 return HAL_ERROR;
155 /* Check factory calibration temperature */
156 if (hdts->Instance->T0VALR1 == 0UL)
158 return HAL_ERROR;
161 /* Check Quick Measure option is enabled or disabled */
162 if (hdts->Init.QuickMeasure == DTS_QUICKMEAS_DISABLE)
164 /* Check Reference clock selection */
165 if (hdts->Init.RefClock == DTS_REFCLKSEL_PCLK)
167 assert_param(IS_DTS_DIVIDER_RATIO_NUMBER(hdts->Init.Divider));
169 /* Quick measurement mode disabled */
170 CLEAR_BIT(hdts->Instance->CFGR1, DTS_CFGR1_Q_MEAS_OPT);
172 else
174 /* DTS_QUICKMEAS_ENABLE shall be used only when the LSE clock is
175 selected as reference clock */
176 if (hdts->Init.RefClock != DTS_REFCLKSEL_LSE)
178 return HAL_ERROR;
181 /* Quick measurement mode enabled - no calibration needed */
182 SET_BIT(hdts->Instance->CFGR1, DTS_CFGR1_Q_MEAS_OPT);
185 /* set the DTS clk source */
186 if (hdts->Init.RefClock == DTS_REFCLKSEL_LSE)
188 SET_BIT(hdts->Instance->CFGR1, DTS_CFGR1_REFCLK_SEL);
190 else
192 CLEAR_BIT(hdts->Instance->CFGR1, DTS_CFGR1_REFCLK_SEL);
195 MODIFY_REG(hdts->Instance->CFGR1, DTS_CFGR1_HSREF_CLK_DIV, (hdts->Init.Divider << DTS_CFGR1_HSREF_CLK_DIV_Pos));
196 MODIFY_REG(hdts->Instance->CFGR1, DTS_CFGR1_TS1_SMP_TIME, hdts->Init.SamplingTime);
197 MODIFY_REG(hdts->Instance->CFGR1, DTS_CFGR1_TS1_INTRIG_SEL, hdts->Init.TriggerInput);
198 MODIFY_REG(hdts->Instance->ITR1, DTS_ITR1_TS1_HITTHD, (hdts->Init.HighThreshold << DTS_ITR1_TS1_HITTHD_Pos));
199 MODIFY_REG(hdts->Instance->ITR1, DTS_ITR1_TS1_LITTHD, hdts->Init.LowThreshold);
201 /* Change the DTS state */
202 hdts->State = HAL_DTS_STATE_READY;
204 return HAL_OK;
208 * @brief DeInitialize the DTS peripheral.
209 * @note Deinitialization cannot be performed if the DTS configuration is locked.
210 * To unlock the configuration, perform a system reset.
211 * @param hdts DTS handle
212 * @retval HAL status
214 HAL_StatusTypeDef HAL_DTS_DeInit(DTS_HandleTypeDef *hdts)
216 /* Check the DTS handle allocation */
217 if (hdts == NULL)
219 return HAL_ERROR;
222 /* Check the parameter */
223 assert_param(IS_DTS_ALL_INSTANCE(hdts->Instance));
225 /* Set DTS_CFGR register to reset value */
226 CLEAR_REG(hdts->Instance->CFGR1);
228 #if (USE_HAL_DTS_REGISTER_CALLBACKS == 1)
229 if (hdts->MspDeInitCallback == NULL)
231 hdts->MspDeInitCallback = HAL_DTS_MspDeInit;
234 /* DeInit the low level hardware: CLOCK, NVIC.*/
235 hdts->MspDeInitCallback(hdts);
236 #else
237 /* DeInit the low level hardware: CLOCK, NVIC.*/
238 HAL_DTS_MspDeInit(hdts);
239 #endif /* USE_HAL_DTS_REGISTER_CALLBACKS */
241 hdts->State = HAL_DTS_STATE_RESET;
243 return HAL_OK;
247 * @brief Initialize the DTS MSP.
248 * @param hdts DTS handle
249 * @retval None
251 __weak void HAL_DTS_MspInit(DTS_HandleTypeDef *hdts)
253 /* Prevent unused argument(s) compilation warning */
254 UNUSED(hdts);
256 /* NOTE : This function should not be modified, when the callback is needed,
257 the HAL_DTS_MspInit could be implemented in the user file
262 * @brief DeInitialize the DTS MSP.
263 * @param hdts DTS handle
264 * @retval None
266 __weak void HAL_DTS_MspDeInit(DTS_HandleTypeDef *hdts)
268 /* Prevent unused argument(s) compilation warning */
269 UNUSED(hdts);
271 /* NOTE : This function should not be modified, when the callback is needed,
272 the HAL_DTS_MspDeInit could be implemented in the user file
277 * @}
280 /** @defgroup DTS_Exported_Functions_Group2 Start-Stop operation functions
281 * @brief Start-Stop operation functions.
283 @verbatim
284 ===============================================================================
285 ##### DTS Start Stop operation functions #####
286 ===============================================================================
287 [..] This section provides functions allowing to:
288 (+) Start a DTS Sensor without interrupt.
289 (+) Stop a DTS Sensor without interrupt.
290 (+) Start a DTS Sensor with interrupt generation.
291 (+) Stop a DTS Sensor with interrupt generation.
293 @endverbatim
294 * @{
298 * @brief Start the DTS sensor.
299 * @param hdts DTS handle
300 * @retval HAL status
302 HAL_StatusTypeDef HAL_DTS_Start(DTS_HandleTypeDef *hdts)
304 uint32_t Ref_Time;
306 /* Check the DTS handle allocation */
307 if (hdts == NULL)
309 return HAL_ERROR;
312 if (hdts->State == HAL_DTS_STATE_READY)
314 hdts->State = HAL_DTS_STATE_BUSY;
316 /* Enable DTS sensor */
317 __HAL_DTS_ENABLE(hdts);
319 /* Get Start Tick*/
320 Ref_Time = HAL_GetTick();
322 /* Wait till TS1_RDY flag is set */
323 while (__HAL_DTS_GET_FLAG(hdts, DTS_FLAG_TS1_RDY) == RESET)
325 if ((HAL_GetTick() - Ref_Time) > DTS_DELAY_STARTUP)
327 return HAL_TIMEOUT;
331 if (__HAL_DTS_GET_TRIGGER(hdts) == DTS_TRIGGER_HW_NONE)
333 /* Start continuous measures */
334 SET_BIT(hdts->Instance->CFGR1, DTS_CFGR1_TS1_START);
336 /* Ensure start is taken into account */
337 HAL_Delay(TS_TIMEOUT_MS);
340 hdts->State = HAL_DTS_STATE_READY;
342 else
344 return HAL_BUSY;
347 return HAL_OK;
351 * @brief Stop the DTS Sensor.
352 * @param hdts DTS handle
353 * @retval HAL status
355 HAL_StatusTypeDef HAL_DTS_Stop(DTS_HandleTypeDef *hdts)
357 /* Check the DTS handle allocation */
358 if (hdts == NULL)
360 return HAL_ERROR;
363 if (hdts->State == HAL_DTS_STATE_READY)
365 hdts->State = HAL_DTS_STATE_BUSY;
367 if (__HAL_DTS_GET_TRIGGER(hdts) == DTS_TRIGGER_HW_NONE)
369 CLEAR_BIT(hdts->Instance->CFGR1, DTS_CFGR1_TS1_START);
372 /* Disable the selected DTS sensor */
373 __HAL_DTS_DISABLE(hdts);
375 hdts->State = HAL_DTS_STATE_READY;
377 else
379 return HAL_BUSY;
382 return HAL_OK;
386 * @brief Enable the interrupt(s) and start the DTS sensor
387 * @param hdts DTS handle
388 * @retval HAL status
390 HAL_StatusTypeDef HAL_DTS_Start_IT(DTS_HandleTypeDef *hdts)
392 uint32_t Ref_Time;
394 /* Check the DTS handle allocation */
395 if (hdts == NULL)
397 return HAL_ERROR;
400 if (hdts->State == HAL_DTS_STATE_READY)
402 hdts->State = HAL_DTS_STATE_BUSY;
404 /* On Asynchronous mode enable the asynchronous IT */
405 if (hdts->Init.RefClock == DTS_REFCLKSEL_LSE)
407 __HAL_DTS_ENABLE_IT(hdts, DTS_IT_TS1_AITE | DTS_IT_TS1_AITL | DTS_IT_TS1_AITH);
409 else
411 /* Enable the IT(s) */
412 __HAL_DTS_ENABLE_IT(hdts, DTS_IT_TS1_ITE | DTS_IT_TS1_ITL | DTS_IT_TS1_ITH);
415 /* Enable the selected DTS sensor */
416 __HAL_DTS_ENABLE(hdts);
418 /* Get Start Tick*/
419 Ref_Time = HAL_GetTick();
421 /* Wait till TS1_RDY flag is set */
422 while (__HAL_DTS_GET_FLAG(hdts, DTS_FLAG_TS1_RDY) == RESET)
424 if ((HAL_GetTick() - Ref_Time) > DTS_DELAY_STARTUP)
426 return HAL_TIMEOUT;
430 if (__HAL_DTS_GET_TRIGGER(hdts) == DTS_TRIGGER_HW_NONE)
432 /* Start continuous measures */
433 SET_BIT(hdts->Instance->CFGR1, DTS_CFGR1_TS1_START);
435 /* Ensure start is taken into account */
436 HAL_Delay(TS_TIMEOUT_MS);
439 hdts->State = HAL_DTS_STATE_READY;
441 else
443 return HAL_BUSY;
446 return HAL_OK;
450 * @brief Disable the interrupt(s) and stop the DTS sensor.
451 * @param hdts DTS handle
452 * @retval HAL status
454 HAL_StatusTypeDef HAL_DTS_Stop_IT(DTS_HandleTypeDef *hdts)
456 /* Check the DTS handle allocation */
457 if (hdts == NULL)
459 return HAL_ERROR;
462 if (hdts->State == HAL_DTS_STATE_READY)
464 hdts->State = HAL_DTS_STATE_BUSY;
466 /* On Asynchronous mode disable the asynchronous IT */
467 if (hdts->Init.RefClock == DTS_REFCLKSEL_LSE)
469 __HAL_DTS_DISABLE_IT(hdts, DTS_IT_TS1_AITE | DTS_IT_TS1_AITL | DTS_IT_TS1_AITH);
471 else
473 /* Disable the IT(s) */
474 __HAL_DTS_DISABLE_IT(hdts, DTS_IT_TS1_ITE | DTS_IT_TS1_ITL | DTS_IT_TS1_ITH);
477 if (__HAL_DTS_GET_TRIGGER(hdts) == DTS_TRIGGER_HW_NONE)
479 CLEAR_BIT(hdts->Instance->CFGR1, DTS_CFGR1_TS1_START);
482 /* Disable the selected DTS sensor */
483 __HAL_DTS_DISABLE(hdts);
485 hdts->State = HAL_DTS_STATE_READY;
487 else
489 return HAL_BUSY;
492 return HAL_OK;
496 * @brief Get temperature from DTS
497 * @param hdts DTS handle
498 * @param Temperature Temperature in deg C
499 * @note This function retrieves latest available measure
500 * @retval HAL status
502 HAL_StatusTypeDef HAL_DTS_GetTemperature(DTS_HandleTypeDef *hdts, int32_t *Temperature)
504 uint32_t freq_meas;
505 uint32_t samples;
506 uint32_t t0_temp;
507 uint32_t t0_freq;
508 uint32_t ramp_coeff;
510 if (hdts->State == HAL_DTS_STATE_READY)
512 hdts->State = HAL_DTS_STATE_BUSY;
514 /* Get the total number of samples */
515 samples = (hdts->Instance->DR & DTS_DR_TS1_MFREQ);
517 if ((hdts->Init.SamplingTime == 0UL) || (samples == 0UL))
519 hdts->State = HAL_DTS_STATE_READY;
520 return HAL_ERROR;
523 if ((hdts->Init.RefClock) == DTS_REFCLKSEL_LSE)
525 freq_meas = (LSE_VALUE * samples) / (hdts->Init.SamplingTime >> DTS_CFGR1_TS1_SMP_TIME_Pos); /* On Hz */
527 else
529 freq_meas = (HAL_RCCEx_GetD3PCLK1Freq() * (hdts->Init.SamplingTime >> DTS_CFGR1_TS1_SMP_TIME_Pos)) / samples; /* On Hz */
532 /* Read factory settings */
533 t0_temp = hdts->Instance->T0VALR1 >> DTS_T0VALR1_TS1_T0_Pos;
535 if (t0_temp == 0UL)
537 t0_temp = 30UL; /* 30 deg C */
539 else if (t0_temp == 1UL)
541 t0_temp = 110UL; /* 110 deg C */
543 else
545 hdts->State = HAL_DTS_STATE_READY;
546 return HAL_ERROR;
549 t0_freq = (hdts->Instance->T0VALR1 & DTS_T0VALR1_TS1_FMT0) * 100UL; /* Hz */
551 ramp_coeff = hdts->Instance->RAMPVALR & DTS_RAMPVALR_TS1_RAMP_COEFF; /* deg C/Hz */
553 if (ramp_coeff == 0UL)
555 hdts->State = HAL_DTS_STATE_READY;
556 return HAL_ERROR;
559 /* Figure out the temperature deg C */
560 *Temperature = (int32_t)t0_temp + (((int32_t)freq_meas - (int32_t)t0_freq) / (int32_t)ramp_coeff);
562 hdts->State = HAL_DTS_STATE_READY;
564 else
566 return HAL_BUSY;
569 return HAL_OK;
573 * @brief DTS sensor IRQ Handler.
574 * @param hdts DTS handle
575 * @retval None
577 void HAL_DTS_IRQHandler(DTS_HandleTypeDef *hdts)
579 /* Check end of measure Asynchronous IT */
580 if ((__HAL_DTS_GET_FLAG(hdts, DTS_FLAG_TS1_AITE)) != RESET)
582 __HAL_DTS_CLEAR_FLAG(hdts, DTS_FLAG_TS1_AITE);
584 #if (USE_HAL_DTS_REGISTER_CALLBACKS == 1)
585 hdts->AsyncEndCallback(hdts);
586 #else
587 HAL_DTS_AsyncEndCallback(hdts);
588 #endif /* USE_HAL_DTS_REGISTER_CALLBACKS */
591 /* Check low threshold Asynchronous IT */
592 if ((__HAL_DTS_GET_FLAG(hdts, DTS_FLAG_TS1_AITL)) != RESET)
594 __HAL_DTS_CLEAR_FLAG(hdts, DTS_FLAG_TS1_AITL);
596 #if (USE_HAL_DTS_REGISTER_CALLBACKS == 1)
597 hdts->AsyncLowCallback(hdts);
598 #else
599 HAL_DTS_AsyncLowCallback(hdts);
600 #endif /* USE_HAL_DTS_REGISTER_CALLBACKS */
603 /* Check high threshold Asynchronous IT */
604 if ((__HAL_DTS_GET_FLAG(hdts, DTS_FLAG_TS1_AITH)) != RESET)
606 __HAL_DTS_CLEAR_FLAG(hdts, DTS_FLAG_TS1_AITH);
608 #if (USE_HAL_DTS_REGISTER_CALLBACKS == 1)
609 hdts->AsyncHighCallback(hdts);
610 #else
611 HAL_DTS_AsyncHighCallback(hdts);
612 #endif /* USE_HAL_DTS_REGISTER_CALLBACKS */
615 /* Check end of measure IT */
616 if ((__HAL_DTS_GET_FLAG(hdts, DTS_FLAG_TS1_ITE)) != RESET)
618 __HAL_DTS_CLEAR_FLAG(hdts, DTS_FLAG_TS1_ITE);
620 #if (USE_HAL_DTS_REGISTER_CALLBACKS == 1)
621 hdts->EndCallback(hdts);
622 #else
623 HAL_DTS_EndCallback(hdts);
624 #endif /* USE_HAL_DTS_REGISTER_CALLBACKS */
627 /* Check low threshold IT */
628 if ((__HAL_DTS_GET_FLAG(hdts, DTS_FLAG_TS1_ITL)) != RESET)
630 __HAL_DTS_CLEAR_FLAG(hdts, DTS_FLAG_TS1_ITL);
632 #if (USE_HAL_DTS_REGISTER_CALLBACKS == 1)
633 hdts->LowCallback(hdts);
634 #else
635 HAL_DTS_LowCallback(hdts);
636 #endif /* USE_HAL_DTS_REGISTER_CALLBACKS */
639 /* Check high threshold IT */
640 if ((__HAL_DTS_GET_FLAG(hdts, DTS_FLAG_TS1_ITH)) != RESET)
642 __HAL_DTS_CLEAR_FLAG(hdts, DTS_FLAG_TS1_ITH);
644 #if (USE_HAL_DTS_REGISTER_CALLBACKS == 1)
645 hdts->HighCallback(hdts);
646 #else
647 HAL_DTS_HighCallback(hdts);
648 #endif /* USE_HAL_DTS_REGISTER_CALLBACKS */
653 * @brief DTS Sensor End measure callback.
654 * @param hdts DTS handle
655 * @retval None
657 __weak void HAL_DTS_EndCallback(DTS_HandleTypeDef *hdts)
659 /* Prevent unused argument(s) compilation warning */
660 UNUSED(hdts);
662 /* NOTE : This function should not be modified, when the callback is needed,
663 the HAL_DTS_EndCallback should be implemented in the user file
668 * @brief DTS Sensor low threshold measure callback.
669 * @param hdts DTS handle
670 * @retval None
672 __weak void HAL_DTS_LowCallback(DTS_HandleTypeDef *hdts)
674 /* Prevent unused argument(s) compilation warning */
675 UNUSED(hdts);
677 /* NOTE : This function should not be modified, when the callback is needed,
678 the HAL_DTS_LowCallback should be implemented in the user file
683 * @brief DTS Sensor high threshold measure callback.
684 * @param hdts DTS handle
685 * @retval None
687 __weak void HAL_DTS_HighCallback(DTS_HandleTypeDef *hdts)
689 /* Prevent unused argument(s) compilation warning */
690 UNUSED(hdts);
692 /* NOTE : This function should not be modified, when the callback is needed,
693 the HAL_DTS_HighCallback should be implemented in the user file
698 * @brief DTS Sensor asynchronous end measure callback.
699 * @param hdts DTS handle
700 * @retval None
702 __weak void HAL_DTS_AsyncEndCallback(DTS_HandleTypeDef *hdts)
704 /* Prevent unused argument(s) compilation warning */
705 UNUSED(hdts);
707 /* NOTE : This function should not be modified, when the callback is needed,
708 the HAL_DTS_AsyncEndCallback should be implemented in the user file
713 * @brief DTS Sensor asynchronous low threshold measure callback.
714 * @param hdts DTS handle
715 * @retval None
717 __weak void HAL_DTS_AsyncLowCallback(DTS_HandleTypeDef *hdts)
719 /* Prevent unused argument(s) compilation warning */
720 UNUSED(hdts);
722 /* NOTE : This function should not be modified, when the callback is needed,
723 the HAL_DTS_AsyncLowCallback should be implemented in the user file
728 * @brief DTS Sensor asynchronous high threshold measure callback.
729 * @param hdts DTS handle
730 * @retval None
732 __weak void HAL_DTS_AsyncHighCallback(DTS_HandleTypeDef *hdts)
734 /* Prevent unused argument(s) compilation warning */
735 UNUSED(hdts);
737 /* NOTE : This function should not be modified, when the callback is needed,
738 the HAL_DTS_AsyncHighCallback should be implemented in the user file
743 * @}
746 /** @defgroup DTS_Exported_Functions_Group3 Peripheral State functions
747 * @brief Peripheral State functions.
749 @verbatim
750 ===============================================================================
751 ##### Peripheral State functions #####
752 ===============================================================================
753 [..]
754 This subsection permits to get in run-time the status of the peripheral.
756 @endverbatim
757 * @{
761 * @brief Return the DTS handle state.
762 * @param hdts DTS handle
763 * @retval HAL state
765 HAL_DTS_StateTypeDef HAL_DTS_GetState(DTS_HandleTypeDef *hdts)
767 /* Check the DTS handle allocation */
768 if (hdts == NULL)
770 return HAL_DTS_STATE_RESET;
773 /* Return DTS handle state */
774 return hdts->State;
777 * @}
781 * @}
784 /* Private functions ---------------------------------------------------------*/
786 /** @defgroup DTS_Private_Functions DTS Private Functions
787 * @{
789 #if (USE_HAL_DTS_REGISTER_CALLBACKS == 1)
791 * @brief Reset interrupt callbacks to the legacy weak callbacks.
792 * @param hdts pointer to a DTS_HandleTypeDef structure that contains
793 * the configuration information for DTS module.
794 * @retval None
796 static void DTS_ResetCallback(DTS_HandleTypeDef *hdts)
798 /* Reset the DTS callback to the legacy weak callbacks */
799 hdts->DTS_EndCallback = HAL_DTS_EndCallback; /* End measure Callback */
800 hdts->DTS_LowCallback = HAL_DTS_LowCallback; /* low threshold Callback */
801 hdts->DTS_HighCallback = HAL_DTS_HighCallback; /* high threshold Callback */
802 hdts->DTS_AsyncEndCallback = HAL_DTS_AsyncEndCallback; /* Asynchronous end of measure Callback */
803 hdts->DTS_AsyncLowCallback = HAL_DTS_AsyncLowCallback; /* Asynchronous low threshold Callback */
804 hdts->DTS_AsyncHighCallback = HAL_DTS_AsyncHighCallback; /* Asynchronous high threshold Callback */
806 #endif /* USE_HAL_DTS_REGISTER_CALLBACKS */
808 * @}
812 * @}
815 #endif /* DTS */
817 #endif /* HAL_DTS_MODULE_ENABLED */
820 * @}
823 /************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/