Updated and Validated
[betaflight.git] / lib / main / STM32F7 / Drivers / STM32F7xx_HAL_Driver / Inc / stm32f7xx_hal_dfsdm.h
blob53cd794c165cf535378eae08f5e7b86d75d970c6
1 /**
2 ******************************************************************************
3 * @file stm32f7xx_hal_dfsdm.h
4 * @author MCD Application Team
5 * @brief Header file of DFSDM HAL module.
6 ******************************************************************************
7 * @attention
9 * <h2><center>&copy; 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 __STM32F7xx_HAL_DFSDM_H
22 #define __STM32F7xx_HAL_DFSDM_H
24 #ifdef __cplusplus
25 extern "C" {
26 #endif
28 #if defined (STM32F765xx) || defined (STM32F767xx) || defined (STM32F769xx) || defined (STM32F777xx) || defined (STM32F779xx)
29 /* Includes ------------------------------------------------------------------*/
30 #include "stm32f7xx_hal_def.h"
32 /** @addtogroup STM32F7xx_HAL_Driver
33 * @{
36 /** @addtogroup DFSDM
37 * @{
38 */
40 /* Exported types ------------------------------------------------------------*/
41 /** @defgroup DFSDM_Exported_Types DFSDM Exported Types
42 * @{
45 /**
46 * @brief HAL DFSDM Channel states definition
47 */
48 typedef enum
50 HAL_DFSDM_CHANNEL_STATE_RESET = 0x00U, /*!< DFSDM channel not initialized */
51 HAL_DFSDM_CHANNEL_STATE_READY = 0x01U, /*!< DFSDM channel initialized and ready for use */
52 HAL_DFSDM_CHANNEL_STATE_ERROR = 0xFFU /*!< DFSDM channel state error */
53 }HAL_DFSDM_Channel_StateTypeDef;
55 /**
56 * @brief DFSDM channel output clock structure definition
57 */
58 typedef struct
60 FunctionalState Activation; /*!< Output clock enable/disable */
61 uint32_t Selection; /*!< Output clock is system clock or audio clock.
62 This parameter can be a value of @ref DFSDM_Channel_OuputClock */
63 uint32_t Divider; /*!< Output clock divider.
64 This parameter must be a number between Min_Data = 2 and Max_Data = 256 */
65 }DFSDM_Channel_OutputClockTypeDef;
67 /**
68 * @brief DFSDM channel input structure definition
69 */
70 typedef struct
72 uint32_t Multiplexer; /*!< Input is external serial inputs or internal register.
73 This parameter can be a value of @ref DFSDM_Channel_InputMultiplexer */
74 uint32_t DataPacking; /*!< Standard, interleaved or dual mode for internal register.
75 This parameter can be a value of @ref DFSDM_Channel_DataPacking */
76 uint32_t Pins; /*!< Input pins are taken from same or following channel.
77 This parameter can be a value of @ref DFSDM_Channel_InputPins */
78 }DFSDM_Channel_InputTypeDef;
80 /**
81 * @brief DFSDM channel serial interface structure definition
82 */
83 typedef struct
85 uint32_t Type; /*!< SPI or Manchester modes.
86 This parameter can be a value of @ref DFSDM_Channel_SerialInterfaceType */
87 uint32_t SpiClock; /*!< SPI clock select (external or internal with different sampling point).
88 This parameter can be a value of @ref DFSDM_Channel_SpiClock */
89 }DFSDM_Channel_SerialInterfaceTypeDef;
91 /**
92 * @brief DFSDM channel analog watchdog structure definition
93 */
94 typedef struct
96 uint32_t FilterOrder; /*!< Analog watchdog Sinc filter order.
97 This parameter can be a value of @ref DFSDM_Channel_AwdFilterOrder */
98 uint32_t Oversampling; /*!< Analog watchdog filter oversampling ratio.
99 This parameter must be a number between Min_Data = 1 and Max_Data = 32 */
100 }DFSDM_Channel_AwdTypeDef;
102 /**
103 * @brief DFSDM channel init structure definition
105 typedef struct
107 DFSDM_Channel_OutputClockTypeDef OutputClock; /*!< DFSDM channel output clock parameters */
108 DFSDM_Channel_InputTypeDef Input; /*!< DFSDM channel input parameters */
109 DFSDM_Channel_SerialInterfaceTypeDef SerialInterface; /*!< DFSDM channel serial interface parameters */
110 DFSDM_Channel_AwdTypeDef Awd; /*!< DFSDM channel analog watchdog parameters */
111 int32_t Offset; /*!< DFSDM channel offset.
112 This parameter must be a number between Min_Data = -8388608 and Max_Data = 8388607 */
113 uint32_t RightBitShift; /*!< DFSDM channel right bit shift.
114 This parameter must be a number between Min_Data = 0x00 and Max_Data = 0x1F */
115 }DFSDM_Channel_InitTypeDef;
117 /**
118 * @brief DFSDM channel handle structure definition
120 #if (USE_HAL_DFSDM_REGISTER_CALLBACKS == 1)
121 typedef struct __DFSDM_Channel_HandleTypeDef
122 #else
123 typedef struct
124 #endif /* USE_HAL_DFSDM_REGISTER_CALLBACKS */
126 DFSDM_Channel_TypeDef *Instance; /*!< DFSDM channel instance */
127 DFSDM_Channel_InitTypeDef Init; /*!< DFSDM channel init parameters */
128 HAL_DFSDM_Channel_StateTypeDef State; /*!< DFSDM channel state */
129 #if (USE_HAL_DFSDM_REGISTER_CALLBACKS == 1)
130 void (*CkabCallback) (struct __DFSDM_Channel_HandleTypeDef *hdfsdm_channel); /*!< DFSDM channel clock absence detection callback */
131 void (*ScdCallback) (struct __DFSDM_Channel_HandleTypeDef *hdfsdm_channel); /*!< DFSDM channel short circuit detection callback */
132 void (*MspInitCallback) (struct __DFSDM_Channel_HandleTypeDef *hdfsdm_channel); /*!< DFSDM channel MSP init callback */
133 void (*MspDeInitCallback) (struct __DFSDM_Channel_HandleTypeDef *hdfsdm_channel); /*!< DFSDM channel MSP de-init callback */
134 #endif
135 }DFSDM_Channel_HandleTypeDef;
137 #if (USE_HAL_DFSDM_REGISTER_CALLBACKS == 1)
139 * @brief DFSDM channel callback ID enumeration definition
141 typedef enum
143 HAL_DFSDM_CHANNEL_CKAB_CB_ID = 0x00U, /*!< DFSDM channel clock absence detection callback ID */
144 HAL_DFSDM_CHANNEL_SCD_CB_ID = 0x01U, /*!< DFSDM channel short circuit detection callback ID */
145 HAL_DFSDM_CHANNEL_MSPINIT_CB_ID = 0x02U, /*!< DFSDM channel MSP init callback ID */
146 HAL_DFSDM_CHANNEL_MSPDEINIT_CB_ID = 0x03U /*!< DFSDM channel MSP de-init callback ID */
147 }HAL_DFSDM_Channel_CallbackIDTypeDef;
150 * @brief DFSDM channel callback pointer definition
152 typedef void (*pDFSDM_Channel_CallbackTypeDef)(DFSDM_Channel_HandleTypeDef *hdfsdm_channel);
153 #endif
154 /**
155 * @brief HAL DFSDM Filter states definition
157 typedef enum
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;
167 /**
168 * @brief DFSDM filter regular conversion parameters structure definition
170 typedef struct
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;
178 /**
179 * @brief DFSDM filter injected conversion parameters structure definition
181 typedef struct
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;
193 /**
194 * @brief DFSDM filter parameters structure definition
196 typedef struct
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;
206 /**
207 * @brief DFSDM filter init structure definition
209 typedef struct
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;
216 /**
217 * @brief DFSDM filter handle structure definition
219 #if (USE_HAL_DFSDM_REGISTER_CALLBACKS == 1)
220 typedef struct __DFSDM_Filter_HandleTypeDef
221 #else
222 typedef struct
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 */
248 #endif
249 }DFSDM_Filter_HandleTypeDef;
251 /**
252 * @brief DFSDM filter analog watchdog parameters structure definition
254 typedef struct
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
274 typedef enum
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);
290 #endif
292 * @}
294 /* End of exported types -----------------------------------------------------*/
296 /* Exported constants --------------------------------------------------------*/
297 /** @defgroup DFSDM_Exported_Constants DFSDM Exported Constants
298 * @{
301 /** @defgroup DFSDM_Channel_OuputClock DFSDM channel output clock selection
302 * @{
304 #define DFSDM_CHANNEL_OUTPUT_CLOCK_SYSTEM ((uint32_t)0x00000000U) /*!< Source for ouput clock is system clock */
305 #define DFSDM_CHANNEL_OUTPUT_CLOCK_AUDIO DFSDM_CHCFGR1_CKOUTSRC /*!< Source for ouput clock is audio clock */
307 * @}
310 /** @defgroup DFSDM_Channel_InputMultiplexer DFSDM channel input multiplexer
311 * @{
313 #define DFSDM_CHANNEL_EXTERNAL_INPUTS ((uint32_t)0x00000000U) /*!< Data are taken from external inputs */
314 #define DFSDM_CHANNEL_INTERNAL_REGISTER DFSDM_CHCFGR1_DATMPX_1 /*!< Data are taken from internal register */
316 * @}
319 /** @defgroup DFSDM_Channel_DataPacking DFSDM channel input data packing
320 * @{
322 #define DFSDM_CHANNEL_STANDARD_MODE ((uint32_t)0x00000000U) /*!< Standard data packing mode */
323 #define DFSDM_CHANNEL_INTERLEAVED_MODE DFSDM_CHCFGR1_DATPACK_0 /*!< Interleaved data packing mode */
324 #define DFSDM_CHANNEL_DUAL_MODE DFSDM_CHCFGR1_DATPACK_1 /*!< Dual data packing mode */
326 * @}
329 /** @defgroup DFSDM_Channel_InputPins DFSDM channel input pins
330 * @{
332 #define DFSDM_CHANNEL_SAME_CHANNEL_PINS ((uint32_t)0x00000000U) /*!< Input from pins on same channel */
333 #define DFSDM_CHANNEL_FOLLOWING_CHANNEL_PINS DFSDM_CHCFGR1_CHINSEL /*!< Input from pins on following channel */
335 * @}
338 /** @defgroup DFSDM_Channel_SerialInterfaceType DFSDM channel serial interface type
339 * @{
341 #define DFSDM_CHANNEL_SPI_RISING ((uint32_t)0x00000000U) /*!< SPI with rising edge */
342 #define DFSDM_CHANNEL_SPI_FALLING DFSDM_CHCFGR1_SITP_0 /*!< SPI with falling edge */
343 #define DFSDM_CHANNEL_MANCHESTER_RISING DFSDM_CHCFGR1_SITP_1 /*!< Manchester with rising edge */
344 #define DFSDM_CHANNEL_MANCHESTER_FALLING DFSDM_CHCFGR1_SITP /*!< Manchester with falling edge */
346 * @}
349 /** @defgroup DFSDM_Channel_SpiClock DFSDM channel SPI clock selection
350 * @{
352 #define DFSDM_CHANNEL_SPI_CLOCK_EXTERNAL ((uint32_t)0x00000000U) /*!< External SPI clock */
353 #define DFSDM_CHANNEL_SPI_CLOCK_INTERNAL DFSDM_CHCFGR1_SPICKSEL_0 /*!< Internal SPI clock */
354 #define DFSDM_CHANNEL_SPI_CLOCK_INTERNAL_DIV2_FALLING DFSDM_CHCFGR1_SPICKSEL_1 /*!< Internal SPI clock divided by 2, falling edge */
355 #define DFSDM_CHANNEL_SPI_CLOCK_INTERNAL_DIV2_RISING DFSDM_CHCFGR1_SPICKSEL /*!< Internal SPI clock divided by 2, rising edge */
357 * @}
360 /** @defgroup DFSDM_Channel_AwdFilterOrder DFSDM channel analog watchdog filter order
361 * @{
363 #define DFSDM_CHANNEL_FASTSINC_ORDER ((uint32_t)0x00000000U) /*!< FastSinc filter type */
364 #define DFSDM_CHANNEL_SINC1_ORDER DFSDM_CHAWSCDR_AWFORD_0 /*!< Sinc 1 filter type */
365 #define DFSDM_CHANNEL_SINC2_ORDER DFSDM_CHAWSCDR_AWFORD_1 /*!< Sinc 2 filter type */
366 #define DFSDM_CHANNEL_SINC3_ORDER DFSDM_CHAWSCDR_AWFORD /*!< Sinc 3 filter type */
368 * @}
371 /** @defgroup DFSDM_Filter_Trigger DFSDM filter conversion trigger
372 * @{
374 #define DFSDM_FILTER_SW_TRIGGER ((uint32_t)0x00000000U) /*!< Software trigger */
375 #define DFSDM_FILTER_SYNC_TRIGGER ((uint32_t)0x00000001U) /*!< Synchronous with DFSDM_FLT0 */
376 #define DFSDM_FILTER_EXT_TRIGGER ((uint32_t)0x00000002U) /*!< External trigger (only for injected conversion) */
378 * @}
381 /** @defgroup DFSDM_Filter_ExtTrigger DFSDM filter external trigger
382 * @{
384 #define DFSDM_FILTER_EXT_TRIG_TIM1_TRGO ((uint32_t)0x00000000U) /*!< For DFSDM filter 0, 1, 2 and 3 */
385 #define DFSDM_FILTER_EXT_TRIG_TIM1_TRGO2 DFSDM_FLTCR1_JEXTSEL_0 /*!< For DFSDM filter 0, 1, 2 and 3 */
386 #define DFSDM_FILTER_EXT_TRIG_TIM8_TRGO DFSDM_FLTCR1_JEXTSEL_1 /*!< For DFSDM filter 0, 1, 2 and 3 */
387 #define DFSDM_FILTER_EXT_TRIG_TIM8_TRGO2 (DFSDM_FLTCR1_JEXTSEL_0 | DFSDM_FLTCR1_JEXTSEL_1) /*!< For DFSDM filter 0, 1, 2 and 3 */
388 #define DFSDM_FILTER_EXT_TRIG_TIM3_TRGO DFSDM_FLTCR1_JEXTSEL_2 /*!< For DFSDM filter 0, 1, 2 and 3 */
389 #define DFSDM_FILTER_EXT_TRIG_TIM4_TRGO (DFSDM_FLTCR1_JEXTSEL_0 | DFSDM_FLTCR1_JEXTSEL_2) /*!< For DFSDM filter 0, 1, 2 and 3 */
390 #define DFSDM_FILTER_EXT_TRIG_TIM10_OC1 (DFSDM_FLTCR1_JEXTSEL_1 | DFSDM_FLTCR1_JEXTSEL_2) /*!< For DFSDM filter 0, 1, 2 and 3 */
391 #define DFSDM_FILTER_EXT_TRIG_TIM6_TRGO (DFSDM_FLTCR1_JEXTSEL_0 | DFSDM_FLTCR1_JEXTSEL_1 | \
392 DFSDM_FLTCR1_JEXTSEL_2) /*!< For DFSDM filter 0, 1, 2 and 3 */
393 #define DFSDM_FILTER_EXT_TRIG_TIM7_TRGO DFSDM_FLTCR1_JEXTSEL_3 /*!< For DFSDM filter 0, 1, 2 and 3 */
394 #define DFSDM_FILTER_EXT_TRIG_EXTI11 (DFSDM_FLTCR1_JEXTSEL_3 | DFSDM_FLTCR1_JEXTSEL_4) /*!< For DFSDM filter 0, 1, 2 and 3 */
395 #define DFSDM_FILTER_EXT_TRIG_EXTI15 (DFSDM_FLTCR1_JEXTSEL_0 | DFSDM_FLTCR1_JEXTSEL_3 | \
396 DFSDM_FLTCR1_JEXTSEL_4) /*!< For DFSDM filter 0, 1, 2 and 3 */
397 #define DFSDM_FILTER_EXT_TRIG_LPTIM1_OUT (DFSDM_FLTCR1_JEXTSEL_1 | DFSDM_FLTCR1_JEXTSEL_3 | \
398 DFSDM_FLTCR1_JEXTSEL_4) /*!< For DFSDM filter 0, 1, 2 and 3 */
400 * @}
403 /** @defgroup DFSDM_Filter_ExtTriggerEdge DFSDM filter external trigger edge
404 * @{
406 #define DFSDM_FILTER_EXT_TRIG_RISING_EDGE DFSDM_FLTCR1_JEXTEN_0 /*!< External rising edge */
407 #define DFSDM_FILTER_EXT_TRIG_FALLING_EDGE DFSDM_FLTCR1_JEXTEN_1 /*!< External falling edge */
408 #define DFSDM_FILTER_EXT_TRIG_BOTH_EDGES DFSDM_FLTCR1_JEXTEN /*!< External rising and falling edges */
410 * @}
413 /** @defgroup DFSDM_Filter_SincOrder DFSDM filter sinc order
414 * @{
416 #define DFSDM_FILTER_FASTSINC_ORDER ((uint32_t)0x00000000U) /*!< FastSinc filter type */
417 #define DFSDM_FILTER_SINC1_ORDER DFSDM_FLTFCR_FORD_0 /*!< Sinc 1 filter type */
418 #define DFSDM_FILTER_SINC2_ORDER DFSDM_FLTFCR_FORD_1 /*!< Sinc 2 filter type */
419 #define DFSDM_FILTER_SINC3_ORDER (DFSDM_FLTFCR_FORD_0 | DFSDM_FLTFCR_FORD_1) /*!< Sinc 3 filter type */
420 #define DFSDM_FILTER_SINC4_ORDER DFSDM_FLTFCR_FORD_2 /*!< Sinc 4 filter type */
421 #define DFSDM_FILTER_SINC5_ORDER (DFSDM_FLTFCR_FORD_0 | DFSDM_FLTFCR_FORD_2) /*!< Sinc 5 filter type */
423 * @}
426 /** @defgroup DFSDM_Filter_AwdDataSource DFSDM filter analog watchdog data source
427 * @{
429 #define DFSDM_FILTER_AWD_FILTER_DATA ((uint32_t)0x00000000U) /*!< From digital filter */
430 #define DFSDM_FILTER_AWD_CHANNEL_DATA DFSDM_FLTCR1_AWFSEL /*!< From analog watchdog channel */
432 * @}
435 /** @defgroup DFSDM_Filter_ErrorCode DFSDM filter error code
436 * @{
438 #define DFSDM_FILTER_ERROR_NONE ((uint32_t)0x00000000U) /*!< No error */
439 #define DFSDM_FILTER_ERROR_REGULAR_OVERRUN ((uint32_t)0x00000001U) /*!< Overrun occurs during regular conversion */
440 #define DFSDM_FILTER_ERROR_INJECTED_OVERRUN ((uint32_t)0x00000002U) /*!< Overrun occurs during injected conversion */
441 #define DFSDM_FILTER_ERROR_DMA ((uint32_t)0x00000003U) /*!< DMA error occurs */
442 #if (USE_HAL_DFSDM_REGISTER_CALLBACKS == 1)
443 #define DFSDM_FILTER_ERROR_INVALID_CALLBACK ((uint32_t)0x00000004U) /*!< Invalid callback error occurs */
444 #endif
446 * @}
449 /** @defgroup DFSDM_BreakSignals DFSDM break signals
450 * @{
452 #define DFSDM_NO_BREAK_SIGNAL ((uint32_t)0x00000000U) /*!< No break signal */
453 #define DFSDM_BREAK_SIGNAL_0 ((uint32_t)0x00000001U) /*!< Break signal 0 */
454 #define DFSDM_BREAK_SIGNAL_1 ((uint32_t)0x00000002U) /*!< Break signal 1 */
455 #define DFSDM_BREAK_SIGNAL_2 ((uint32_t)0x00000004U) /*!< Break signal 2 */
456 #define DFSDM_BREAK_SIGNAL_3 ((uint32_t)0x00000008U) /*!< Break signal 3 */
458 * @}
461 /** @defgroup DFSDM_Channel_Selection DFSDM Channel Selection
462 * @{
464 /* DFSDM Channels ------------------------------------------------------------*/
465 /* The DFSDM channels are defined as follows:
466 - in 16-bit LSB the channel mask is set
467 - in 16-bit MSB the channel number is set
468 e.g. for channel 5 definition:
469 - the channel mask is 0x00000020 (bit 5 is set)
470 - the channel number 5 is 0x00050000
471 --> Consequently, channel 5 definition is 0x00000020 | 0x00050000 = 0x00050020 */
472 #define DFSDM_CHANNEL_0 ((uint32_t)0x00000001U)
473 #define DFSDM_CHANNEL_1 ((uint32_t)0x00010002U)
474 #define DFSDM_CHANNEL_2 ((uint32_t)0x00020004U)
475 #define DFSDM_CHANNEL_3 ((uint32_t)0x00030008U)
476 #define DFSDM_CHANNEL_4 ((uint32_t)0x00040010U)
477 #define DFSDM_CHANNEL_5 ((uint32_t)0x00050020U)
478 #define DFSDM_CHANNEL_6 ((uint32_t)0x00060040U)
479 #define DFSDM_CHANNEL_7 ((uint32_t)0x00070080U)
481 * @}
484 /** @defgroup DFSDM_ContinuousMode DFSDM Continuous Mode
485 * @{
487 #define DFSDM_CONTINUOUS_CONV_OFF ((uint32_t)0x00000000U) /*!< Conversion are not continuous */
488 #define DFSDM_CONTINUOUS_CONV_ON ((uint32_t)0x00000001U) /*!< Conversion are continuous */
490 * @}
493 /** @defgroup DFSDM_AwdThreshold DFSDM analog watchdog threshold
494 * @{
496 #define DFSDM_AWD_HIGH_THRESHOLD ((uint32_t)0x00000000U) /*!< Analog watchdog high threshold */
497 #define DFSDM_AWD_LOW_THRESHOLD ((uint32_t)0x00000001U) /*!< Analog watchdog low threshold */
499 * @}
503 * @}
505 /* End of exported constants -------------------------------------------------*/
507 /* Exported macros -----------------------------------------------------------*/
508 /** @defgroup DFSDM_Exported_Macros DFSDM Exported Macros
509 * @{
512 /** @brief Reset DFSDM channel handle state.
513 * @param __HANDLE__: DFSDM channel handle.
514 * @retval None
516 #if (USE_HAL_DFSDM_REGISTER_CALLBACKS == 1)
517 #define __HAL_DFSDM_CHANNEL_RESET_HANDLE_STATE(__HANDLE__) do{ \
518 (__HANDLE__)->State = HAL_DFSDM_CHANNEL_STATE_RESET; \
519 (__HANDLE__)->MspInitCallback = NULL; \
520 (__HANDLE__)->MspDeInitCallback = NULL; \
521 } while(0)
522 #else
523 #define __HAL_DFSDM_CHANNEL_RESET_HANDLE_STATE(__HANDLE__) ((__HANDLE__)->State = HAL_DFSDM_CHANNEL_STATE_RESET)
524 #endif
526 /** @brief Reset DFSDM filter handle state.
527 * @param __HANDLE__: DFSDM filter handle.
528 * @retval None
530 #if (USE_HAL_DFSDM_REGISTER_CALLBACKS == 1)
531 #define __HAL_DFSDM_FILTER_RESET_HANDLE_STATE(__HANDLE__) do{ \
532 (__HANDLE__)->State = HAL_DFSDM_FILTER_STATE_RESET; \
533 (__HANDLE__)->MspInitCallback = NULL; \
534 (__HANDLE__)->MspDeInitCallback = NULL; \
535 } while(0)
536 #else
537 #define __HAL_DFSDM_FILTER_RESET_HANDLE_STATE(__HANDLE__) ((__HANDLE__)->State = HAL_DFSDM_FILTER_STATE_RESET)
538 #endif
541 * @}
543 /* End of exported macros ----------------------------------------------------*/
545 /* Exported functions --------------------------------------------------------*/
546 /** @addtogroup DFSDM_Exported_Functions DFSDM Exported Functions
547 * @{
550 /** @addtogroup DFSDM_Exported_Functions_Group1_Channel Channel initialization and de-initialization functions
551 * @{
553 /* Channel initialization and de-initialization functions *********************/
554 HAL_StatusTypeDef HAL_DFSDM_ChannelInit(DFSDM_Channel_HandleTypeDef *hdfsdm_channel);
555 HAL_StatusTypeDef HAL_DFSDM_ChannelDeInit(DFSDM_Channel_HandleTypeDef *hdfsdm_channel);
556 void HAL_DFSDM_ChannelMspInit(DFSDM_Channel_HandleTypeDef *hdfsdm_channel);
557 void HAL_DFSDM_ChannelMspDeInit(DFSDM_Channel_HandleTypeDef *hdfsdm_channel);
559 #if (USE_HAL_DFSDM_REGISTER_CALLBACKS == 1)
560 /* Channel callbacks register/unregister functions ****************************/
561 HAL_StatusTypeDef HAL_DFSDM_Channel_RegisterCallback(DFSDM_Channel_HandleTypeDef *hdfsdm_channel,
562 HAL_DFSDM_Channel_CallbackIDTypeDef CallbackID,
563 pDFSDM_Channel_CallbackTypeDef pCallback);
564 HAL_StatusTypeDef HAL_DFSDM_Channel_UnRegisterCallback(DFSDM_Channel_HandleTypeDef *hdfsdm_channel,
565 HAL_DFSDM_Channel_CallbackIDTypeDef CallbackID);
566 #endif
568 * @}
571 /** @addtogroup DFSDM_Exported_Functions_Group2_Channel Channel operation functions
572 * @{
574 /* Channel operation functions ************************************************/
575 HAL_StatusTypeDef HAL_DFSDM_ChannelCkabStart(DFSDM_Channel_HandleTypeDef *hdfsdm_channel);
576 HAL_StatusTypeDef HAL_DFSDM_ChannelCkabStart_IT(DFSDM_Channel_HandleTypeDef *hdfsdm_channel);
577 HAL_StatusTypeDef HAL_DFSDM_ChannelCkabStop(DFSDM_Channel_HandleTypeDef *hdfsdm_channel);
578 HAL_StatusTypeDef HAL_DFSDM_ChannelCkabStop_IT(DFSDM_Channel_HandleTypeDef *hdfsdm_channel);
580 HAL_StatusTypeDef HAL_DFSDM_ChannelScdStart(DFSDM_Channel_HandleTypeDef *hdfsdm_channel, uint32_t Threshold, uint32_t BreakSignal);
581 HAL_StatusTypeDef HAL_DFSDM_ChannelScdStart_IT(DFSDM_Channel_HandleTypeDef *hdfsdm_channel, uint32_t Threshold, uint32_t BreakSignal);
582 HAL_StatusTypeDef HAL_DFSDM_ChannelScdStop(DFSDM_Channel_HandleTypeDef *hdfsdm_channel);
583 HAL_StatusTypeDef HAL_DFSDM_ChannelScdStop_IT(DFSDM_Channel_HandleTypeDef *hdfsdm_channel);
585 int16_t HAL_DFSDM_ChannelGetAwdValue(DFSDM_Channel_HandleTypeDef *hdfsdm_channel);
586 HAL_StatusTypeDef HAL_DFSDM_ChannelModifyOffset(DFSDM_Channel_HandleTypeDef *hdfsdm_channel, int32_t Offset);
588 HAL_StatusTypeDef HAL_DFSDM_ChannelPollForCkab(DFSDM_Channel_HandleTypeDef *hdfsdm_channel, uint32_t Timeout);
589 HAL_StatusTypeDef HAL_DFSDM_ChannelPollForScd(DFSDM_Channel_HandleTypeDef *hdfsdm_channel, uint32_t Timeout);
591 void HAL_DFSDM_ChannelCkabCallback(DFSDM_Channel_HandleTypeDef *hdfsdm_channel);
592 void HAL_DFSDM_ChannelScdCallback(DFSDM_Channel_HandleTypeDef *hdfsdm_channel);
594 * @}
597 /** @defgroup DFSDM_Exported_Functions_Group3_Channel Channel state function
598 * @{
600 /* Channel state function *****************************************************/
601 HAL_DFSDM_Channel_StateTypeDef HAL_DFSDM_ChannelGetState(DFSDM_Channel_HandleTypeDef *hdfsdm_channel);
603 * @}
606 /** @addtogroup DFSDM_Exported_Functions_Group1_Filter Filter initialization and de-initialization functions
607 * @{
609 /* Filter initialization and de-initialization functions *********************/
610 HAL_StatusTypeDef HAL_DFSDM_FilterInit(DFSDM_Filter_HandleTypeDef *hdfsdm_filter);
611 HAL_StatusTypeDef HAL_DFSDM_FilterDeInit(DFSDM_Filter_HandleTypeDef *hdfsdm_filter);
612 void HAL_DFSDM_FilterMspInit(DFSDM_Filter_HandleTypeDef *hdfsdm_filter);
613 void HAL_DFSDM_FilterMspDeInit(DFSDM_Filter_HandleTypeDef *hdfsdm_filter);
615 #if (USE_HAL_DFSDM_REGISTER_CALLBACKS == 1)
616 /* Filter callbacks register/unregister functions ****************************/
617 HAL_StatusTypeDef HAL_DFSDM_Filter_RegisterCallback(DFSDM_Filter_HandleTypeDef *hdfsdm_filter,
618 HAL_DFSDM_Filter_CallbackIDTypeDef CallbackID,
619 pDFSDM_Filter_CallbackTypeDef pCallback);
620 HAL_StatusTypeDef HAL_DFSDM_Filter_UnRegisterCallback(DFSDM_Filter_HandleTypeDef *hdfsdm_filter,
621 HAL_DFSDM_Filter_CallbackIDTypeDef CallbackID);
622 HAL_StatusTypeDef HAL_DFSDM_Filter_RegisterAwdCallback(DFSDM_Filter_HandleTypeDef *hdfsdm_filter,
623 pDFSDM_Filter_AwdCallbackTypeDef pCallback);
624 HAL_StatusTypeDef HAL_DFSDM_Filter_UnRegisterAwdCallback(DFSDM_Filter_HandleTypeDef *hdfsdm_filter);
625 #endif
627 * @}
630 /** @addtogroup DFSDM_Exported_Functions_Group2_Filter Filter control functions
631 * @{
633 /* Filter control functions *********************/
634 HAL_StatusTypeDef HAL_DFSDM_FilterConfigRegChannel(DFSDM_Filter_HandleTypeDef *hdfsdm_filter,
635 uint32_t Channel,
636 uint32_t ContinuousMode);
637 HAL_StatusTypeDef HAL_DFSDM_FilterConfigInjChannel(DFSDM_Filter_HandleTypeDef *hdfsdm_filter,
638 uint32_t Channel);
640 * @}
643 /** @addtogroup DFSDM_Exported_Functions_Group3_Filter Filter operation functions
644 * @{
646 /* Filter operation functions *********************/
647 HAL_StatusTypeDef HAL_DFSDM_FilterRegularStart(DFSDM_Filter_HandleTypeDef *hdfsdm_filter);
648 HAL_StatusTypeDef HAL_DFSDM_FilterRegularStart_IT(DFSDM_Filter_HandleTypeDef *hdfsdm_filter);
649 HAL_StatusTypeDef HAL_DFSDM_FilterRegularStart_DMA(DFSDM_Filter_HandleTypeDef *hdfsdm_filter, int32_t *pData, uint32_t Length);
650 HAL_StatusTypeDef HAL_DFSDM_FilterRegularMsbStart_DMA(DFSDM_Filter_HandleTypeDef *hdfsdm_filter, int16_t *pData, uint32_t Length);
651 HAL_StatusTypeDef HAL_DFSDM_FilterRegularStop(DFSDM_Filter_HandleTypeDef *hdfsdm_filter);
652 HAL_StatusTypeDef HAL_DFSDM_FilterRegularStop_IT(DFSDM_Filter_HandleTypeDef *hdfsdm_filter);
653 HAL_StatusTypeDef HAL_DFSDM_FilterRegularStop_DMA(DFSDM_Filter_HandleTypeDef *hdfsdm_filter);
654 HAL_StatusTypeDef HAL_DFSDM_FilterInjectedStart(DFSDM_Filter_HandleTypeDef *hdfsdm_filter);
655 HAL_StatusTypeDef HAL_DFSDM_FilterInjectedStart_IT(DFSDM_Filter_HandleTypeDef *hdfsdm_filter);
656 HAL_StatusTypeDef HAL_DFSDM_FilterInjectedStart_DMA(DFSDM_Filter_HandleTypeDef *hdfsdm_filter, int32_t *pData, uint32_t Length);
657 HAL_StatusTypeDef HAL_DFSDM_FilterInjectedMsbStart_DMA(DFSDM_Filter_HandleTypeDef *hdfsdm_filter, int16_t *pData, uint32_t Length);
658 HAL_StatusTypeDef HAL_DFSDM_FilterInjectedStop(DFSDM_Filter_HandleTypeDef *hdfsdm_filter);
659 HAL_StatusTypeDef HAL_DFSDM_FilterInjectedStop_IT(DFSDM_Filter_HandleTypeDef *hdfsdm_filter);
660 HAL_StatusTypeDef HAL_DFSDM_FilterInjectedStop_DMA(DFSDM_Filter_HandleTypeDef *hdfsdm_filter);
661 HAL_StatusTypeDef HAL_DFSDM_FilterAwdStart_IT(DFSDM_Filter_HandleTypeDef *hdfsdm_filter,
662 DFSDM_Filter_AwdParamTypeDef* awdParam);
663 HAL_StatusTypeDef HAL_DFSDM_FilterAwdStop_IT(DFSDM_Filter_HandleTypeDef *hdfsdm_filter);
664 HAL_StatusTypeDef HAL_DFSDM_FilterExdStart(DFSDM_Filter_HandleTypeDef *hdfsdm_filter, uint32_t Channel);
665 HAL_StatusTypeDef HAL_DFSDM_FilterExdStop(DFSDM_Filter_HandleTypeDef *hdfsdm_filter);
667 int32_t HAL_DFSDM_FilterGetRegularValue(DFSDM_Filter_HandleTypeDef *hdfsdm_filter, uint32_t* Channel);
668 int32_t HAL_DFSDM_FilterGetInjectedValue(DFSDM_Filter_HandleTypeDef *hdfsdm_filter, uint32_t* Channel);
669 int32_t HAL_DFSDM_FilterGetExdMaxValue(DFSDM_Filter_HandleTypeDef *hdfsdm_filter, uint32_t* Channel);
670 int32_t HAL_DFSDM_FilterGetExdMinValue(DFSDM_Filter_HandleTypeDef *hdfsdm_filter, uint32_t* Channel);
671 uint32_t HAL_DFSDM_FilterGetConvTimeValue(DFSDM_Filter_HandleTypeDef *hdfsdm_filter);
673 void HAL_DFSDM_IRQHandler(DFSDM_Filter_HandleTypeDef *hdfsdm_filter);
675 HAL_StatusTypeDef HAL_DFSDM_FilterPollForRegConversion(DFSDM_Filter_HandleTypeDef *hdfsdm_filter, uint32_t Timeout);
676 HAL_StatusTypeDef HAL_DFSDM_FilterPollForInjConversion(DFSDM_Filter_HandleTypeDef *hdfsdm_filter, uint32_t Timeout);
678 void HAL_DFSDM_FilterRegConvCpltCallback(DFSDM_Filter_HandleTypeDef *hdfsdm_filter);
679 void HAL_DFSDM_FilterRegConvHalfCpltCallback(DFSDM_Filter_HandleTypeDef *hdfsdm_filter);
680 void HAL_DFSDM_FilterInjConvCpltCallback(DFSDM_Filter_HandleTypeDef *hdfsdm_filter);
681 void HAL_DFSDM_FilterInjConvHalfCpltCallback(DFSDM_Filter_HandleTypeDef *hdfsdm_filter);
682 void HAL_DFSDM_FilterAwdCallback(DFSDM_Filter_HandleTypeDef *hdfsdm_filter, uint32_t Channel, uint32_t Threshold);
683 void HAL_DFSDM_FilterErrorCallback(DFSDM_Filter_HandleTypeDef *hdfsdm_filter);
685 * @}
688 /** @defgroup DFSDM_Exported_Functions_Group4_Filter Filter state functions
689 * @{
691 /* Filter state functions *****************************************************/
692 HAL_DFSDM_Filter_StateTypeDef HAL_DFSDM_FilterGetState(DFSDM_Filter_HandleTypeDef *hdfsdm_filter);
693 uint32_t HAL_DFSDM_FilterGetError(DFSDM_Filter_HandleTypeDef *hdfsdm_filter);
695 * @}
699 * @}
701 /* End of exported functions -------------------------------------------------*/
703 /* Private macros ------------------------------------------------------------*/
704 /** @defgroup DFSDM_Private_Macros DFSDM Private Macros
705 * @{
707 #define IS_DFSDM_CHANNEL_OUTPUT_CLOCK(CLOCK) (((CLOCK) == DFSDM_CHANNEL_OUTPUT_CLOCK_SYSTEM) || \
708 ((CLOCK) == DFSDM_CHANNEL_OUTPUT_CLOCK_AUDIO))
709 #define IS_DFSDM_CHANNEL_OUTPUT_CLOCK_DIVIDER(DIVIDER) ((2 <= (DIVIDER)) && ((DIVIDER) <= 256))
710 #define IS_DFSDM_CHANNEL_INPUT(INPUT) (((INPUT) == DFSDM_CHANNEL_EXTERNAL_INPUTS) || \
711 ((INPUT) == DFSDM_CHANNEL_INTERNAL_REGISTER))
712 #define IS_DFSDM_CHANNEL_DATA_PACKING(MODE) (((MODE) == DFSDM_CHANNEL_STANDARD_MODE) || \
713 ((MODE) == DFSDM_CHANNEL_INTERLEAVED_MODE) || \
714 ((MODE) == DFSDM_CHANNEL_DUAL_MODE))
715 #define IS_DFSDM_CHANNEL_INPUT_PINS(PINS) (((PINS) == DFSDM_CHANNEL_SAME_CHANNEL_PINS) || \
716 ((PINS) == DFSDM_CHANNEL_FOLLOWING_CHANNEL_PINS))
717 #define IS_DFSDM_CHANNEL_SERIAL_INTERFACE_TYPE(MODE) (((MODE) == DFSDM_CHANNEL_SPI_RISING) || \
718 ((MODE) == DFSDM_CHANNEL_SPI_FALLING) || \
719 ((MODE) == DFSDM_CHANNEL_MANCHESTER_RISING) || \
720 ((MODE) == DFSDM_CHANNEL_MANCHESTER_FALLING))
721 #define IS_DFSDM_CHANNEL_SPI_CLOCK(TYPE) (((TYPE) == DFSDM_CHANNEL_SPI_CLOCK_EXTERNAL) || \
722 ((TYPE) == DFSDM_CHANNEL_SPI_CLOCK_INTERNAL) || \
723 ((TYPE) == DFSDM_CHANNEL_SPI_CLOCK_INTERNAL_DIV2_FALLING) || \
724 ((TYPE) == DFSDM_CHANNEL_SPI_CLOCK_INTERNAL_DIV2_RISING))
725 #define IS_DFSDM_CHANNEL_FILTER_ORDER(ORDER) (((ORDER) == DFSDM_CHANNEL_FASTSINC_ORDER) || \
726 ((ORDER) == DFSDM_CHANNEL_SINC1_ORDER) || \
727 ((ORDER) == DFSDM_CHANNEL_SINC2_ORDER) || \
728 ((ORDER) == DFSDM_CHANNEL_SINC3_ORDER))
729 #define IS_DFSDM_CHANNEL_FILTER_OVS_RATIO(RATIO) ((1 <= (RATIO)) && ((RATIO) <= 32))
730 #define IS_DFSDM_CHANNEL_OFFSET(VALUE) ((-8388608 <= (VALUE)) && ((VALUE) <= 8388607))
731 #define IS_DFSDM_CHANNEL_RIGHT_BIT_SHIFT(VALUE) ((VALUE) <= 0x1F)
732 #define IS_DFSDM_CHANNEL_SCD_THRESHOLD(VALUE) ((VALUE) <= 0xFF)
733 #define IS_DFSDM_FILTER_REG_TRIGGER(TRIG) (((TRIG) == DFSDM_FILTER_SW_TRIGGER) || \
734 ((TRIG) == DFSDM_FILTER_SYNC_TRIGGER))
735 #define IS_DFSDM_FILTER_INJ_TRIGGER(TRIG) (((TRIG) == DFSDM_FILTER_SW_TRIGGER) || \
736 ((TRIG) == DFSDM_FILTER_SYNC_TRIGGER) || \
737 ((TRIG) == DFSDM_FILTER_EXT_TRIGGER))
738 #define IS_DFSDM_FILTER_EXT_TRIG(TRIG) (((TRIG) == DFSDM_FILTER_EXT_TRIG_TIM1_TRGO) || \
739 ((TRIG) == DFSDM_FILTER_EXT_TRIG_TIM1_TRGO2)|| \
740 ((TRIG) == DFSDM_FILTER_EXT_TRIG_TIM8_TRGO) || \
741 ((TRIG) == DFSDM_FILTER_EXT_TRIG_TIM8_TRGO2)|| \
742 ((TRIG) == DFSDM_FILTER_EXT_TRIG_TIM3_TRGO) || \
743 ((TRIG) == DFSDM_FILTER_EXT_TRIG_TIM4_TRGO) || \
744 ((TRIG) == DFSDM_FILTER_EXT_TRIG_TIM10_OC1) || \
745 ((TRIG) == DFSDM_FILTER_EXT_TRIG_TIM6_TRGO) || \
746 ((TRIG) == DFSDM_FILTER_EXT_TRIG_TIM7_TRGO) || \
747 ((TRIG) == DFSDM_FILTER_EXT_TRIG_EXTI11) || \
748 ((TRIG) == DFSDM_FILTER_EXT_TRIG_EXTI15) ||\
749 ((TRIG) == DFSDM_FILTER_EXT_TRIG_LPTIM1_OUT))
750 #define IS_DFSDM_FILTER_EXT_TRIG_EDGE(EDGE) (((EDGE) == DFSDM_FILTER_EXT_TRIG_RISING_EDGE) || \
751 ((EDGE) == DFSDM_FILTER_EXT_TRIG_FALLING_EDGE) || \
752 ((EDGE) == DFSDM_FILTER_EXT_TRIG_BOTH_EDGES))
753 #define IS_DFSDM_FILTER_SINC_ORDER(ORDER) (((ORDER) == DFSDM_FILTER_FASTSINC_ORDER) || \
754 ((ORDER) == DFSDM_FILTER_SINC1_ORDER) || \
755 ((ORDER) == DFSDM_FILTER_SINC2_ORDER) || \
756 ((ORDER) == DFSDM_FILTER_SINC3_ORDER) || \
757 ((ORDER) == DFSDM_FILTER_SINC4_ORDER) || \
758 ((ORDER) == DFSDM_FILTER_SINC5_ORDER))
759 #define IS_DFSDM_FILTER_OVS_RATIO(RATIO) ((1 <= (RATIO)) && ((RATIO) <= 1024))
760 #define IS_DFSDM_FILTER_INTEGRATOR_OVS_RATIO(RATIO) ((1 <= (RATIO)) && ((RATIO) <= 256))
761 #define IS_DFSDM_FILTER_AWD_DATA_SOURCE(DATA) (((DATA) == DFSDM_FILTER_AWD_FILTER_DATA) || \
762 ((DATA) == DFSDM_FILTER_AWD_CHANNEL_DATA))
763 #define IS_DFSDM_FILTER_AWD_THRESHOLD(VALUE) ((-8388608 <= (VALUE)) && ((VALUE) <= 8388607))
764 #define IS_DFSDM_BREAK_SIGNALS(VALUE) ((VALUE) <= 0xFU)
765 #define IS_DFSDM_REGULAR_CHANNEL(CHANNEL) (((CHANNEL) == DFSDM_CHANNEL_0) || \
766 ((CHANNEL) == DFSDM_CHANNEL_1) || \
767 ((CHANNEL) == DFSDM_CHANNEL_2) || \
768 ((CHANNEL) == DFSDM_CHANNEL_3) || \
769 ((CHANNEL) == DFSDM_CHANNEL_4) || \
770 ((CHANNEL) == DFSDM_CHANNEL_5) || \
771 ((CHANNEL) == DFSDM_CHANNEL_6) || \
772 ((CHANNEL) == DFSDM_CHANNEL_7))
773 #define IS_DFSDM_INJECTED_CHANNEL(CHANNEL) (((CHANNEL) != 0) && ((CHANNEL) <= 0x000F00FFU))
774 #define IS_DFSDM_CONTINUOUS_MODE(MODE) (((MODE) == DFSDM_CONTINUOUS_CONV_OFF) || \
775 ((MODE) == DFSDM_CONTINUOUS_CONV_ON))
777 * @}
779 /* End of private macros -----------------------------------------------------*/
782 * @}
786 * @}
788 #endif /* STM32F765xx || STM32F767xx || STM32F769xx || STM32F777xx || STM32F779xx */
789 #ifdef __cplusplus
791 #endif
793 #endif /* __STM32F7xx_HAL_DFSDM_H */
795 /************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/