2 ******************************************************************************
3 * @file stm32h7xx_hal_dfsdm.h
4 * @author MCD Application Team
5 * @brief Header file of DFSDM HAL module.
6 ******************************************************************************
9 * <h2><center>© Copyright (c) 2017 STMicroelectronics.
10 * All rights reserved.</center></h2>
12 * This software component is licensed by ST under BSD 3-Clause license,
13 * the "License"; You may not use this file except in compliance with the
14 * License. You may obtain a copy of the License at:
15 * opensource.org/licenses/BSD-3-Clause
17 ******************************************************************************
20 /* Define to prevent recursive inclusion -------------------------------------*/
21 #ifndef STM32H7xx_HAL_DFSDM_H
22 #define STM32H7xx_HAL_DFSDM_H
28 /* Includes ------------------------------------------------------------------*/
29 #include "stm32h7xx_hal_def.h"
31 /** @addtogroup STM32H7xx_HAL_Driver
39 /* Exported types ------------------------------------------------------------*/
40 /** @defgroup DFSDM_Exported_Types DFSDM Exported Types
45 * @brief HAL DFSDM Channel states definition
49 HAL_DFSDM_CHANNEL_STATE_RESET
= 0x00U
, /*!< DFSDM channel not initialized */
50 HAL_DFSDM_CHANNEL_STATE_READY
= 0x01U
, /*!< DFSDM channel initialized and ready for use */
51 HAL_DFSDM_CHANNEL_STATE_ERROR
= 0xFFU
/*!< DFSDM channel state error */
52 } HAL_DFSDM_Channel_StateTypeDef
;
55 * @brief DFSDM channel output clock structure definition
59 FunctionalState Activation
; /*!< Output clock enable/disable */
60 uint32_t Selection
; /*!< Output clock is system clock or audio clock.
61 This parameter can be a value of @ref DFSDM_Channel_OuputClock */
62 uint32_t Divider
; /*!< Output clock divider.
63 This parameter must be a number between Min_Data = 2 and Max_Data = 256 */
64 } DFSDM_Channel_OutputClockTypeDef
;
67 * @brief DFSDM channel input structure definition
71 uint32_t Multiplexer
; /*!< Input is external serial inputs, internal register or ADC output.
72 This parameter can be a value of @ref DFSDM_Channel_InputMultiplexer */
73 uint32_t DataPacking
; /*!< Standard, interleaved or dual mode for internal register.
74 This parameter can be a value of @ref DFSDM_Channel_DataPacking */
75 uint32_t Pins
; /*!< Input pins are taken from same or following channel.
76 This parameter can be a value of @ref DFSDM_Channel_InputPins */
77 } DFSDM_Channel_InputTypeDef
;
80 * @brief DFSDM channel serial interface structure definition
84 uint32_t Type
; /*!< SPI or Manchester modes.
85 This parameter can be a value of @ref DFSDM_Channel_SerialInterfaceType */
86 uint32_t SpiClock
; /*!< SPI clock select (external or internal with different sampling point).
87 This parameter can be a value of @ref DFSDM_Channel_SpiClock */
88 } DFSDM_Channel_SerialInterfaceTypeDef
;
91 * @brief DFSDM channel analog watchdog structure definition
95 uint32_t FilterOrder
; /*!< Analog watchdog Sinc filter order.
96 This parameter can be a value of @ref DFSDM_Channel_AwdFilterOrder */
97 uint32_t Oversampling
; /*!< Analog watchdog filter oversampling ratio.
98 This parameter must be a number between Min_Data = 1 and Max_Data = 32 */
99 } DFSDM_Channel_AwdTypeDef
;
102 * @brief DFSDM channel init structure definition
106 DFSDM_Channel_OutputClockTypeDef OutputClock
; /*!< DFSDM channel output clock parameters */
107 DFSDM_Channel_InputTypeDef Input
; /*!< DFSDM channel input parameters */
108 DFSDM_Channel_SerialInterfaceTypeDef SerialInterface
; /*!< DFSDM channel serial interface parameters */
109 DFSDM_Channel_AwdTypeDef Awd
; /*!< DFSDM channel analog watchdog parameters */
110 int32_t Offset
; /*!< DFSDM channel offset.
111 This parameter must be a number between Min_Data = -8388608 and Max_Data = 8388607 */
112 uint32_t RightBitShift
; /*!< DFSDM channel right bit shift.
113 This parameter must be a number between Min_Data = 0x00 and Max_Data = 0x1F */
114 } DFSDM_Channel_InitTypeDef
;
117 * @brief DFSDM channel handle structure definition
119 #if (USE_HAL_DFSDM_REGISTER_CALLBACKS == 1)
120 typedef struct __DFSDM_Channel_HandleTypeDef
123 #endif /* USE_HAL_DFSDM_REGISTER_CALLBACKS */
125 DFSDM_Channel_TypeDef
*Instance
; /*!< DFSDM channel instance */
126 DFSDM_Channel_InitTypeDef Init
; /*!< DFSDM channel init parameters */
127 HAL_DFSDM_Channel_StateTypeDef State
; /*!< DFSDM channel state */
128 #if (USE_HAL_DFSDM_REGISTER_CALLBACKS == 1)
129 void (*CkabCallback
) (struct __DFSDM_Channel_HandleTypeDef
*hdfsdm_channel
); /*!< DFSDM channel clock absence detection callback */
130 void (*ScdCallback
) (struct __DFSDM_Channel_HandleTypeDef
*hdfsdm_channel
); /*!< DFSDM channel short circuit detection callback */
131 void (*MspInitCallback
) (struct __DFSDM_Channel_HandleTypeDef
*hdfsdm_channel
); /*!< DFSDM channel MSP init callback */
132 void (*MspDeInitCallback
) (struct __DFSDM_Channel_HandleTypeDef
*hdfsdm_channel
); /*!< DFSDM channel MSP de-init callback */
134 } DFSDM_Channel_HandleTypeDef
;
136 #if (USE_HAL_DFSDM_REGISTER_CALLBACKS == 1)
138 * @brief DFSDM channel callback ID enumeration definition
142 HAL_DFSDM_CHANNEL_CKAB_CB_ID
= 0x00U
, /*!< DFSDM channel clock absence detection callback ID */
143 HAL_DFSDM_CHANNEL_SCD_CB_ID
= 0x01U
, /*!< DFSDM channel short circuit detection callback ID */
144 HAL_DFSDM_CHANNEL_MSPINIT_CB_ID
= 0x02U
, /*!< DFSDM channel MSP init callback ID */
145 HAL_DFSDM_CHANNEL_MSPDEINIT_CB_ID
= 0x03U
/*!< DFSDM channel MSP de-init callback ID */
146 } HAL_DFSDM_Channel_CallbackIDTypeDef
;
149 * @brief DFSDM channel callback pointer definition
151 typedef void (*pDFSDM_Channel_CallbackTypeDef
)(DFSDM_Channel_HandleTypeDef
*hdfsdm_channel
);
155 * @brief HAL DFSDM Filter states definition
159 HAL_DFSDM_FILTER_STATE_RESET
= 0x00U
, /*!< DFSDM filter not initialized */
160 HAL_DFSDM_FILTER_STATE_READY
= 0x01U
, /*!< DFSDM filter initialized and ready for use */
161 HAL_DFSDM_FILTER_STATE_REG
= 0x02U
, /*!< DFSDM filter regular conversion in progress */
162 HAL_DFSDM_FILTER_STATE_INJ
= 0x03U
, /*!< DFSDM filter injected conversion in progress */
163 HAL_DFSDM_FILTER_STATE_REG_INJ
= 0x04U
, /*!< DFSDM filter regular and injected conversions in progress */
164 HAL_DFSDM_FILTER_STATE_ERROR
= 0xFFU
/*!< DFSDM filter state error */
165 } HAL_DFSDM_Filter_StateTypeDef
;
168 * @brief DFSDM filter regular conversion parameters structure definition
172 uint32_t Trigger
; /*!< Trigger used to start regular conversion: software or synchronous.
173 This parameter can be a value of @ref DFSDM_Filter_Trigger */
174 FunctionalState FastMode
; /*!< Enable/disable fast mode for regular conversion */
175 FunctionalState DmaMode
; /*!< Enable/disable DMA for regular conversion */
176 } DFSDM_Filter_RegularParamTypeDef
;
179 * @brief DFSDM filter injected conversion parameters structure definition
183 uint32_t Trigger
; /*!< Trigger used to start injected conversion: software, external or synchronous.
184 This parameter can be a value of @ref DFSDM_Filter_Trigger */
185 FunctionalState ScanMode
; /*!< Enable/disable scanning mode for injected conversion */
186 FunctionalState DmaMode
; /*!< Enable/disable DMA for injected conversion */
187 uint32_t ExtTrigger
; /*!< External trigger.
188 This parameter can be a value of @ref DFSDM_Filter_ExtTrigger */
189 uint32_t ExtTriggerEdge
; /*!< External trigger edge: rising, falling or both.
190 This parameter can be a value of @ref DFSDM_Filter_ExtTriggerEdge */
191 } DFSDM_Filter_InjectedParamTypeDef
;
194 * @brief DFSDM filter parameters structure definition
198 uint32_t SincOrder
; /*!< Sinc filter order.
199 This parameter can be a value of @ref DFSDM_Filter_SincOrder */
200 uint32_t Oversampling
; /*!< Filter oversampling ratio.
201 This parameter must be a number between Min_Data = 1 and Max_Data = 1024 */
202 uint32_t IntOversampling
; /*!< Integrator oversampling ratio.
203 This parameter must be a number between Min_Data = 1 and Max_Data = 256 */
204 } DFSDM_Filter_FilterParamTypeDef
;
207 * @brief DFSDM filter init structure definition
211 DFSDM_Filter_RegularParamTypeDef RegularParam
; /*!< DFSDM regular conversion parameters */
212 DFSDM_Filter_InjectedParamTypeDef InjectedParam
; /*!< DFSDM injected conversion parameters */
213 DFSDM_Filter_FilterParamTypeDef FilterParam
; /*!< DFSDM filter parameters */
214 } DFSDM_Filter_InitTypeDef
;
217 * @brief DFSDM filter handle structure definition
219 #if (USE_HAL_DFSDM_REGISTER_CALLBACKS == 1)
220 typedef struct __DFSDM_Filter_HandleTypeDef
223 #endif /* USE_HAL_DFSDM_REGISTER_CALLBACKS */
225 DFSDM_Filter_TypeDef
*Instance
; /*!< DFSDM filter instance */
226 DFSDM_Filter_InitTypeDef Init
; /*!< DFSDM filter init parameters */
227 DMA_HandleTypeDef
*hdmaReg
; /*!< Pointer on DMA handler for regular conversions */
228 DMA_HandleTypeDef
*hdmaInj
; /*!< Pointer on DMA handler for injected conversions */
229 uint32_t RegularContMode
; /*!< Regular conversion continuous mode */
230 uint32_t RegularTrigger
; /*!< Trigger used for regular conversion */
231 uint32_t InjectedTrigger
; /*!< Trigger used for injected conversion */
232 uint32_t ExtTriggerEdge
; /*!< Rising, falling or both edges selected */
233 FunctionalState InjectedScanMode
; /*!< Injected scanning mode */
234 uint32_t InjectedChannelsNbr
; /*!< Number of channels in injected sequence */
235 uint32_t InjConvRemaining
; /*!< Injected conversions remaining */
236 HAL_DFSDM_Filter_StateTypeDef State
; /*!< DFSDM filter state */
237 uint32_t ErrorCode
; /*!< DFSDM filter error code */
238 #if (USE_HAL_DFSDM_REGISTER_CALLBACKS == 1)
239 void (*AwdCallback
) (struct __DFSDM_Filter_HandleTypeDef
*hdfsdm_filter
,
240 uint32_t Channel
, uint32_t Threshold
); /*!< DFSDM filter analog watchdog callback */
241 void (*RegConvCpltCallback
) (struct __DFSDM_Filter_HandleTypeDef
*hdfsdm_filter
); /*!< DFSDM filter regular conversion complete callback */
242 void (*RegConvHalfCpltCallback
) (struct __DFSDM_Filter_HandleTypeDef
*hdfsdm_filter
); /*!< DFSDM filter half regular conversion complete callback */
243 void (*InjConvCpltCallback
) (struct __DFSDM_Filter_HandleTypeDef
*hdfsdm_filter
); /*!< DFSDM filter injected conversion complete callback */
244 void (*InjConvHalfCpltCallback
) (struct __DFSDM_Filter_HandleTypeDef
*hdfsdm_filter
); /*!< DFSDM filter half injected conversion complete callback */
245 void (*ErrorCallback
) (struct __DFSDM_Filter_HandleTypeDef
*hdfsdm_filter
); /*!< DFSDM filter error callback */
246 void (*MspInitCallback
) (struct __DFSDM_Filter_HandleTypeDef
*hdfsdm_filter
); /*!< DFSDM filter MSP init callback */
247 void (*MspDeInitCallback
) (struct __DFSDM_Filter_HandleTypeDef
*hdfsdm_filter
); /*!< DFSDM filter MSP de-init callback */
249 }DFSDM_Filter_HandleTypeDef
;
252 * @brief DFSDM filter analog watchdog parameters structure definition
256 uint32_t DataSource
; /*!< Values from digital filter or from channel watchdog filter.
257 This parameter can be a value of @ref DFSDM_Filter_AwdDataSource */
258 uint32_t Channel
; /*!< Analog watchdog channel selection.
259 This parameter can be a values combination of @ref DFSDM_Channel_Selection */
260 int32_t HighThreshold
; /*!< High threshold for the analog watchdog.
261 This parameter must be a number between Min_Data = -8388608 and Max_Data = 8388607 */
262 int32_t LowThreshold
; /*!< Low threshold for the analog watchdog.
263 This parameter must be a number between Min_Data = -8388608 and Max_Data = 8388607 */
264 uint32_t HighBreakSignal
; /*!< Break signal assigned to analog watchdog high threshold event.
265 This parameter can be a values combination of @ref DFSDM_BreakSignals */
266 uint32_t LowBreakSignal
; /*!< Break signal assigned to analog watchdog low threshold event.
267 This parameter can be a values combination of @ref DFSDM_BreakSignals */
268 } DFSDM_Filter_AwdParamTypeDef
;
270 #if (USE_HAL_DFSDM_REGISTER_CALLBACKS == 1)
272 * @brief DFSDM filter callback ID enumeration definition
276 HAL_DFSDM_FILTER_REGCONV_COMPLETE_CB_ID
= 0x00U
, /*!< DFSDM filter regular conversion complete callback ID */
277 HAL_DFSDM_FILTER_REGCONV_HALFCOMPLETE_CB_ID
= 0x01U
, /*!< DFSDM filter half regular conversion complete callback ID */
278 HAL_DFSDM_FILTER_INJCONV_COMPLETE_CB_ID
= 0x02U
, /*!< DFSDM filter injected conversion complete callback ID */
279 HAL_DFSDM_FILTER_INJCONV_HALFCOMPLETE_CB_ID
= 0x03U
, /*!< DFSDM filter half injected conversion complete callback ID */
280 HAL_DFSDM_FILTER_ERROR_CB_ID
= 0x04U
, /*!< DFSDM filter error callback ID */
281 HAL_DFSDM_FILTER_MSPINIT_CB_ID
= 0x05U
, /*!< DFSDM filter MSP init callback ID */
282 HAL_DFSDM_FILTER_MSPDEINIT_CB_ID
= 0x06U
/*!< DFSDM filter MSP de-init callback ID */
283 } HAL_DFSDM_Filter_CallbackIDTypeDef
;
286 * @brief DFSDM filter callback pointer definition
288 typedef void (*pDFSDM_Filter_CallbackTypeDef
)(DFSDM_Filter_HandleTypeDef
*hdfsdm_filter
);
289 typedef void (*pDFSDM_Filter_AwdCallbackTypeDef
)(DFSDM_Filter_HandleTypeDef
*hdfsdm_filter
, uint32_t Channel
, uint32_t Threshold
);
295 /* End of exported types -----------------------------------------------------*/
297 /* Exported constants --------------------------------------------------------*/
298 /** @defgroup DFSDM_Exported_Constants DFSDM Exported Constants
302 /** @defgroup DFSDM_Channel_OuputClock DFSDM channel output clock selection
305 #define DFSDM_CHANNEL_OUTPUT_CLOCK_SYSTEM 0x00000000U /*!< Source for ouput clock is system clock */
306 #define DFSDM_CHANNEL_OUTPUT_CLOCK_AUDIO DFSDM_CHCFGR1_CKOUTSRC /*!< Source for ouput clock is audio clock */
311 /** @defgroup DFSDM_Channel_InputMultiplexer DFSDM channel input multiplexer
314 #define DFSDM_CHANNEL_EXTERNAL_INPUTS 0x00000000U /*!< Data are taken from external inputs */
315 #define DFSDM_CHANNEL_ADC_OUTPUT DFSDM_CHCFGR1_DATMPX_0 /*!< Data are taken from ADC output */
316 #define DFSDM_CHANNEL_INTERNAL_REGISTER DFSDM_CHCFGR1_DATMPX_1 /*!< Data are taken from internal register */
321 /** @defgroup DFSDM_Channel_DataPacking DFSDM channel input data packing
324 #define DFSDM_CHANNEL_STANDARD_MODE 0x00000000U /*!< Standard data packing mode */
325 #define DFSDM_CHANNEL_INTERLEAVED_MODE DFSDM_CHCFGR1_DATPACK_0 /*!< Interleaved data packing mode */
326 #define DFSDM_CHANNEL_DUAL_MODE DFSDM_CHCFGR1_DATPACK_1 /*!< Dual data packing mode */
331 /** @defgroup DFSDM_Channel_InputPins DFSDM channel input pins
334 #define DFSDM_CHANNEL_SAME_CHANNEL_PINS 0x00000000U /*!< Input from pins on same channel */
335 #define DFSDM_CHANNEL_FOLLOWING_CHANNEL_PINS DFSDM_CHCFGR1_CHINSEL /*!< Input from pins on following channel */
340 /** @defgroup DFSDM_Channel_SerialInterfaceType DFSDM channel serial interface type
343 #define DFSDM_CHANNEL_SPI_RISING 0x00000000U /*!< SPI with rising edge */
344 #define DFSDM_CHANNEL_SPI_FALLING DFSDM_CHCFGR1_SITP_0 /*!< SPI with falling edge */
345 #define DFSDM_CHANNEL_MANCHESTER_RISING DFSDM_CHCFGR1_SITP_1 /*!< Manchester with rising edge */
346 #define DFSDM_CHANNEL_MANCHESTER_FALLING DFSDM_CHCFGR1_SITP /*!< Manchester with falling edge */
351 /** @defgroup DFSDM_Channel_SpiClock DFSDM channel SPI clock selection
354 #define DFSDM_CHANNEL_SPI_CLOCK_EXTERNAL 0x00000000U /*!< External SPI clock */
355 #define DFSDM_CHANNEL_SPI_CLOCK_INTERNAL DFSDM_CHCFGR1_SPICKSEL_0 /*!< Internal SPI clock */
356 #define DFSDM_CHANNEL_SPI_CLOCK_INTERNAL_DIV2_FALLING DFSDM_CHCFGR1_SPICKSEL_1 /*!< Internal SPI clock divided by 2, falling edge */
357 #define DFSDM_CHANNEL_SPI_CLOCK_INTERNAL_DIV2_RISING DFSDM_CHCFGR1_SPICKSEL /*!< Internal SPI clock divided by 2, rising edge */
362 /** @defgroup DFSDM_Channel_AwdFilterOrder DFSDM channel analog watchdog filter order
365 #define DFSDM_CHANNEL_FASTSINC_ORDER 0x00000000U /*!< FastSinc filter type */
366 #define DFSDM_CHANNEL_SINC1_ORDER DFSDM_CHAWSCDR_AWFORD_0 /*!< Sinc 1 filter type */
367 #define DFSDM_CHANNEL_SINC2_ORDER DFSDM_CHAWSCDR_AWFORD_1 /*!< Sinc 2 filter type */
368 #define DFSDM_CHANNEL_SINC3_ORDER DFSDM_CHAWSCDR_AWFORD /*!< Sinc 3 filter type */
373 /** @defgroup DFSDM_Filter_Trigger DFSDM filter conversion trigger
376 #define DFSDM_FILTER_SW_TRIGGER 0x00000000U /*!< Software trigger */
377 #define DFSDM_FILTER_SYNC_TRIGGER 0x00000001U /*!< Synchronous with DFSDM_FLT0 */
378 #define DFSDM_FILTER_EXT_TRIGGER 0x00000002U /*!< External trigger (only for injected conversion) */
383 /** @defgroup DFSDM_Filter_ExtTrigger DFSDM filter external trigger
386 #define DFSDM_FILTER_EXT_TRIG_TIM1_TRGO 0x00000000U /*!< For all DFSDM filters */
387 #define DFSDM_FILTER_EXT_TRIG_TIM1_TRGO2 DFSDM_FLTCR1_JEXTSEL_0 /*!< For all DFSDM filters */
388 #define DFSDM_FILTER_EXT_TRIG_TIM8_TRGO DFSDM_FLTCR1_JEXTSEL_1 /*!< For all DFSDM filters */
389 #define DFSDM_FILTER_EXT_TRIG_TIM8_TRGO2 (DFSDM_FLTCR1_JEXTSEL_0 | DFSDM_FLTCR1_JEXTSEL_1) /*!< For all DFSDM filters */
390 #define DFSDM_FILTER_EXT_TRIG_TIM3_TRGO DFSDM_FLTCR1_JEXTSEL_2 /*!< For all DFSDM filters */
391 #define DFSDM_FILTER_EXT_TRIG_TIM4_TRGO (DFSDM_FLTCR1_JEXTSEL_0 | DFSDM_FLTCR1_JEXTSEL_2) /*!< For all DFSDM filters */
392 #define DFSDM_FILTER_EXT_TRIG_TIM16_OC1 (DFSDM_FLTCR1_JEXTSEL_2 | DFSDM_FLTCR1_JEXTSEL_1) /*!< For all DFSDM filters */
393 #define DFSDM_FILTER_EXT_TRIG_TIM6_TRGO (DFSDM_FLTCR1_JEXTSEL_0 | DFSDM_FLTCR1_JEXTSEL_2 | DFSDM_FLTCR1_JEXTSEL_1) /*!< For all DFSDM filters */
394 #define DFSDM_FILTER_EXT_TRIG_TIM7_TRGO DFSDM_FLTCR1_JEXTSEL_3 /*!< For all DFSDM filters */
395 #define DFSDM_FILTER_EXT_TRIG_HRTIM1_ADCTRG1 (DFSDM_FLTCR1_JEXTSEL_3 | DFSDM_FLTCR1_JEXTSEL_0)
396 #define DFSDM_FILTER_EXT_TRIG_HRTIM1_ADCTRG3 (DFSDM_FLTCR1_JEXTSEL_3 | DFSDM_FLTCR1_JEXTSEL_1)
397 #define DFSDM_FILTER_EXT_TRIG_EXTI11 (DFSDM_FLTCR1_JEXTSEL_4 | DFSDM_FLTCR1_JEXTSEL_3) /*!< For all DFSDM filters */
398 #define DFSDM_FILTER_EXT_TRIG_EXTI15 (DFSDM_FLTCR1_JEXTSEL_4 | DFSDM_FLTCR1_JEXTSEL_3 | DFSDM_FLTCR1_JEXTSEL_0) /*!< For all DFSDM filters */
399 #define DFSDM_FILTER_EXT_TRIG_LPTIM1_OUT (DFSDM_FLTCR1_JEXTSEL_4 | DFSDM_FLTCR1_JEXTSEL_3 | DFSDM_FLTCR1_JEXTSEL_1) /*!< For all DFSDM filters */
400 #define DFSDM_FILTER_EXT_TRIG_LPTIM2_OUT (DFSDM_FLTCR1_JEXTSEL_4 | DFSDM_FLTCR1_JEXTSEL_3 | DFSDM_FLTCR1_JEXTSEL_1 | DFSDM_FLTCR1_JEXTSEL_0) /*!< For all DFSDM filters */
401 #define DFSDM_FILTER_EXT_TRIG_LPTIM3_OUT (DFSDM_FLTCR1_JEXTSEL_4 | DFSDM_FLTCR1_JEXTSEL_3 | DFSDM_FLTCR1_JEXTSEL_2) /*!< For all DFSDM filters */
402 #if (STM32H7_DEV_ID == 0x480UL)
403 #define DFSDM_FILTER_EXT_TRIG_COMP1_OUT (DFSDM_FLTCR1_JEXTSEL_4 | DFSDM_FLTCR1_JEXTSEL_3 | \
404 DFSDM_FLTCR1_JEXTSEL_2 | DFSDM_FLTCR1_JEXTSEL_0)
405 #define DFSDM_FILTER_EXT_TRIG_COMP2_OUT (DFSDM_FLTCR1_JEXTSEL_4 | DFSDM_FLTCR1_JEXTSEL_3 | \
406 DFSDM_FLTCR1_JEXTSEL_2 | DFSDM_FLTCR1_JEXTSEL_1)
407 #elif (STM32H7_DEV_ID == 0x483UL)
408 #define DFSDM_FILTER_EXT_TRIG_TIM23_TRGO (DFSDM_FLTCR1_JEXTSEL_3 | DFSDM_FLTCR1_JEXTSEL_1 | \
409 DFSDM_FLTCR1_JEXTSEL_0)
410 #define DFSDM_FILTER_EXT_TRIG_TIM24_TRGO (DFSDM_FLTCR1_JEXTSEL_3 | DFSDM_FLTCR1_JEXTSEL_2 )
411 #endif /* STM32H7_DEV_ID == 0x480UL */
416 /** @defgroup DFSDM_Filter_ExtTriggerEdge DFSDM filter external trigger edge
419 #define DFSDM_FILTER_EXT_TRIG_RISING_EDGE DFSDM_FLTCR1_JEXTEN_0 /*!< External rising edge */
420 #define DFSDM_FILTER_EXT_TRIG_FALLING_EDGE DFSDM_FLTCR1_JEXTEN_1 /*!< External falling edge */
421 #define DFSDM_FILTER_EXT_TRIG_BOTH_EDGES DFSDM_FLTCR1_JEXTEN /*!< External rising and falling edges */
426 /** @defgroup DFSDM_Filter_SincOrder DFSDM filter sinc order
429 #define DFSDM_FILTER_FASTSINC_ORDER 0x00000000U /*!< FastSinc filter type */
430 #define DFSDM_FILTER_SINC1_ORDER DFSDM_FLTFCR_FORD_0 /*!< Sinc 1 filter type */
431 #define DFSDM_FILTER_SINC2_ORDER DFSDM_FLTFCR_FORD_1 /*!< Sinc 2 filter type */
432 #define DFSDM_FILTER_SINC3_ORDER (DFSDM_FLTFCR_FORD_0 | DFSDM_FLTFCR_FORD_1) /*!< Sinc 3 filter type */
433 #define DFSDM_FILTER_SINC4_ORDER DFSDM_FLTFCR_FORD_2 /*!< Sinc 4 filter type */
434 #define DFSDM_FILTER_SINC5_ORDER (DFSDM_FLTFCR_FORD_0 | DFSDM_FLTFCR_FORD_2) /*!< Sinc 5 filter type */
439 /** @defgroup DFSDM_Filter_AwdDataSource DFSDM filter analog watchdog data source
442 #define DFSDM_FILTER_AWD_FILTER_DATA 0x00000000U /*!< From digital filter */
443 #define DFSDM_FILTER_AWD_CHANNEL_DATA DFSDM_FLTCR1_AWFSEL /*!< From analog watchdog channel */
448 /** @defgroup DFSDM_Filter_ErrorCode DFSDM filter error code
451 #define DFSDM_FILTER_ERROR_NONE 0x00000000U /*!< No error */
452 #define DFSDM_FILTER_ERROR_REGULAR_OVERRUN 0x00000001U /*!< Overrun occurs during regular conversion */
453 #define DFSDM_FILTER_ERROR_INJECTED_OVERRUN 0x00000002U /*!< Overrun occurs during injected conversion */
454 #define DFSDM_FILTER_ERROR_DMA 0x00000003U /*!< DMA error occurs */
455 #if (USE_HAL_DFSDM_REGISTER_CALLBACKS == 1)
456 #define DFSDM_FILTER_ERROR_INVALID_CALLBACK 0x00000004U /*!< Invalid callback error occurs */
462 /** @defgroup DFSDM_BreakSignals DFSDM break signals
465 #define DFSDM_NO_BREAK_SIGNAL 0x00000000U /*!< No break signal */
466 #define DFSDM_BREAK_SIGNAL_0 0x00000001U /*!< Break signal 0 */
467 #define DFSDM_BREAK_SIGNAL_1 0x00000002U /*!< Break signal 1 */
468 #define DFSDM_BREAK_SIGNAL_2 0x00000004U /*!< Break signal 2 */
469 #define DFSDM_BREAK_SIGNAL_3 0x00000008U /*!< Break signal 3 */
474 /** @defgroup DFSDM_Channel_Selection DFSDM Channel Selection
477 /* DFSDM Channels ------------------------------------------------------------*/
478 /* The DFSDM channels are defined as follows:
479 - in 16-bit LSB the channel mask is set
480 - in 16-bit MSB the channel number is set
481 e.g. for channel 5 definition:
482 - the channel mask is 0x00000020 (bit 5 is set)
483 - the channel number 5 is 0x00050000
484 --> Consequently, channel 5 definition is 0x00000020 | 0x00050000 = 0x00050020 */
485 #define DFSDM_CHANNEL_0 0x00000001U
486 #define DFSDM_CHANNEL_1 0x00010002U
487 #define DFSDM_CHANNEL_2 0x00020004U
488 #define DFSDM_CHANNEL_3 0x00030008U
489 #define DFSDM_CHANNEL_4 0x00040010U
490 #define DFSDM_CHANNEL_5 0x00050020U
491 #define DFSDM_CHANNEL_6 0x00060040U
492 #define DFSDM_CHANNEL_7 0x00070080U
497 /** @defgroup DFSDM_ContinuousMode DFSDM Continuous Mode
500 #define DFSDM_CONTINUOUS_CONV_OFF 0x00000000U /*!< Conversion are not continuous */
501 #define DFSDM_CONTINUOUS_CONV_ON 0x00000001U /*!< Conversion are continuous */
506 /** @defgroup DFSDM_AwdThreshold DFSDM analog watchdog threshold
509 #define DFSDM_AWD_HIGH_THRESHOLD 0x00000000U /*!< Analog watchdog high threshold */
510 #define DFSDM_AWD_LOW_THRESHOLD 0x00000001U /*!< Analog watchdog low threshold */
518 /* End of exported constants -------------------------------------------------*/
520 /* Exported macros -----------------------------------------------------------*/
521 /** @defgroup DFSDM_Exported_Macros DFSDM Exported Macros
525 /** @brief Reset DFSDM channel handle state.
526 * @param __HANDLE__ DFSDM channel handle.
529 #if (USE_HAL_DFSDM_REGISTER_CALLBACKS == 1)
530 #define __HAL_DFSDM_CHANNEL_RESET_HANDLE_STATE(__HANDLE__) do{ \
531 (__HANDLE__)->State = HAL_DFSDM_CHANNEL_STATE_RESET; \
532 (__HANDLE__)->MspInitCallback = NULL; \
533 (__HANDLE__)->MspDeInitCallback = NULL; \
536 #define __HAL_DFSDM_CHANNEL_RESET_HANDLE_STATE(__HANDLE__) ((__HANDLE__)->State = HAL_DFSDM_CHANNEL_STATE_RESET)
539 /** @brief Reset DFSDM filter handle state.
540 * @param __HANDLE__ DFSDM filter handle.
543 #if (USE_HAL_DFSDM_REGISTER_CALLBACKS == 1)
544 #define __HAL_DFSDM_FILTER_RESET_HANDLE_STATE(__HANDLE__) do{ \
545 (__HANDLE__)->State = HAL_DFSDM_FILTER_STATE_RESET; \
546 (__HANDLE__)->MspInitCallback = NULL; \
547 (__HANDLE__)->MspDeInitCallback = NULL; \
550 #define __HAL_DFSDM_FILTER_RESET_HANDLE_STATE(__HANDLE__) ((__HANDLE__)->State = HAL_DFSDM_FILTER_STATE_RESET)
556 /* End of exported macros ----------------------------------------------------*/
558 #if defined(DFSDM_CHDLYR_PLSSKP)
559 /* Include DFSDM HAL Extension module */
560 #include "stm32h7xx_hal_dfsdm_ex.h"
561 #endif /* DFSDM_CHDLYR_PLSSKP */
563 /* Exported functions --------------------------------------------------------*/
564 /** @addtogroup DFSDM_Exported_Functions DFSDM Exported Functions
568 /** @addtogroup DFSDM_Exported_Functions_Group1_Channel Channel initialization and de-initialization functions
571 /* Channel initialization and de-initialization functions *********************/
572 HAL_StatusTypeDef
HAL_DFSDM_ChannelInit(DFSDM_Channel_HandleTypeDef
*hdfsdm_channel
);
573 HAL_StatusTypeDef
HAL_DFSDM_ChannelDeInit(DFSDM_Channel_HandleTypeDef
*hdfsdm_channel
);
574 void HAL_DFSDM_ChannelMspInit(DFSDM_Channel_HandleTypeDef
*hdfsdm_channel
);
575 void HAL_DFSDM_ChannelMspDeInit(DFSDM_Channel_HandleTypeDef
*hdfsdm_channel
);
577 #if (USE_HAL_DFSDM_REGISTER_CALLBACKS == 1)
578 /* Channel callbacks register/unregister functions ****************************/
579 HAL_StatusTypeDef
HAL_DFSDM_Channel_RegisterCallback(DFSDM_Channel_HandleTypeDef
*hdfsdm_channel
,
580 HAL_DFSDM_Channel_CallbackIDTypeDef CallbackID
,
581 pDFSDM_Channel_CallbackTypeDef pCallback
);
582 HAL_StatusTypeDef
HAL_DFSDM_Channel_UnRegisterCallback(DFSDM_Channel_HandleTypeDef
*hdfsdm_channel
,
583 HAL_DFSDM_Channel_CallbackIDTypeDef CallbackID
);
589 /** @addtogroup DFSDM_Exported_Functions_Group2_Channel Channel operation functions
592 /* Channel operation functions ************************************************/
593 HAL_StatusTypeDef
HAL_DFSDM_ChannelCkabStart(DFSDM_Channel_HandleTypeDef
*hdfsdm_channel
);
594 HAL_StatusTypeDef
HAL_DFSDM_ChannelCkabStart_IT(DFSDM_Channel_HandleTypeDef
*hdfsdm_channel
);
595 HAL_StatusTypeDef
HAL_DFSDM_ChannelCkabStop(DFSDM_Channel_HandleTypeDef
*hdfsdm_channel
);
596 HAL_StatusTypeDef
HAL_DFSDM_ChannelCkabStop_IT(DFSDM_Channel_HandleTypeDef
*hdfsdm_channel
);
598 HAL_StatusTypeDef
HAL_DFSDM_ChannelScdStart(DFSDM_Channel_HandleTypeDef
*hdfsdm_channel
, uint32_t Threshold
, uint32_t BreakSignal
);
599 HAL_StatusTypeDef
HAL_DFSDM_ChannelScdStart_IT(DFSDM_Channel_HandleTypeDef
*hdfsdm_channel
, uint32_t Threshold
, uint32_t BreakSignal
);
600 HAL_StatusTypeDef
HAL_DFSDM_ChannelScdStop(DFSDM_Channel_HandleTypeDef
*hdfsdm_channel
);
601 HAL_StatusTypeDef
HAL_DFSDM_ChannelScdStop_IT(DFSDM_Channel_HandleTypeDef
*hdfsdm_channel
);
603 int16_t HAL_DFSDM_ChannelGetAwdValue(DFSDM_Channel_HandleTypeDef
*hdfsdm_channel
);
604 HAL_StatusTypeDef
HAL_DFSDM_ChannelModifyOffset(DFSDM_Channel_HandleTypeDef
*hdfsdm_channel
, int32_t Offset
);
606 HAL_StatusTypeDef
HAL_DFSDM_ChannelPollForCkab(DFSDM_Channel_HandleTypeDef
*hdfsdm_channel
, uint32_t Timeout
);
607 HAL_StatusTypeDef
HAL_DFSDM_ChannelPollForScd(DFSDM_Channel_HandleTypeDef
*hdfsdm_channel
, uint32_t Timeout
);
609 void HAL_DFSDM_ChannelCkabCallback(DFSDM_Channel_HandleTypeDef
*hdfsdm_channel
);
610 void HAL_DFSDM_ChannelScdCallback(DFSDM_Channel_HandleTypeDef
*hdfsdm_channel
);
615 /** @defgroup DFSDM_Exported_Functions_Group3_Channel Channel state function
618 /* Channel state function *****************************************************/
619 HAL_DFSDM_Channel_StateTypeDef
HAL_DFSDM_ChannelGetState(DFSDM_Channel_HandleTypeDef
*hdfsdm_channel
);
624 /** @addtogroup DFSDM_Exported_Functions_Group1_Filter Filter initialization and de-initialization functions
627 /* Filter initialization and de-initialization functions *********************/
628 HAL_StatusTypeDef
HAL_DFSDM_FilterInit(DFSDM_Filter_HandleTypeDef
*hdfsdm_filter
);
629 HAL_StatusTypeDef
HAL_DFSDM_FilterDeInit(DFSDM_Filter_HandleTypeDef
*hdfsdm_filter
);
630 void HAL_DFSDM_FilterMspInit(DFSDM_Filter_HandleTypeDef
*hdfsdm_filter
);
631 void HAL_DFSDM_FilterMspDeInit(DFSDM_Filter_HandleTypeDef
*hdfsdm_filter
);
633 #if (USE_HAL_DFSDM_REGISTER_CALLBACKS == 1)
634 /* Filter callbacks register/unregister functions ****************************/
635 HAL_StatusTypeDef
HAL_DFSDM_Filter_RegisterCallback(DFSDM_Filter_HandleTypeDef
*hdfsdm_filter
,
636 HAL_DFSDM_Filter_CallbackIDTypeDef CallbackID
,
637 pDFSDM_Filter_CallbackTypeDef pCallback
);
638 HAL_StatusTypeDef
HAL_DFSDM_Filter_UnRegisterCallback(DFSDM_Filter_HandleTypeDef
*hdfsdm_filter
,
639 HAL_DFSDM_Filter_CallbackIDTypeDef CallbackID
);
640 HAL_StatusTypeDef
HAL_DFSDM_Filter_RegisterAwdCallback(DFSDM_Filter_HandleTypeDef
*hdfsdm_filter
,
641 pDFSDM_Filter_AwdCallbackTypeDef pCallback
);
642 HAL_StatusTypeDef
HAL_DFSDM_Filter_UnRegisterAwdCallback(DFSDM_Filter_HandleTypeDef
*hdfsdm_filter
);
648 /** @addtogroup DFSDM_Exported_Functions_Group2_Filter Filter control functions
651 /* Filter control functions *********************/
652 HAL_StatusTypeDef
HAL_DFSDM_FilterConfigRegChannel(DFSDM_Filter_HandleTypeDef
*hdfsdm_filter
,
654 uint32_t ContinuousMode
);
655 HAL_StatusTypeDef
HAL_DFSDM_FilterConfigInjChannel(DFSDM_Filter_HandleTypeDef
*hdfsdm_filter
,
661 /** @addtogroup DFSDM_Exported_Functions_Group3_Filter Filter operation functions
664 /* Filter operation functions *********************/
665 HAL_StatusTypeDef
HAL_DFSDM_FilterRegularStart(DFSDM_Filter_HandleTypeDef
*hdfsdm_filter
);
666 HAL_StatusTypeDef
HAL_DFSDM_FilterRegularStart_IT(DFSDM_Filter_HandleTypeDef
*hdfsdm_filter
);
667 HAL_StatusTypeDef
HAL_DFSDM_FilterRegularStart_DMA(DFSDM_Filter_HandleTypeDef
*hdfsdm_filter
, int32_t *pData
, uint32_t Length
);
668 HAL_StatusTypeDef
HAL_DFSDM_FilterRegularMsbStart_DMA(DFSDM_Filter_HandleTypeDef
*hdfsdm_filter
, int16_t *pData
, uint32_t Length
);
669 HAL_StatusTypeDef
HAL_DFSDM_FilterRegularStop(DFSDM_Filter_HandleTypeDef
*hdfsdm_filter
);
670 HAL_StatusTypeDef
HAL_DFSDM_FilterRegularStop_IT(DFSDM_Filter_HandleTypeDef
*hdfsdm_filter
);
671 HAL_StatusTypeDef
HAL_DFSDM_FilterRegularStop_DMA(DFSDM_Filter_HandleTypeDef
*hdfsdm_filter
);
672 HAL_StatusTypeDef
HAL_DFSDM_FilterInjectedStart(DFSDM_Filter_HandleTypeDef
*hdfsdm_filter
);
673 HAL_StatusTypeDef
HAL_DFSDM_FilterInjectedStart_IT(DFSDM_Filter_HandleTypeDef
*hdfsdm_filter
);
674 HAL_StatusTypeDef
HAL_DFSDM_FilterInjectedStart_DMA(DFSDM_Filter_HandleTypeDef
*hdfsdm_filter
, int32_t *pData
, uint32_t Length
);
675 HAL_StatusTypeDef
HAL_DFSDM_FilterInjectedMsbStart_DMA(DFSDM_Filter_HandleTypeDef
*hdfsdm_filter
, int16_t *pData
, uint32_t Length
);
676 HAL_StatusTypeDef
HAL_DFSDM_FilterInjectedStop(DFSDM_Filter_HandleTypeDef
*hdfsdm_filter
);
677 HAL_StatusTypeDef
HAL_DFSDM_FilterInjectedStop_IT(DFSDM_Filter_HandleTypeDef
*hdfsdm_filter
);
678 HAL_StatusTypeDef
HAL_DFSDM_FilterInjectedStop_DMA(DFSDM_Filter_HandleTypeDef
*hdfsdm_filter
);
679 HAL_StatusTypeDef
HAL_DFSDM_FilterAwdStart_IT(DFSDM_Filter_HandleTypeDef
*hdfsdm_filter
,
680 DFSDM_Filter_AwdParamTypeDef
*awdParam
);
681 HAL_StatusTypeDef
HAL_DFSDM_FilterAwdStop_IT(DFSDM_Filter_HandleTypeDef
*hdfsdm_filter
);
682 HAL_StatusTypeDef
HAL_DFSDM_FilterExdStart(DFSDM_Filter_HandleTypeDef
*hdfsdm_filter
, uint32_t Channel
);
683 HAL_StatusTypeDef
HAL_DFSDM_FilterExdStop(DFSDM_Filter_HandleTypeDef
*hdfsdm_filter
);
685 int32_t HAL_DFSDM_FilterGetRegularValue(DFSDM_Filter_HandleTypeDef
*hdfsdm_filter
, uint32_t *Channel
);
686 int32_t HAL_DFSDM_FilterGetInjectedValue(DFSDM_Filter_HandleTypeDef
*hdfsdm_filter
, uint32_t *Channel
);
687 int32_t HAL_DFSDM_FilterGetExdMaxValue(DFSDM_Filter_HandleTypeDef
*hdfsdm_filter
, uint32_t *Channel
);
688 int32_t HAL_DFSDM_FilterGetExdMinValue(DFSDM_Filter_HandleTypeDef
*hdfsdm_filter
, uint32_t *Channel
);
689 uint32_t HAL_DFSDM_FilterGetConvTimeValue(DFSDM_Filter_HandleTypeDef
*hdfsdm_filter
);
691 void HAL_DFSDM_IRQHandler(DFSDM_Filter_HandleTypeDef
*hdfsdm_filter
);
693 HAL_StatusTypeDef
HAL_DFSDM_FilterPollForRegConversion(DFSDM_Filter_HandleTypeDef
*hdfsdm_filter
, uint32_t Timeout
);
694 HAL_StatusTypeDef
HAL_DFSDM_FilterPollForInjConversion(DFSDM_Filter_HandleTypeDef
*hdfsdm_filter
, uint32_t Timeout
);
696 void HAL_DFSDM_FilterRegConvCpltCallback(DFSDM_Filter_HandleTypeDef
*hdfsdm_filter
);
697 void HAL_DFSDM_FilterRegConvHalfCpltCallback(DFSDM_Filter_HandleTypeDef
*hdfsdm_filter
);
698 void HAL_DFSDM_FilterInjConvCpltCallback(DFSDM_Filter_HandleTypeDef
*hdfsdm_filter
);
699 void HAL_DFSDM_FilterInjConvHalfCpltCallback(DFSDM_Filter_HandleTypeDef
*hdfsdm_filter
);
700 void HAL_DFSDM_FilterAwdCallback(DFSDM_Filter_HandleTypeDef
*hdfsdm_filter
, uint32_t Channel
, uint32_t Threshold
);
701 void HAL_DFSDM_FilterErrorCallback(DFSDM_Filter_HandleTypeDef
*hdfsdm_filter
);
706 /** @defgroup DFSDM_Exported_Functions_Group4_Filter Filter state functions
709 /* Filter state functions *****************************************************/
710 HAL_DFSDM_Filter_StateTypeDef
HAL_DFSDM_FilterGetState(DFSDM_Filter_HandleTypeDef
*hdfsdm_filter
);
711 uint32_t HAL_DFSDM_FilterGetError(DFSDM_Filter_HandleTypeDef
*hdfsdm_filter
);
719 /* End of exported functions -------------------------------------------------*/
721 /* Private macros ------------------------------------------------------------*/
722 /** @defgroup DFSDM_Private_Macros DFSDM Private Macros
725 #define IS_DFSDM_CHANNEL_OUTPUT_CLOCK(CLOCK) (((CLOCK) == DFSDM_CHANNEL_OUTPUT_CLOCK_SYSTEM) || \
726 ((CLOCK) == DFSDM_CHANNEL_OUTPUT_CLOCK_AUDIO))
727 #define IS_DFSDM_CHANNEL_OUTPUT_CLOCK_DIVIDER(DIVIDER) ((2U <= (DIVIDER)) && ((DIVIDER) <= 256U))
728 #define IS_DFSDM_CHANNEL_INPUT(INPUT) (((INPUT) == DFSDM_CHANNEL_EXTERNAL_INPUTS) || \
729 ((INPUT) == DFSDM_CHANNEL_ADC_OUTPUT) || \
730 ((INPUT) == DFSDM_CHANNEL_INTERNAL_REGISTER))
731 #define IS_DFSDM_CHANNEL_DATA_PACKING(MODE) (((MODE) == DFSDM_CHANNEL_STANDARD_MODE) || \
732 ((MODE) == DFSDM_CHANNEL_INTERLEAVED_MODE) || \
733 ((MODE) == DFSDM_CHANNEL_DUAL_MODE))
734 #define IS_DFSDM_CHANNEL_INPUT_PINS(PINS) (((PINS) == DFSDM_CHANNEL_SAME_CHANNEL_PINS) || \
735 ((PINS) == DFSDM_CHANNEL_FOLLOWING_CHANNEL_PINS))
736 #define IS_DFSDM_CHANNEL_SERIAL_INTERFACE_TYPE(MODE) (((MODE) == DFSDM_CHANNEL_SPI_RISING) || \
737 ((MODE) == DFSDM_CHANNEL_SPI_FALLING) || \
738 ((MODE) == DFSDM_CHANNEL_MANCHESTER_RISING) || \
739 ((MODE) == DFSDM_CHANNEL_MANCHESTER_FALLING))
740 #define IS_DFSDM_CHANNEL_SPI_CLOCK(TYPE) (((TYPE) == DFSDM_CHANNEL_SPI_CLOCK_EXTERNAL) || \
741 ((TYPE) == DFSDM_CHANNEL_SPI_CLOCK_INTERNAL) || \
742 ((TYPE) == DFSDM_CHANNEL_SPI_CLOCK_INTERNAL_DIV2_FALLING) || \
743 ((TYPE) == DFSDM_CHANNEL_SPI_CLOCK_INTERNAL_DIV2_RISING))
744 #define IS_DFSDM_CHANNEL_FILTER_ORDER(ORDER) (((ORDER) == DFSDM_CHANNEL_FASTSINC_ORDER) || \
745 ((ORDER) == DFSDM_CHANNEL_SINC1_ORDER) || \
746 ((ORDER) == DFSDM_CHANNEL_SINC2_ORDER) || \
747 ((ORDER) == DFSDM_CHANNEL_SINC3_ORDER))
748 #define IS_DFSDM_CHANNEL_FILTER_OVS_RATIO(RATIO) ((1U <= (RATIO)) && ((RATIO) <= 32U))
749 #define IS_DFSDM_CHANNEL_OFFSET(VALUE) ((-8388608 <= (VALUE)) && ((VALUE) <= 8388607))
750 #define IS_DFSDM_CHANNEL_RIGHT_BIT_SHIFT(VALUE) ((VALUE) <= 0x1FU)
751 #define IS_DFSDM_CHANNEL_SCD_THRESHOLD(VALUE) ((VALUE) <= 0xFFU)
752 #define IS_DFSDM_FILTER_REG_TRIGGER(TRIG) (((TRIG) == DFSDM_FILTER_SW_TRIGGER) || \
753 ((TRIG) == DFSDM_FILTER_SYNC_TRIGGER))
754 #define IS_DFSDM_FILTER_INJ_TRIGGER(TRIG) (((TRIG) == DFSDM_FILTER_SW_TRIGGER) || \
755 ((TRIG) == DFSDM_FILTER_SYNC_TRIGGER) || \
756 ((TRIG) == DFSDM_FILTER_EXT_TRIGGER))
757 #if (STM32H7_DEV_ID == 0x480UL)
758 #define IS_DFSDM_FILTER_EXT_TRIG(TRIG) (((TRIG) == DFSDM_FILTER_EXT_TRIG_TIM1_TRGO) || \
759 ((TRIG) == DFSDM_FILTER_EXT_TRIG_TIM1_TRGO2) || \
760 ((TRIG) == DFSDM_FILTER_EXT_TRIG_TIM8_TRGO) || \
761 ((TRIG) == DFSDM_FILTER_EXT_TRIG_TIM8_TRGO2) || \
762 ((TRIG) == DFSDM_FILTER_EXT_TRIG_TIM3_TRGO) || \
763 ((TRIG) == DFSDM_FILTER_EXT_TRIG_TIM4_TRGO) || \
764 ((TRIG) == DFSDM_FILTER_EXT_TRIG_TIM16_OC1) || \
765 ((TRIG) == DFSDM_FILTER_EXT_TRIG_TIM6_TRGO) || \
766 ((TRIG) == DFSDM_FILTER_EXT_TRIG_TIM7_TRGO) || \
767 ((TRIG) == DFSDM_FILTER_EXT_TRIG_EXTI11) || \
768 ((TRIG) == DFSDM_FILTER_EXT_TRIG_EXTI15) || \
769 ((TRIG) == DFSDM_FILTER_EXT_TRIG_LPTIM1_OUT) || \
770 ((TRIG) == DFSDM_FILTER_EXT_TRIG_LPTIM2_OUT) || \
771 ((TRIG) == DFSDM_FILTER_EXT_TRIG_LPTIM3_OUT) || \
772 ((TRIG) == DFSDM_FILTER_EXT_TRIG_COMP1_OUT) || \
773 ((TRIG) == DFSDM_FILTER_EXT_TRIG_COMP2_OUT))
774 #elif (STM32H7_DEV_ID == 0x483UL)
775 #define IS_DFSDM_FILTER_EXT_TRIG(TRIG) (((TRIG) == DFSDM_FILTER_EXT_TRIG_TIM1_TRGO) || \
776 ((TRIG) == DFSDM_FILTER_EXT_TRIG_TIM1_TRGO2) || \
777 ((TRIG) == DFSDM_FILTER_EXT_TRIG_TIM8_TRGO) || \
778 ((TRIG) == DFSDM_FILTER_EXT_TRIG_TIM8_TRGO2) || \
779 ((TRIG) == DFSDM_FILTER_EXT_TRIG_TIM3_TRGO) || \
780 ((TRIG) == DFSDM_FILTER_EXT_TRIG_TIM4_TRGO) || \
781 ((TRIG) == DFSDM_FILTER_EXT_TRIG_TIM16_OC1) || \
782 ((TRIG) == DFSDM_FILTER_EXT_TRIG_TIM6_TRGO) || \
783 ((TRIG) == DFSDM_FILTER_EXT_TRIG_TIM7_TRGO) || \
784 ((TRIG) == DFSDM_FILTER_EXT_TRIG_EXTI11) || \
785 ((TRIG) == DFSDM_FILTER_EXT_TRIG_EXTI15) || \
786 ((TRIG) == DFSDM_FILTER_EXT_TRIG_LPTIM1_OUT) || \
787 ((TRIG) == DFSDM_FILTER_EXT_TRIG_LPTIM2_OUT) || \
788 ((TRIG) == DFSDM_FILTER_EXT_TRIG_LPTIM3_OUT) || \
789 ((TRIG) == DFSDM_FILTER_EXT_TRIG_TIM23_TRGO) || \
790 ((TRIG) == DFSDM_FILTER_EXT_TRIG_TIM24_TRGO))
793 #define IS_DFSDM_FILTER_EXT_TRIG(TRIG) (((TRIG) == DFSDM_FILTER_EXT_TRIG_TIM1_TRGO) || \
794 ((TRIG) == DFSDM_FILTER_EXT_TRIG_TIM1_TRGO2) || \
795 ((TRIG) == DFSDM_FILTER_EXT_TRIG_TIM8_TRGO) || \
796 ((TRIG) == DFSDM_FILTER_EXT_TRIG_TIM8_TRGO2) || \
797 ((TRIG) == DFSDM_FILTER_EXT_TRIG_TIM3_TRGO) || \
798 ((TRIG) == DFSDM_FILTER_EXT_TRIG_TIM4_TRGO) || \
799 ((TRIG) == DFSDM_FILTER_EXT_TRIG_TIM16_OC1) || \
800 ((TRIG) == DFSDM_FILTER_EXT_TRIG_TIM6_TRGO) || \
801 ((TRIG) == DFSDM_FILTER_EXT_TRIG_TIM7_TRGO) || \
802 ((TRIG) == DFSDM_FILTER_EXT_TRIG_HRTIM1_ADCTRG1) || \
803 ((TRIG) == DFSDM_FILTER_EXT_TRIG_HRTIM1_ADCTRG3) || \
804 ((TRIG) == DFSDM_FILTER_EXT_TRIG_EXTI11) || \
805 ((TRIG) == DFSDM_FILTER_EXT_TRIG_EXTI15) || \
806 ((TRIG) == DFSDM_FILTER_EXT_TRIG_LPTIM1_OUT) || \
807 ((TRIG) == DFSDM_FILTER_EXT_TRIG_LPTIM2_OUT) || \
808 ((TRIG) == DFSDM_FILTER_EXT_TRIG_LPTIM3_OUT))
809 #endif /* STM32H7_DEV_ID == 0x480UL */
810 #define IS_DFSDM_FILTER_EXT_TRIG_EDGE(EDGE) (((EDGE) == DFSDM_FILTER_EXT_TRIG_RISING_EDGE) || \
811 ((EDGE) == DFSDM_FILTER_EXT_TRIG_FALLING_EDGE) || \
812 ((EDGE) == DFSDM_FILTER_EXT_TRIG_BOTH_EDGES))
813 #define IS_DFSDM_FILTER_SINC_ORDER(ORDER) (((ORDER) == DFSDM_FILTER_FASTSINC_ORDER) || \
814 ((ORDER) == DFSDM_FILTER_SINC1_ORDER) || \
815 ((ORDER) == DFSDM_FILTER_SINC2_ORDER) || \
816 ((ORDER) == DFSDM_FILTER_SINC3_ORDER) || \
817 ((ORDER) == DFSDM_FILTER_SINC4_ORDER) || \
818 ((ORDER) == DFSDM_FILTER_SINC5_ORDER))
819 #define IS_DFSDM_FILTER_OVS_RATIO(RATIO) ((1U <= (RATIO)) && ((RATIO) <= 1024U))
820 #define IS_DFSDM_FILTER_INTEGRATOR_OVS_RATIO(RATIO) ((1U <= (RATIO)) && ((RATIO) <= 256U))
821 #define IS_DFSDM_FILTER_AWD_DATA_SOURCE(DATA) (((DATA) == DFSDM_FILTER_AWD_FILTER_DATA) || \
822 ((DATA) == DFSDM_FILTER_AWD_CHANNEL_DATA))
823 #define IS_DFSDM_FILTER_AWD_THRESHOLD(VALUE) ((-8388608 <= (VALUE)) && ((VALUE) <= 8388607))
824 #define IS_DFSDM_BREAK_SIGNALS(VALUE) ((VALUE) <= 0xFU)
825 #define IS_DFSDM_REGULAR_CHANNEL(CHANNEL) (((CHANNEL) == DFSDM_CHANNEL_0) || \
826 ((CHANNEL) == DFSDM_CHANNEL_1) || \
827 ((CHANNEL) == DFSDM_CHANNEL_2) || \
828 ((CHANNEL) == DFSDM_CHANNEL_3) || \
829 ((CHANNEL) == DFSDM_CHANNEL_4) || \
830 ((CHANNEL) == DFSDM_CHANNEL_5) || \
831 ((CHANNEL) == DFSDM_CHANNEL_6) || \
832 ((CHANNEL) == DFSDM_CHANNEL_7))
833 #define IS_DFSDM_INJECTED_CHANNEL(CHANNEL) (((CHANNEL) != 0U) && ((CHANNEL) <= 0x000F00FFU))
834 #define IS_DFSDM_CONTINUOUS_MODE(MODE) (((MODE) == DFSDM_CONTINUOUS_CONV_OFF) || \
835 ((MODE) == DFSDM_CONTINUOUS_CONV_ON))
836 #if defined(DFSDM2_Channel0)
837 #define IS_DFSDM1_CHANNEL_INSTANCE(INSTANCE) (((INSTANCE) == DFSDM1_Channel0) || \
838 ((INSTANCE) == DFSDM1_Channel1) || \
839 ((INSTANCE) == DFSDM1_Channel2) || \
840 ((INSTANCE) == DFSDM1_Channel3) || \
841 ((INSTANCE) == DFSDM1_Channel4) || \
842 ((INSTANCE) == DFSDM1_Channel5) || \
843 ((INSTANCE) == DFSDM1_Channel6) || \
844 ((INSTANCE) == DFSDM1_Channel7))
845 #define IS_DFSDM1_FILTER_INSTANCE(INSTANCE) (((INSTANCE) == DFSDM1_Filter0) || \
846 ((INSTANCE) == DFSDM1_Filter1) || \
847 ((INSTANCE) == DFSDM1_Filter2) || \
848 ((INSTANCE) == DFSDM1_Filter3) || \
849 ((INSTANCE) == DFSDM1_Filter4) || \
850 ((INSTANCE) == DFSDM1_Filter5) || \
851 ((INSTANCE) == DFSDM1_Filter6) || \
852 ((INSTANCE) == DFSDM1_Filter7))
853 #endif /* DFSDM2_Channel0 */
857 /* End of private macros -----------------------------------------------------*/
871 #endif /* STM32H7xx_HAL_DFSDM_H */
873 /************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/