Create release.yml
[betaflight.git] / lib / main / STM32F4 / Drivers / STM32F4xx_HAL_Driver / Inc / stm32f4xx_hal_dfsdm.h
blobdb72ad9b0b55348f43d0a19f85a074175abe0180
1 /**
2 ******************************************************************************
3 * @file stm32f4xx_hal_dfsdm.h
4 * @author MCD Application Team
5 * @version V1.7.1
6 * @date 14-April-2017
7 * @brief Header file of DFSDM HAL module.
8 ******************************************************************************
9 * @attention
11 * <h2><center>&copy; COPYRIGHT(c) 2017 STMicroelectronics</center></h2>
13 * Redistribution and use in source and binary forms, with or without modification,
14 * are permitted provided that the following conditions are met:
15 * 1. Redistributions of source code must retain the above copyright notice,
16 * this list of conditions and the following disclaimer.
17 * 2. Redistributions in binary form must reproduce the above copyright notice,
18 * this list of conditions and the following disclaimer in the documentation
19 * and/or other materials provided with the distribution.
20 * 3. Neither the name of STMicroelectronics nor the names of its contributors
21 * may be used to endorse or promote products derived from this software
22 * without specific prior written permission.
24 * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
25 * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
26 * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE
27 * DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE
28 * FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL
29 * DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR
30 * SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
31 * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY,
32 * OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE
33 * OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
35 ******************************************************************************
38 /* Define to prevent recursive inclusion -------------------------------------*/
39 #ifndef __STM32F4xx_HAL_DFSDM_H
40 #define __STM32F4xx_HAL_DFSDM_H
42 #ifdef __cplusplus
43 extern "C" {
44 #endif
46 #if defined(STM32F412Zx) || defined(STM32F412Vx) || defined(STM32F412Rx) || defined(STM32F412Cx) || defined(STM32F413xx) || defined(STM32F423xx)
47 /* Includes ------------------------------------------------------------------*/
48 #include "stm32f4xx_hal_def.h"
50 /** @addtogroup STM32F4xx_HAL_Driver
51 * @{
54 /** @addtogroup DFSDM
55 * @{
56 */
58 /* Exported types ------------------------------------------------------------*/
59 /** @defgroup DFSDM_Exported_Types DFSDM Exported Types
60 * @{
63 /**
64 * @brief HAL DFSDM Channel states definition
65 */
66 typedef enum
68 HAL_DFSDM_CHANNEL_STATE_RESET = 0x00U, /*!< DFSDM channel not initialized */
69 HAL_DFSDM_CHANNEL_STATE_READY = 0x01U, /*!< DFSDM channel initialized and ready for use */
70 HAL_DFSDM_CHANNEL_STATE_ERROR = 0xFFU /*!< DFSDM channel state error */
71 }HAL_DFSDM_Channel_StateTypeDef;
73 /**
74 * @brief DFSDM channel output clock structure definition
75 */
76 typedef struct
78 FunctionalState Activation; /*!< Output clock enable/disable */
79 uint32_t Selection; /*!< Output clock is system clock or audio clock.
80 This parameter can be a value of @ref DFSDM_Channel_OuputClock */
81 uint32_t Divider; /*!< Output clock divider.
82 This parameter must be a number between Min_Data = 2 and Max_Data = 256 */
83 }DFSDM_Channel_OutputClockTypeDef;
85 /**
86 * @brief DFSDM channel input structure definition
87 */
88 typedef struct
90 uint32_t Multiplexer; /*!< Input is external serial inputs or internal register.
91 This parameter can be a value of @ref DFSDM_Channel_InputMultiplexer */
92 uint32_t DataPacking; /*!< Standard, interleaved or dual mode for internal register.
93 This parameter can be a value of @ref DFSDM_Channel_DataPacking */
94 uint32_t Pins; /*!< Input pins are taken from same or following channel.
95 This parameter can be a value of @ref DFSDM_Channel_InputPins */
96 }DFSDM_Channel_InputTypeDef;
98 /**
99 * @brief DFSDM channel serial interface structure definition
101 typedef struct
103 uint32_t Type; /*!< SPI or Manchester modes.
104 This parameter can be a value of @ref DFSDM_Channel_SerialInterfaceType */
105 uint32_t SpiClock; /*!< SPI clock select (external or internal with different sampling point).
106 This parameter can be a value of @ref DFSDM_Channel_SpiClock */
107 }DFSDM_Channel_SerialInterfaceTypeDef;
109 /**
110 * @brief DFSDM channel analog watchdog structure definition
112 typedef struct
114 uint32_t FilterOrder; /*!< Analog watchdog Sinc filter order.
115 This parameter can be a value of @ref DFSDM_Channel_AwdFilterOrder */
116 uint32_t Oversampling; /*!< Analog watchdog filter oversampling ratio.
117 This parameter must be a number between Min_Data = 1 and Max_Data = 32 */
118 }DFSDM_Channel_AwdTypeDef;
120 /**
121 * @brief DFSDM channel init structure definition
123 typedef struct
125 DFSDM_Channel_OutputClockTypeDef OutputClock; /*!< DFSDM channel output clock parameters */
126 DFSDM_Channel_InputTypeDef Input; /*!< DFSDM channel input parameters */
127 DFSDM_Channel_SerialInterfaceTypeDef SerialInterface; /*!< DFSDM channel serial interface parameters */
128 DFSDM_Channel_AwdTypeDef Awd; /*!< DFSDM channel analog watchdog parameters */
129 int32_t Offset; /*!< DFSDM channel offset.
130 This parameter must be a number between Min_Data = -8388608 and Max_Data = 8388607 */
131 uint32_t RightBitShift; /*!< DFSDM channel right bit shift.
132 This parameter must be a number between Min_Data = 0x00 and Max_Data = 0x1F */
133 }DFSDM_Channel_InitTypeDef;
135 /**
136 * @brief DFSDM channel handle structure definition
138 typedef struct
140 DFSDM_Channel_TypeDef *Instance; /*!< DFSDM channel instance */
141 DFSDM_Channel_InitTypeDef Init; /*!< DFSDM channel init parameters */
142 HAL_DFSDM_Channel_StateTypeDef State; /*!< DFSDM channel state */
143 }DFSDM_Channel_HandleTypeDef;
145 /**
146 * @brief HAL DFSDM Filter states definition
148 typedef enum
150 HAL_DFSDM_FILTER_STATE_RESET = 0x00U, /*!< DFSDM filter not initialized */
151 HAL_DFSDM_FILTER_STATE_READY = 0x01U, /*!< DFSDM filter initialized and ready for use */
152 HAL_DFSDM_FILTER_STATE_REG = 0x02U, /*!< DFSDM filter regular conversion in progress */
153 HAL_DFSDM_FILTER_STATE_INJ = 0x03U, /*!< DFSDM filter injected conversion in progress */
154 HAL_DFSDM_FILTER_STATE_REG_INJ = 0x04U, /*!< DFSDM filter regular and injected conversions in progress */
155 HAL_DFSDM_FILTER_STATE_ERROR = 0xFFU /*!< DFSDM filter state error */
156 }HAL_DFSDM_Filter_StateTypeDef;
158 /**
159 * @brief DFSDM filter regular conversion parameters structure definition
161 typedef struct
163 uint32_t Trigger; /*!< Trigger used to start regular conversion: software or synchronous.
164 This parameter can be a value of @ref DFSDM_Filter_Trigger */
165 FunctionalState FastMode; /*!< Enable/disable fast mode for regular conversion */
166 FunctionalState DmaMode; /*!< Enable/disable DMA for regular conversion */
167 }DFSDM_Filter_RegularParamTypeDef;
169 /**
170 * @brief DFSDM filter injected conversion parameters structure definition
172 typedef struct
174 uint32_t Trigger; /*!< Trigger used to start injected conversion: software, external or synchronous.
175 This parameter can be a value of @ref DFSDM_Filter_Trigger */
176 FunctionalState ScanMode; /*!< Enable/disable scanning mode for injected conversion */
177 FunctionalState DmaMode; /*!< Enable/disable DMA for injected conversion */
178 uint32_t ExtTrigger; /*!< External trigger.
179 This parameter can be a value of @ref DFSDM_Filter_ExtTrigger */
180 uint32_t ExtTriggerEdge; /*!< External trigger edge: rising, falling or both.
181 This parameter can be a value of @ref DFSDM_Filter_ExtTriggerEdge */
182 }DFSDM_Filter_InjectedParamTypeDef;
184 /**
185 * @brief DFSDM filter parameters structure definition
187 typedef struct
189 uint32_t SincOrder; /*!< Sinc filter order.
190 This parameter can be a value of @ref DFSDM_Filter_SincOrder */
191 uint32_t Oversampling; /*!< Filter oversampling ratio.
192 This parameter must be a number between Min_Data = 1 and Max_Data = 1024 */
193 uint32_t IntOversampling; /*!< Integrator oversampling ratio.
194 This parameter must be a number between Min_Data = 1 and Max_Data = 256 */
195 }DFSDM_Filter_FilterParamTypeDef;
197 /**
198 * @brief DFSDM filter init structure definition
200 typedef struct
202 DFSDM_Filter_RegularParamTypeDef RegularParam; /*!< DFSDM regular conversion parameters */
203 DFSDM_Filter_InjectedParamTypeDef InjectedParam; /*!< DFSDM injected conversion parameters */
204 DFSDM_Filter_FilterParamTypeDef FilterParam; /*!< DFSDM filter parameters */
205 }DFSDM_Filter_InitTypeDef;
207 /**
208 * @brief DFSDM filter handle structure definition
210 typedef struct
212 DFSDM_Filter_TypeDef *Instance; /*!< DFSDM filter instance */
213 DFSDM_Filter_InitTypeDef Init; /*!< DFSDM filter init parameters */
214 DMA_HandleTypeDef *hdmaReg; /*!< Pointer on DMA handler for regular conversions */
215 DMA_HandleTypeDef *hdmaInj; /*!< Pointer on DMA handler for injected conversions */
216 uint32_t RegularContMode; /*!< Regular conversion continuous mode */
217 uint32_t RegularTrigger; /*!< Trigger used for regular conversion */
218 uint32_t InjectedTrigger; /*!< Trigger used for injected conversion */
219 uint32_t ExtTriggerEdge; /*!< Rising, falling or both edges selected */
220 FunctionalState InjectedScanMode; /*!< Injected scanning mode */
221 uint32_t InjectedChannelsNbr; /*!< Number of channels in injected sequence */
222 uint32_t InjConvRemaining; /*!< Injected conversions remaining */
223 HAL_DFSDM_Filter_StateTypeDef State; /*!< DFSDM filter state */
224 uint32_t ErrorCode; /*!< DFSDM filter error code */
225 }DFSDM_Filter_HandleTypeDef;
227 /**
228 * @brief DFSDM filter analog watchdog parameters structure definition
230 typedef struct
232 uint32_t DataSource; /*!< Values from digital filter or from channel watchdog filter.
233 This parameter can be a value of @ref DFSDM_Filter_AwdDataSource */
234 uint32_t Channel; /*!< Analog watchdog channel selection.
235 This parameter can be a values combination of @ref DFSDM_Channel_Selection */
236 int32_t HighThreshold; /*!< High threshold for the analog watchdog.
237 This parameter must be a number between Min_Data = -8388608 and Max_Data = 8388607 */
238 int32_t LowThreshold; /*!< Low threshold for the analog watchdog.
239 This parameter must be a number between Min_Data = -8388608 and Max_Data = 8388607 */
240 uint32_t HighBreakSignal; /*!< Break signal assigned to analog watchdog high threshold event.
241 This parameter can be a values combination of @ref DFSDM_BreakSignals */
242 uint32_t LowBreakSignal; /*!< Break signal assigned to analog watchdog low threshold event.
243 This parameter can be a values combination of @ref DFSDM_BreakSignals */
244 }DFSDM_Filter_AwdParamTypeDef;
247 * @}
249 #if defined(SYSCFG_MCHDLYCR_BSCKSEL)
250 /**
251 * @brief Synchronization parameters structure definition for STM32F413xx/STM32F423xx devices
253 typedef struct
255 uint32_t DFSDM1ClockIn; /*!< Source selection for DFSDM1_Ckin.
256 This parameter can be a value of @ref DFSDM_1_CLOCKIN_SELECTION*/
257 uint32_t DFSDM2ClockIn; /*!< Source selection for DFSDM2_Ckin.
258 This parameter can be a value of @ref DFSDM_2_CLOCKIN_SELECTION*/
259 uint32_t DFSDM1ClockOut; /*!< Source selection for DFSDM1_Ckout.
260 This parameter can be a value of @ref DFSDM_1_CLOCKOUT_SELECTION*/
261 uint32_t DFSDM2ClockOut; /*!< Source selection for DFSDM2_Ckout.
262 This parameter can be a value of @ref DFSDM_2_CLOCKOUT_SELECTION*/
263 uint32_t DFSDM1BitClkDistribution; /*!< Distribution of the DFSDM1 bitstream clock gated by TIM4 OC1 or TIM4 OC2.
264 This parameter can be a value of @ref DFSDM_1_BIT_STREAM_DISTRIBUTION
265 @note The DFSDM2 audio gated by TIM4 OC2 can be injected on CKIN0 or CKIN2
266 @note The DFSDM2 audio gated by TIM4 OC1 can be injected on CKIN1 or CKIN3 */
267 uint32_t DFSDM2BitClkDistribution; /*!< Distribution of the DFSDM2 bitstream clock gated by TIM3 OC1 or TIM3 OC2 or TIM3 OC3 or TIM3 OC4.
268 This parameter can be a value of @ref DFSDM_2_BIT_STREAM_DISTRIBUTION
269 @note The DFSDM2 audio gated by TIM3 OC4 can be injected on CKIN0 or CKIN4
270 @note The DFSDM2 audio gated by TIM3 OC3 can be injected on CKIN1 or CKIN5
271 @note The DFSDM2 audio gated by TIM3 OC2 can be injected on CKIN2 or CKIN6
272 @note The DFSDM2 audio gated by TIM3 OC1 can be injected on CKIN3 or CKIN7 */
273 uint32_t DFSDM1DataDistribution; /*!< Source selection for DatIn0 and DatIn2 of DFSDM1.
274 This parameter can be a value of @ref DFSDM_1_DATA_DISTRIBUTION */
275 uint32_t DFSDM2DataDistribution; /*!< Source selection for DatIn0, DatIn2, DatIn4 and DatIn6 of DFSDM2.
276 This parameter can be a value of @ref DFSDM_2_DATA_DISTRIBUTION */
277 }DFSDM_MultiChannelConfigTypeDef;
278 #endif /* SYSCFG_MCHDLYCR_BSCKSEL */
280 * @}
283 /* End of exported types -----------------------------------------------------*/
285 /* Exported constants --------------------------------------------------------*/
286 /** @defgroup DFSDM_Exported_Constants DFSDM Exported Constants
287 * @{
290 /** @defgroup DFSDM_Channel_OuputClock DFSDM channel output clock selection
291 * @{
293 #define DFSDM_CHANNEL_OUTPUT_CLOCK_SYSTEM 0x00000000U /*!< Source for ouput clock is system clock */
294 #define DFSDM_CHANNEL_OUTPUT_CLOCK_AUDIO DFSDM_CHCFGR1_CKOUTSRC /*!< Source for ouput clock is audio clock */
296 * @}
299 /** @defgroup DFSDM_Channel_InputMultiplexer DFSDM channel input multiplexer
300 * @{
302 #define DFSDM_CHANNEL_EXTERNAL_INPUTS 0x00000000U /*!< Data are taken from external inputs */
303 #define DFSDM_CHANNEL_INTERNAL_REGISTER DFSDM_CHCFGR1_DATMPX_1 /*!< Data are taken from internal register */
305 * @}
308 /** @defgroup DFSDM_Channel_DataPacking DFSDM channel input data packing
309 * @{
311 #define DFSDM_CHANNEL_STANDARD_MODE 0x00000000U /*!< Standard data packing mode */
312 #define DFSDM_CHANNEL_INTERLEAVED_MODE DFSDM_CHCFGR1_DATPACK_0 /*!< Interleaved data packing mode */
313 #define DFSDM_CHANNEL_DUAL_MODE DFSDM_CHCFGR1_DATPACK_1 /*!< Dual data packing mode */
315 * @}
318 /** @defgroup DFSDM_Channel_InputPins DFSDM channel input pins
319 * @{
321 #define DFSDM_CHANNEL_SAME_CHANNEL_PINS 0x00000000U /*!< Input from pins on same channel */
322 #define DFSDM_CHANNEL_FOLLOWING_CHANNEL_PINS DFSDM_CHCFGR1_CHINSEL /*!< Input from pins on following channel */
324 * @}
327 /** @defgroup DFSDM_Channel_SerialInterfaceType DFSDM channel serial interface type
328 * @{
330 #define DFSDM_CHANNEL_SPI_RISING 0x00000000U /*!< SPI with rising edge */
331 #define DFSDM_CHANNEL_SPI_FALLING DFSDM_CHCFGR1_SITP_0 /*!< SPI with falling edge */
332 #define DFSDM_CHANNEL_MANCHESTER_RISING DFSDM_CHCFGR1_SITP_1 /*!< Manchester with rising edge */
333 #define DFSDM_CHANNEL_MANCHESTER_FALLING DFSDM_CHCFGR1_SITP /*!< Manchester with falling edge */
335 * @}
338 /** @defgroup DFSDM_Channel_SpiClock DFSDM channel SPI clock selection
339 * @{
341 #define DFSDM_CHANNEL_SPI_CLOCK_EXTERNAL 0x00000000U /*!< External SPI clock */
342 #define DFSDM_CHANNEL_SPI_CLOCK_INTERNAL DFSDM_CHCFGR1_SPICKSEL_0 /*!< Internal SPI clock */
343 #define DFSDM_CHANNEL_SPI_CLOCK_INTERNAL_DIV2_FALLING DFSDM_CHCFGR1_SPICKSEL_1 /*!< Internal SPI clock divided by 2, falling edge */
344 #define DFSDM_CHANNEL_SPI_CLOCK_INTERNAL_DIV2_RISING DFSDM_CHCFGR1_SPICKSEL /*!< Internal SPI clock divided by 2, rising edge */
346 * @}
349 /** @defgroup DFSDM_Channel_AwdFilterOrder DFSDM channel analog watchdog filter order
350 * @{
352 #define DFSDM_CHANNEL_FASTSINC_ORDER 0x00000000U /*!< FastSinc filter type */
353 #define DFSDM_CHANNEL_SINC1_ORDER DFSDM_CHAWSCDR_AWFORD_0 /*!< Sinc 1 filter type */
354 #define DFSDM_CHANNEL_SINC2_ORDER DFSDM_CHAWSCDR_AWFORD_1 /*!< Sinc 2 filter type */
355 #define DFSDM_CHANNEL_SINC3_ORDER DFSDM_CHAWSCDR_AWFORD /*!< Sinc 3 filter type */
357 * @}
360 /** @defgroup DFSDM_Filter_Trigger DFSDM filter conversion trigger
361 * @{
363 #define DFSDM_FILTER_SW_TRIGGER 0x00000000U /*!< Software trigger */
364 #define DFSDM_FILTER_SYNC_TRIGGER 0x00000001U /*!< Synchronous with DFSDM_FLT0 */
365 #define DFSDM_FILTER_EXT_TRIGGER 0x00000002U /*!< External trigger (only for injected conversion) */
367 * @}
370 /** @defgroup DFSDM_Filter_ExtTrigger DFSDM filter external trigger
371 * @{
373 #if defined(STM32F413xx) || defined(STM32F423xx)
374 /* Trigger for stm32f413xx and STM32f423xx devices */
375 #define DFSDM_FILTER_EXT_TRIG_TIM1_TRGO 0x00000000U /*!< For All DFSDM1/2 filters */
376 #define DFSDM_FILTER_EXT_TRIG_TIM3_TRGO DFSDM_FLTCR1_JEXTSEL_0 /*!< For All DFSDM1/2 filters */
377 #define DFSDM_FILTER_EXT_TRIG_TIM8_TRGO DFSDM_FLTCR1_JEXTSEL_1 /*!< For All DFSDM1/2 filters */
378 #define DFSDM_FILTER_EXT_TRIG_TIM10_OC1 (DFSDM_FLTCR1_JEXTSEL_0 | DFSDM_FLTCR1_JEXTSEL_1) /*!< For DFSDM1 filter 0 and 1 and DFSDM2 filter 0, 1 and 2 */
379 #define DFSDM_FILTER_EXT_TRIG_TIM2_TRGO (DFSDM_FLTCR1_JEXTSEL_0 | DFSDM_FLTCR1_JEXTSEL_1) /*!< For DFSDM2 filter 3 */
380 #define DFSDM_FILTER_EXT_TRIG_TIM4_TRGO DFSDM_FLTCR1_JEXTSEL_2 /*!< For DFSDM1 filter 0 and 1 and DFSDM2 filter 0, 1 and 2 */
381 #define DFSDM_FILTER_EXT_TRIG_TIM11_OC1 DFSDM_FLTCR1_JEXTSEL_2 /*!< For DFSDM2 filter 3 */
382 #define DFSDM_FILTER_EXT_TRIG_TIM6_TRGO (DFSDM_FLTCR1_JEXTSEL_0 | DFSDM_FLTCR1_JEXTSEL_2) /*!< For DFSDM1 filter 0 and 1 and DFSDM2 filter 0 and 1 */
383 #define DFSDM_FILTER_EXT_TRIG_TIM7_TRGO (DFSDM_FLTCR1_JEXTSEL_0 | DFSDM_FLTCR1_JEXTSEL_2) /*!< For DFSDM2 filter 2 and 3*/
384 #define DFSDM_FILTER_EXT_TRIG_EXTI11 (DFSDM_FLTCR1_JEXTSEL_1 | DFSDM_FLTCR1_JEXTSEL_2) /*!< For All DFSDM1/2 filters */
385 #define DFSDM_FILTER_EXT_TRIG_EXTI15 DFSDM_FLTCR1_JEXTSEL /*!< For All DFSDM1/2 filters */
386 #else
387 /* Trigger for stm32f412xx devices */
388 #define DFSDM_FILTER_EXT_TRIG_TIM1_TRGO 0x00000000U /*!< For DFSDM1 filter 0 and 1*/
389 #define DFSDM_FILTER_EXT_TRIG_TIM3_TRGO DFSDM_FLTCR1_JEXTSEL_0 /*!< For DFSDM1 filter 0 and 1*/
390 #define DFSDM_FILTER_EXT_TRIG_TIM8_TRGO DFSDM_FLTCR1_JEXTSEL_1 /*!< For DFSDM1 filter 0 and 1*/
391 #define DFSDM_FILTER_EXT_TRIG_TIM10_OC1 (DFSDM_FLTCR1_JEXTSEL_0 | DFSDM_FLTCR1_JEXTSEL_1) /*!< For DFSDM1 filter 0 and 1*/
392 #define DFSDM_FILTER_EXT_TRIG_TIM4_TRGO DFSDM_FLTCR1_JEXTSEL_2 /*!< For DFSDM1 filter 0 and 1*/
393 #define DFSDM_FILTER_EXT_TRIG_TIM6_TRGO (DFSDM_FLTCR1_JEXTSEL_0 | DFSDM_FLTCR1_JEXTSEL_2) /*!< For DFSDM1 filter 0 and 1*/
394 #define DFSDM_FILTER_EXT_TRIG_EXTI11 (DFSDM_FLTCR1_JEXTSEL_1 | DFSDM_FLTCR1_JEXTSEL_2) /*!< For DFSDM1 filter 0 and 1*/
395 #define DFSDM_FILTER_EXT_TRIG_EXTI15 DFSDM_FLTCR1_JEXTSEL /*!< For DFSDM1 filter 0 and 1*/
396 #endif
398 * @}
401 /** @defgroup DFSDM_Filter_ExtTriggerEdge DFSDM filter external trigger edge
402 * @{
404 #define DFSDM_FILTER_EXT_TRIG_RISING_EDGE DFSDM_FLTCR1_JEXTEN_0 /*!< External rising edge */
405 #define DFSDM_FILTER_EXT_TRIG_FALLING_EDGE DFSDM_FLTCR1_JEXTEN_1 /*!< External falling edge */
406 #define DFSDM_FILTER_EXT_TRIG_BOTH_EDGES DFSDM_FLTCR1_JEXTEN /*!< External rising and falling edges */
408 * @}
411 /** @defgroup DFSDM_Filter_SincOrder DFSDM filter sinc order
412 * @{
414 #define DFSDM_FILTER_FASTSINC_ORDER 0x00000000U /*!< FastSinc filter type */
415 #define DFSDM_FILTER_SINC1_ORDER DFSDM_FLTFCR_FORD_0 /*!< Sinc 1 filter type */
416 #define DFSDM_FILTER_SINC2_ORDER DFSDM_FLTFCR_FORD_1 /*!< Sinc 2 filter type */
417 #define DFSDM_FILTER_SINC3_ORDER (DFSDM_FLTFCR_FORD_0 | DFSDM_FLTFCR_FORD_1) /*!< Sinc 3 filter type */
418 #define DFSDM_FILTER_SINC4_ORDER DFSDM_FLTFCR_FORD_2 /*!< Sinc 4 filter type */
419 #define DFSDM_FILTER_SINC5_ORDER (DFSDM_FLTFCR_FORD_0 | DFSDM_FLTFCR_FORD_2) /*!< Sinc 5 filter type */
421 * @}
424 /** @defgroup DFSDM_Filter_AwdDataSource DFSDM filter analog watchdog data source
425 * @{
427 #define DFSDM_FILTER_AWD_FILTER_DATA 0x00000000U /*!< From digital filter */
428 #define DFSDM_FILTER_AWD_CHANNEL_DATA DFSDM_FLTCR1_AWFSEL /*!< From analog watchdog channel */
430 * @}
433 /** @defgroup DFSDM_Filter_ErrorCode DFSDM filter error code
434 * @{
436 #define DFSDM_FILTER_ERROR_NONE 0x00000000U /*!< No error */
437 #define DFSDM_FILTER_ERROR_REGULAR_OVERRUN 0x00000001U /*!< Overrun occurs during regular conversion */
438 #define DFSDM_FILTER_ERROR_INJECTED_OVERRUN 0x00000002U /*!< Overrun occurs during injected conversion */
439 #define DFSDM_FILTER_ERROR_DMA 0x00000003U /*!< DMA error occurs */
441 * @}
444 /** @defgroup DFSDM_BreakSignals DFSDM break signals
445 * @{
447 #define DFSDM_NO_BREAK_SIGNAL 0x00000000U /*!< No break signal */
448 #define DFSDM_BREAK_SIGNAL_0 0x00000001U /*!< Break signal 0 */
449 #define DFSDM_BREAK_SIGNAL_1 0x00000002U /*!< Break signal 1 */
450 #define DFSDM_BREAK_SIGNAL_2 0x00000004U /*!< Break signal 2 */
451 #define DFSDM_BREAK_SIGNAL_3 0x00000008U /*!< Break signal 3 */
453 * @}
456 /** @defgroup DFSDM_Channel_Selection DFSDM Channel Selection
457 * @{
459 /* DFSDM Channels ------------------------------------------------------------*/
460 /* The DFSDM channels are defined as follows:
461 - in 16-bit LSB the channel mask is set
462 - in 16-bit MSB the channel number is set
463 e.g. for channel 3 definition:
464 - the channel mask is 0x00000008 (bit 3 is set)
465 - the channel number 3 is 0x00030000
466 --> Consequently, channel 3 definition is 0x00000008 | 0x00030000 = 0x00030008 */
467 #define DFSDM_CHANNEL_0 0x00000001U
468 #define DFSDM_CHANNEL_1 0x00010002U
469 #define DFSDM_CHANNEL_2 0x00020004U
470 #define DFSDM_CHANNEL_3 0x00030008U
471 #define DFSDM_CHANNEL_4 0x00040010U /* only for stmm32f413xx and stm32f423xx devices */
472 #define DFSDM_CHANNEL_5 0x00050020U /* only for stmm32f413xx and stm32f423xx devices */
473 #define DFSDM_CHANNEL_6 0x00060040U /* only for stmm32f413xx and stm32f423xx devices */
474 #define DFSDM_CHANNEL_7 0x00070080U /* only for stmm32f413xx and stm32f423xx devices */
476 * @}
479 /** @defgroup DFSDM_ContinuousMode DFSDM Continuous Mode
480 * @{
482 #define DFSDM_CONTINUOUS_CONV_OFF 0x00000000U /*!< Conversion are not continuous */
483 #define DFSDM_CONTINUOUS_CONV_ON 0x00000001U /*!< Conversion are continuous */
485 * @}
488 /** @defgroup DFSDM_AwdThreshold DFSDM analog watchdog threshold
489 * @{
491 #define DFSDM_AWD_HIGH_THRESHOLD 0x00000000U /*!< Analog watchdog high threshold */
492 #define DFSDM_AWD_LOW_THRESHOLD 0x00000001U /*!< Analog watchdog low threshold */
494 * @}
497 #if defined(SYSCFG_MCHDLYCR_BSCKSEL)
498 /** @defgroup DFSDM_1_CLOCKOUT_SELECTION DFSDM1 ClockOut Selection
499 * @{
501 #define DFSDM1_CKOUT_DFSDM2_CKOUT 0x00000080U
502 #define DFSDM1_CKOUT_DFSDM1 0x00000000U
504 * @}
507 /** @defgroup DFSDM_2_CLOCKOUT_SELECTION DFSDM2 ClockOut Selection
508 * @{
510 #define DFSDM2_CKOUT_DFSDM2_CKOUT 0x00040000U
511 #define DFSDM2_CKOUT_DFSDM2 0x00000000U
513 * @}
516 /** @defgroup DFSDM_1_CLOCKIN_SELECTION DFSDM1 ClockIn Selection
517 * @{
519 #define DFSDM1_CKIN_DFSDM2_CKOUT 0x00000040U
520 #define DFSDM1_CKIN_PAD 0x00000000U
522 * @}
525 /** @defgroup DFSDM_2_CLOCKIN_SELECTION DFSDM2 ClockIn Selection
526 * @{
528 #define DFSDM2_CKIN_DFSDM2_CKOUT 0x00020000U
529 #define DFSDM2_CKIN_PAD 0x00000000U
531 * @}
534 /** @defgroup DFSDM_1_BIT_STREAM_DISTRIBUTION DFSDM1 Bit Stream Distribution
535 * @{
537 #define DFSDM1_T4_OC2_BITSTREAM_CKIN0 0x00000000U /* TIM4_OC2 to CLKIN0 */
538 #define DFSDM1_T4_OC2_BITSTREAM_CKIN2 SYSCFG_MCHDLYCR_DFSDM1CK02SEL /* TIM4_OC2 to CLKIN2 */
539 #define DFSDM1_T4_OC1_BITSTREAM_CKIN3 SYSCFG_MCHDLYCR_DFSDM1CK13SEL /* TIM4_OC1 to CLKIN3 */
540 #define DFSDM1_T4_OC1_BITSTREAM_CKIN1 0x00000000U /* TIM4_OC1 to CLKIN1 */
542 * @}
545 /** @defgroup DFSDM_2_BIT_STREAM_DISTRIBUTION DFSDM12 Bit Stream Distribution
546 * @{
548 #define DFSDM2_T3_OC4_BITSTREAM_CKIN0 0x00000000U /* TIM3_OC4 to CKIN0 */
549 #define DFSDM2_T3_OC4_BITSTREAM_CKIN4 SYSCFG_MCHDLYCR_DFSDM2CK04SEL /* TIM3_OC4 to CKIN4 */
550 #define DFSDM2_T3_OC3_BITSTREAM_CKIN5 SYSCFG_MCHDLYCR_DFSDM2CK15SEL /* TIM3_OC3 to CKIN5 */
551 #define DFSDM2_T3_OC3_BITSTREAM_CKIN1 0x00000000U /* TIM3_OC3 to CKIN1 */
552 #define DFSDM2_T3_OC2_BITSTREAM_CKIN6 SYSCFG_MCHDLYCR_DFSDM2CK26SEL /* TIM3_OC2to CKIN6 */
553 #define DFSDM2_T3_OC2_BITSTREAM_CKIN2 0x00000000U /* TIM3_OC2 to CKIN2 */
554 #define DFSDM2_T3_OC1_BITSTREAM_CKIN3 0x00000000U /* TIM3_OC1 to CKIN3 */
555 #define DFSDM2_T3_OC1_BITSTREAM_CKIN7 SYSCFG_MCHDLYCR_DFSDM2CK37SEL /* TIM3_OC1 to CKIN7 */
557 * @}
560 /** @defgroup DFSDM_1_DATA_DISTRIBUTION DFSDM1 Data Distribution
561 * @{
563 #define DFSDM1_DATIN0_TO_DATIN0_PAD 0x00000000U
564 #define DFSDM1_DATIN0_TO_DATIN1_PAD SYSCFG_MCHDLYCR_DFSDM1D0SEL
565 #define DFSDM1_DATIN2_TO_DATIN2_PAD 0x00000000U
566 #define DFSDM1_DATIN2_TO_DATIN3_PAD SYSCFG_MCHDLYCR_DFSDM1D2SEL
568 * @}
571 /** @defgroup DFSDM_2_DATA_DISTRIBUTION DFSDM2 Data Distribution
572 * @{
574 #define DFSDM2_DATIN0_TO_DATIN0_PAD 0x00000000U
575 #define DFSDM2_DATIN0_TO_DATIN1_PAD SYSCFG_MCHDLYCR_DFSDM2D0SEL
576 #define DFSDM2_DATIN2_TO_DATIN2_PAD 0x00000000U
577 #define DFSDM2_DATIN2_TO_DATIN3_PAD SYSCFG_MCHDLYCR_DFSDM2D2SEL
578 #define DFSDM2_DATIN4_TO_DATIN4_PAD 0x00000000U
579 #define DFSDM2_DATIN4_TO_DATIN5_PAD SYSCFG_MCHDLYCR_DFSDM2D4SEL
580 #define DFSDM2_DATIN6_TO_DATIN6_PAD 0x00000000U
581 #define DFSDM2_DATIN6_TO_DATIN7_PAD SYSCFG_MCHDLYCR_DFSDM2D6SEL
583 * @}
586 /** @defgroup HAL_MCHDLY_CLOCK HAL MCHDLY Clock enable
587 * @{
589 #define HAL_MCHDLY_CLOCK_DFSDM2 SYSCFG_MCHDLYCR_MCHDLY2EN
590 #define HAL_MCHDLY_CLOCK_DFSDM1 SYSCFG_MCHDLYCR_MCHDLY1EN
592 * @}
595 /** @defgroup DFSDM_CLOCKIN_SOURCE DFSDM Clock In Source Selection
596 * @{
598 #define HAL_DFSDM2_CKIN_PAD 0x00040000U
599 #define HAL_DFSDM2_CKIN_DM SYSCFG_MCHDLYCR_DFSDM2CFG
600 #define HAL_DFSDM1_CKIN_PAD 0x00000000U
601 #define HAL_DFSDM1_CKIN_DM SYSCFG_MCHDLYCR_DFSDM1CFG
603 * @}
606 /** @defgroup DFSDM_CLOCKOUT_SOURCE DFSDM Clock Source Selection
607 * @{
609 #define HAL_DFSDM2_CKOUT_DFSDM2 0x10000000U
610 #define HAL_DFSDM2_CKOUT_M27 SYSCFG_MCHDLYCR_DFSDM2CKOSEL
611 #define HAL_DFSDM1_CKOUT_DFSDM1 0x00000000U
612 #define HAL_DFSDM1_CKOUT_M27 SYSCFG_MCHDLYCR_DFSDM1CKOSEL
614 * @}
617 /** @defgroup DFSDM_DATAIN0_SOURCE DFSDM Source Selection For DATAIN0
618 * @{
620 #define HAL_DATAIN0_DFSDM2_PAD 0x10000000U
621 #define HAL_DATAIN0_DFSDM2_DATAIN1 SYSCFG_MCHDLYCR_DFSDM2D0SEL
622 #define HAL_DATAIN0_DFSDM1_PAD 0x00000000U
623 #define HAL_DATAIN0_DFSDM1_DATAIN1 SYSCFG_MCHDLYCR_DFSDM1D0SEL
625 * @}
628 /** @defgroup DFSDM_DATAIN2_SOURCE DFSDM Source Selection For DATAIN2
629 * @{
631 #define HAL_DATAIN2_DFSDM2_PAD 0x10000000U
632 #define HAL_DATAIN2_DFSDM2_DATAIN3 SYSCFG_MCHDLYCR_DFSDM2D2SEL
633 #define HAL_DATAIN2_DFSDM1_PAD 0x00000000U
634 #define HAL_DATAIN2_DFSDM1_DATAIN3 SYSCFG_MCHDLYCR_DFSDM1D2SEL
636 * @}
639 /** @defgroup DFSDM_DATAIN4_SOURCE DFSDM Source Selection For DATAIN4
640 * @{
642 #define HAL_DATAIN4_DFSDM2_PAD 0x00000000U
643 #define HAL_DATAIN4_DFSDM2_DATAIN5 SYSCFG_MCHDLYCR_DFSDM2D4SEL
645 * @}
648 /** @defgroup DFSDM_DATAIN6_SOURCE DFSDM Source Selection For DATAIN6
649 * @{
651 #define HAL_DATAIN6_DFSDM2_PAD 0x00000000U
652 #define HAL_DATAIN6_DFSDM2_DATAIN7 SYSCFG_MCHDLYCR_DFSDM2D6SEL
654 * @}
657 /** @defgroup DFSDM1_CLKIN_SOURCE DFSDM1 Source Selection For CLKIN
658 * @{
660 #define HAL_DFSDM1_CLKIN0_TIM4OC2 0x01000000U
661 #define HAL_DFSDM1_CLKIN2_TIM4OC2 SYSCFG_MCHDLYCR_DFSDM1CK02SEL
662 #define HAL_DFSDM1_CLKIN1_TIM4OC1 0x02000000U
663 #define HAL_DFSDM1_CLKIN3_TIM4OC1 SYSCFG_MCHDLYCR_DFSDM1CK13SEL
665 * @}
668 /** @defgroup DFSDM2_CLKIN_SOURCE DFSDM2 Source Selection For CLKIN
669 * @{
671 #define HAL_DFSDM2_CLKIN0_TIM3OC4 0x04000000U
672 #define HAL_DFSDM2_CLKIN4_TIM3OC4 SYSCFG_MCHDLYCR_DFSDM2CK04SEL
673 #define HAL_DFSDM2_CLKIN1_TIM3OC3 0x08000000U
674 #define HAL_DFSDM2_CLKIN5_TIM3OC3 SYSCFG_MCHDLYCR_DFSDM2CK15SEL
675 #define HAL_DFSDM2_CLKIN2_TIM3OC2 0x10000000U
676 #define HAL_DFSDM2_CLKIN6_TIM3OC2 SYSCFG_MCHDLYCR_DFSDM2CK26SEL
677 #define HAL_DFSDM2_CLKIN3_TIM3OC1 0x00000000U
678 #define HAL_DFSDM2_CLKIN7_TIM3OC1 SYSCFG_MCHDLYCR_DFSDM2CK37SEL
680 * @}
683 #endif /* SYSCFG_MCHDLYCR_BSCKSEL*/
685 * @}
687 /* End of exported constants -------------------------------------------------*/
689 /* Exported macros -----------------------------------------------------------*/
690 /** @defgroup DFSDM_Exported_Macros DFSDM Exported Macros
691 * @{
694 /** @brief Reset DFSDM channel handle state.
695 * @param __HANDLE__: DFSDM channel handle.
696 * @retval None
698 #define __HAL_DFSDM_CHANNEL_RESET_HANDLE_STATE(__HANDLE__) ((__HANDLE__)->State = HAL_DFSDM_CHANNEL_STATE_RESET)
700 /** @brief Reset DFSDM filter handle state.
701 * @param __HANDLE__: DFSDM filter handle.
702 * @retval None
704 #define __HAL_DFSDM_FILTER_RESET_HANDLE_STATE(__HANDLE__) ((__HANDLE__)->State = HAL_DFSDM_FILTER_STATE_RESET)
707 * @}
709 /* End of exported macros ----------------------------------------------------*/
711 /* Exported functions --------------------------------------------------------*/
712 /** @addtogroup DFSDM_Exported_Functions DFSDM Exported Functions
713 * @{
716 /** @addtogroup DFSDM_Exported_Functions_Group1_Channel Channel initialization and de-initialization functions
717 * @{
719 /* Channel initialization and de-initialization functions *********************/
720 HAL_StatusTypeDef HAL_DFSDM_ChannelInit(DFSDM_Channel_HandleTypeDef *hdfsdm_channel);
721 HAL_StatusTypeDef HAL_DFSDM_ChannelDeInit(DFSDM_Channel_HandleTypeDef *hdfsdm_channel);
722 void HAL_DFSDM_ChannelMspInit(DFSDM_Channel_HandleTypeDef *hdfsdm_channel);
723 void HAL_DFSDM_ChannelMspDeInit(DFSDM_Channel_HandleTypeDef *hdfsdm_channel);
725 * @}
728 /** @addtogroup DFSDM_Exported_Functions_Group2_Channel Channel operation functions
729 * @{
731 /* Channel operation functions ************************************************/
732 HAL_StatusTypeDef HAL_DFSDM_ChannelCkabStart(DFSDM_Channel_HandleTypeDef *hdfsdm_channel);
733 HAL_StatusTypeDef HAL_DFSDM_ChannelCkabStart_IT(DFSDM_Channel_HandleTypeDef *hdfsdm_channel);
734 HAL_StatusTypeDef HAL_DFSDM_ChannelCkabStop(DFSDM_Channel_HandleTypeDef *hdfsdm_channel);
735 HAL_StatusTypeDef HAL_DFSDM_ChannelCkabStop_IT(DFSDM_Channel_HandleTypeDef *hdfsdm_channel);
737 HAL_StatusTypeDef HAL_DFSDM_ChannelScdStart(DFSDM_Channel_HandleTypeDef *hdfsdm_channel, uint32_t Threshold, uint32_t BreakSignal);
738 HAL_StatusTypeDef HAL_DFSDM_ChannelScdStart_IT(DFSDM_Channel_HandleTypeDef *hdfsdm_channel, uint32_t Threshold, uint32_t BreakSignal);
739 HAL_StatusTypeDef HAL_DFSDM_ChannelScdStop(DFSDM_Channel_HandleTypeDef *hdfsdm_channel);
740 HAL_StatusTypeDef HAL_DFSDM_ChannelScdStop_IT(DFSDM_Channel_HandleTypeDef *hdfsdm_channel);
742 int16_t HAL_DFSDM_ChannelGetAwdValue(DFSDM_Channel_HandleTypeDef *hdfsdm_channel);
743 HAL_StatusTypeDef HAL_DFSDM_ChannelModifyOffset(DFSDM_Channel_HandleTypeDef *hdfsdm_channel, int32_t Offset);
745 HAL_StatusTypeDef HAL_DFSDM_ChannelPollForCkab(DFSDM_Channel_HandleTypeDef *hdfsdm_channel, uint32_t Timeout);
746 HAL_StatusTypeDef HAL_DFSDM_ChannelPollForScd(DFSDM_Channel_HandleTypeDef *hdfsdm_channel, uint32_t Timeout);
748 void HAL_DFSDM_ChannelCkabCallback(DFSDM_Channel_HandleTypeDef *hdfsdm_channel);
749 void HAL_DFSDM_ChannelScdCallback(DFSDM_Channel_HandleTypeDef *hdfsdm_channel);
751 * @}
754 /** @defgroup DFSDM_Exported_Functions_Group3_Channel Channel state function
755 * @{
757 /* Channel state function *****************************************************/
758 HAL_DFSDM_Channel_StateTypeDef HAL_DFSDM_ChannelGetState(DFSDM_Channel_HandleTypeDef *hdfsdm_channel);
760 * @}
763 /** @addtogroup DFSDM_Exported_Functions_Group1_Filter Filter initialization and de-initialization functions
764 * @{
766 /* Filter initialization and de-initialization functions *********************/
767 HAL_StatusTypeDef HAL_DFSDM_FilterInit(DFSDM_Filter_HandleTypeDef *hdfsdm_filter);
768 HAL_StatusTypeDef HAL_DFSDM_FilterDeInit(DFSDM_Filter_HandleTypeDef *hdfsdm_filter);
769 void HAL_DFSDM_FilterMspInit(DFSDM_Filter_HandleTypeDef *hdfsdm_filter);
770 void HAL_DFSDM_FilterMspDeInit(DFSDM_Filter_HandleTypeDef *hdfsdm_filter);
772 * @}
775 /** @addtogroup DFSDM_Exported_Functions_Group2_Filter Filter control functions
776 * @{
778 /* Filter control functions *********************/
779 HAL_StatusTypeDef HAL_DFSDM_FilterConfigRegChannel(DFSDM_Filter_HandleTypeDef *hdfsdm_filter,
780 uint32_t Channel,
781 uint32_t ContinuousMode);
782 HAL_StatusTypeDef HAL_DFSDM_FilterConfigInjChannel(DFSDM_Filter_HandleTypeDef *hdfsdm_filter,
783 uint32_t Channel);
785 * @}
788 /** @addtogroup DFSDM_Exported_Functions_Group3_Filter Filter operation functions
789 * @{
791 /* Filter operation functions *********************/
792 HAL_StatusTypeDef HAL_DFSDM_FilterRegularStart(DFSDM_Filter_HandleTypeDef *hdfsdm_filter);
793 HAL_StatusTypeDef HAL_DFSDM_FilterRegularStart_IT(DFSDM_Filter_HandleTypeDef *hdfsdm_filter);
794 HAL_StatusTypeDef HAL_DFSDM_FilterRegularStart_DMA(DFSDM_Filter_HandleTypeDef *hdfsdm_filter, int32_t *pData, uint32_t Length);
795 HAL_StatusTypeDef HAL_DFSDM_FilterRegularMsbStart_DMA(DFSDM_Filter_HandleTypeDef *hdfsdm_filter, int16_t *pData, uint32_t Length);
796 HAL_StatusTypeDef HAL_DFSDM_FilterRegularStop(DFSDM_Filter_HandleTypeDef *hdfsdm_filter);
797 HAL_StatusTypeDef HAL_DFSDM_FilterRegularStop_IT(DFSDM_Filter_HandleTypeDef *hdfsdm_filter);
798 HAL_StatusTypeDef HAL_DFSDM_FilterRegularStop_DMA(DFSDM_Filter_HandleTypeDef *hdfsdm_filter);
799 HAL_StatusTypeDef HAL_DFSDM_FilterInjectedStart(DFSDM_Filter_HandleTypeDef *hdfsdm_filter);
800 HAL_StatusTypeDef HAL_DFSDM_FilterInjectedStart_IT(DFSDM_Filter_HandleTypeDef *hdfsdm_filter);
801 HAL_StatusTypeDef HAL_DFSDM_FilterInjectedStart_DMA(DFSDM_Filter_HandleTypeDef *hdfsdm_filter, int32_t *pData, uint32_t Length);
802 HAL_StatusTypeDef HAL_DFSDM_FilterInjectedMsbStart_DMA(DFSDM_Filter_HandleTypeDef *hdfsdm_filter, int16_t *pData, uint32_t Length);
803 HAL_StatusTypeDef HAL_DFSDM_FilterInjectedStop(DFSDM_Filter_HandleTypeDef *hdfsdm_filter);
804 HAL_StatusTypeDef HAL_DFSDM_FilterInjectedStop_IT(DFSDM_Filter_HandleTypeDef *hdfsdm_filter);
805 HAL_StatusTypeDef HAL_DFSDM_FilterInjectedStop_DMA(DFSDM_Filter_HandleTypeDef *hdfsdm_filter);
806 HAL_StatusTypeDef HAL_DFSDM_FilterAwdStart_IT(DFSDM_Filter_HandleTypeDef *hdfsdm_filter,
807 DFSDM_Filter_AwdParamTypeDef* awdParam);
808 HAL_StatusTypeDef HAL_DFSDM_FilterAwdStop_IT(DFSDM_Filter_HandleTypeDef *hdfsdm_filter);
809 HAL_StatusTypeDef HAL_DFSDM_FilterExdStart(DFSDM_Filter_HandleTypeDef *hdfsdm_filter, uint32_t Channel);
810 HAL_StatusTypeDef HAL_DFSDM_FilterExdStop(DFSDM_Filter_HandleTypeDef *hdfsdm_filter);
812 int32_t HAL_DFSDM_FilterGetRegularValue(DFSDM_Filter_HandleTypeDef *hdfsdm_filter, uint32_t* Channel);
813 int32_t HAL_DFSDM_FilterGetInjectedValue(DFSDM_Filter_HandleTypeDef *hdfsdm_filter, uint32_t* Channel);
814 int32_t HAL_DFSDM_FilterGetExdMaxValue(DFSDM_Filter_HandleTypeDef *hdfsdm_filter, uint32_t* Channel);
815 int32_t HAL_DFSDM_FilterGetExdMinValue(DFSDM_Filter_HandleTypeDef *hdfsdm_filter, uint32_t* Channel);
816 uint32_t HAL_DFSDM_FilterGetConvTimeValue(DFSDM_Filter_HandleTypeDef *hdfsdm_filter);
818 void HAL_DFSDM_IRQHandler(DFSDM_Filter_HandleTypeDef *hdfsdm_filter);
820 HAL_StatusTypeDef HAL_DFSDM_FilterPollForRegConversion(DFSDM_Filter_HandleTypeDef *hdfsdm_filter, uint32_t Timeout);
821 HAL_StatusTypeDef HAL_DFSDM_FilterPollForInjConversion(DFSDM_Filter_HandleTypeDef *hdfsdm_filter, uint32_t Timeout);
823 void HAL_DFSDM_FilterRegConvCpltCallback(DFSDM_Filter_HandleTypeDef *hdfsdm_filter);
824 void HAL_DFSDM_FilterRegConvHalfCpltCallback(DFSDM_Filter_HandleTypeDef *hdfsdm_filter);
825 void HAL_DFSDM_FilterInjConvCpltCallback(DFSDM_Filter_HandleTypeDef *hdfsdm_filter);
826 void HAL_DFSDM_FilterInjConvHalfCpltCallback(DFSDM_Filter_HandleTypeDef *hdfsdm_filter);
827 void HAL_DFSDM_FilterAwdCallback(DFSDM_Filter_HandleTypeDef *hdfsdm_filter, uint32_t Channel, uint32_t Threshold);
828 void HAL_DFSDM_FilterErrorCallback(DFSDM_Filter_HandleTypeDef *hdfsdm_filter);
830 * @}
833 /** @addtogroup DFSDM_Exported_Functions_Group4_Filter Filter state functions
834 * @{
836 /* Filter state functions *****************************************************/
837 HAL_DFSDM_Filter_StateTypeDef HAL_DFSDM_FilterGetState(DFSDM_Filter_HandleTypeDef *hdfsdm_filter);
838 uint32_t HAL_DFSDM_FilterGetError(DFSDM_Filter_HandleTypeDef *hdfsdm_filter);
840 * @}
842 /** @addtogroup DFSDM_Exported_Functions_Group5_Filter MultiChannel operation functions
843 * @{
845 #if defined(SYSCFG_MCHDLYCR_BSCKSEL)
846 void HAL_DFSDM_ConfigMultiChannelDelay(DFSDM_MultiChannelConfigTypeDef* mchdlystruct);
847 void HAL_DFSDM_BitstreamClock_Start(void);
848 void HAL_DFSDM_BitstreamClock_Stop(void);
849 void HAL_DFSDM_DisableDelayClock(uint32_t MCHDLY);
850 void HAL_DFSDM_EnableDelayClock(uint32_t MCHDLY);
851 void HAL_DFSDM_ClockIn_SourceSelection(uint32_t source);
852 void HAL_DFSDM_ClockOut_SourceSelection(uint32_t source);
853 void HAL_DFSDM_DataIn0_SourceSelection(uint32_t source);
854 void HAL_DFSDM_DataIn2_SourceSelection(uint32_t source);
855 void HAL_DFSDM_DataIn4_SourceSelection(uint32_t source);
856 void HAL_DFSDM_DataIn6_SourceSelection(uint32_t source);
857 void HAL_DFSDM_BitStreamClkDistribution_Config(uint32_t source);
858 #endif /* SYSCFG_MCHDLYCR_BSCKSEL */
860 * @}
863 * @}
865 /* End of exported functions -------------------------------------------------*/
867 /* Private macros ------------------------------------------------------------*/
868 /** @defgroup DFSDM_Private_Macros DFSDM Private Macros
869 * @{
871 #define IS_DFSDM_CHANNEL_OUTPUT_CLOCK(CLOCK) (((CLOCK) == DFSDM_CHANNEL_OUTPUT_CLOCK_SYSTEM) || \
872 ((CLOCK) == DFSDM_CHANNEL_OUTPUT_CLOCK_AUDIO))
873 #define IS_DFSDM_CHANNEL_OUTPUT_CLOCK_DIVIDER(DIVIDER) ((2U <= (DIVIDER)) && ((DIVIDER) <= 256U))
874 #define IS_DFSDM_CHANNEL_INPUT(INPUT) (((INPUT) == DFSDM_CHANNEL_EXTERNAL_INPUTS) || \
875 ((INPUT) == DFSDM_CHANNEL_INTERNAL_REGISTER))
876 #define IS_DFSDM_CHANNEL_DATA_PACKING(MODE) (((MODE) == DFSDM_CHANNEL_STANDARD_MODE) || \
877 ((MODE) == DFSDM_CHANNEL_INTERLEAVED_MODE) || \
878 ((MODE) == DFSDM_CHANNEL_DUAL_MODE))
879 #define IS_DFSDM_CHANNEL_INPUT_PINS(PINS) (((PINS) == DFSDM_CHANNEL_SAME_CHANNEL_PINS) || \
880 ((PINS) == DFSDM_CHANNEL_FOLLOWING_CHANNEL_PINS))
881 #define IS_DFSDM_CHANNEL_SERIAL_INTERFACE_TYPE(MODE) (((MODE) == DFSDM_CHANNEL_SPI_RISING) || \
882 ((MODE) == DFSDM_CHANNEL_SPI_FALLING) || \
883 ((MODE) == DFSDM_CHANNEL_MANCHESTER_RISING) || \
884 ((MODE) == DFSDM_CHANNEL_MANCHESTER_FALLING))
885 #define IS_DFSDM_CHANNEL_SPI_CLOCK(TYPE) (((TYPE) == DFSDM_CHANNEL_SPI_CLOCK_EXTERNAL) || \
886 ((TYPE) == DFSDM_CHANNEL_SPI_CLOCK_INTERNAL) || \
887 ((TYPE) == DFSDM_CHANNEL_SPI_CLOCK_INTERNAL_DIV2_FALLING) || \
888 ((TYPE) == DFSDM_CHANNEL_SPI_CLOCK_INTERNAL_DIV2_RISING))
889 #define IS_DFSDM_CHANNEL_FILTER_ORDER(ORDER) (((ORDER) == DFSDM_CHANNEL_FASTSINC_ORDER) || \
890 ((ORDER) == DFSDM_CHANNEL_SINC1_ORDER) || \
891 ((ORDER) == DFSDM_CHANNEL_SINC2_ORDER) || \
892 ((ORDER) == DFSDM_CHANNEL_SINC3_ORDER))
893 #define IS_DFSDM_CHANNEL_FILTER_OVS_RATIO(RATIO) ((1U <= (RATIO)) && ((RATIO) <= 32U))
894 #define IS_DFSDM_CHANNEL_OFFSET(VALUE) ((-8388608 <= (VALUE)) && ((VALUE) <= 8388607))
895 #define IS_DFSDM_CHANNEL_RIGHT_BIT_SHIFT(VALUE) ((VALUE) <= 0x1FU)
896 #define IS_DFSDM_CHANNEL_SCD_THRESHOLD(VALUE) ((VALUE) <= 0xFFU)
897 #define IS_DFSDM_FILTER_REG_TRIGGER(TRIG) (((TRIG) == DFSDM_FILTER_SW_TRIGGER) || \
898 ((TRIG) == DFSDM_FILTER_SYNC_TRIGGER))
899 #define IS_DFSDM_FILTER_INJ_TRIGGER(TRIG) (((TRIG) == DFSDM_FILTER_SW_TRIGGER) || \
900 ((TRIG) == DFSDM_FILTER_SYNC_TRIGGER) || \
901 ((TRIG) == DFSDM_FILTER_EXT_TRIGGER))
902 #if defined (STM32F413xx) || defined (STM32F423xx)
903 #define IS_DFSDM_FILTER_EXT_TRIG(TRIG) (((TRIG) == DFSDM_FILTER_EXT_TRIG_TIM1_TRGO) || \
904 ((TRIG) == DFSDM_FILTER_EXT_TRIG_TIM3_TRGO) || \
905 ((TRIG) == DFSDM_FILTER_EXT_TRIG_TIM8_TRGO) || \
906 ((TRIG) == DFSDM_FILTER_EXT_TRIG_TIM10_OC1) || \
907 ((TRIG) == DFSDM_FILTER_EXT_TRIG_TIM2_TRGO) || \
908 ((TRIG) == DFSDM_FILTER_EXT_TRIG_TIM4_TRGO) || \
909 ((TRIG) == DFSDM_FILTER_EXT_TRIG_TIM11_OC1) || \
910 ((TRIG) == DFSDM_FILTER_EXT_TRIG_TIM6_TRGO) || \
911 ((TRIG) == DFSDM_FILTER_EXT_TRIG_EXTI11) || \
912 ((TRIG) == DFSDM_FILTER_EXT_TRIG_EXTI15))
913 #define IS_DFSDM_DELAY_CLOCK(CLOCK) (((CLOCK) == HAL_MCHDLY_CLOCK_DFSDM2) || \
914 ((CLOCK) == HAL_MCHDLY_CLOCK_DFSDM1))
915 #else
916 #define IS_DFSDM_FILTER_EXT_TRIG(TRIG) (((TRIG) == DFSDM_FILTER_EXT_TRIG_TIM1_TRGO) || \
917 ((TRIG) == DFSDM_FILTER_EXT_TRIG_TIM3_TRGO) || \
918 ((TRIG) == DFSDM_FILTER_EXT_TRIG_TIM8_TRGO) || \
919 ((TRIG) == DFSDM_FILTER_EXT_TRIG_TIM10_OC1) || \
920 ((TRIG) == DFSDM_FILTER_EXT_TRIG_TIM4_TRGO) || \
921 ((TRIG) == DFSDM_FILTER_EXT_TRIG_TIM6_TRGO) || \
922 ((TRIG) == DFSDM_FILTER_EXT_TRIG_EXTI11) || \
923 ((TRIG) == DFSDM_FILTER_EXT_TRIG_EXTI15))
924 #endif
925 #define IS_DFSDM_FILTER_EXT_TRIG_EDGE(EDGE) (((EDGE) == DFSDM_FILTER_EXT_TRIG_RISING_EDGE) || \
926 ((EDGE) == DFSDM_FILTER_EXT_TRIG_FALLING_EDGE) || \
927 ((EDGE) == DFSDM_FILTER_EXT_TRIG_BOTH_EDGES))
928 #define IS_DFSDM_FILTER_SINC_ORDER(ORDER) (((ORDER) == DFSDM_FILTER_FASTSINC_ORDER) || \
929 ((ORDER) == DFSDM_FILTER_SINC1_ORDER) || \
930 ((ORDER) == DFSDM_FILTER_SINC2_ORDER) || \
931 ((ORDER) == DFSDM_FILTER_SINC3_ORDER) || \
932 ((ORDER) == DFSDM_FILTER_SINC4_ORDER) || \
933 ((ORDER) == DFSDM_FILTER_SINC5_ORDER))
934 #define IS_DFSDM_FILTER_OVS_RATIO(RATIO) ((1U <= (RATIO)) && ((RATIO) <= 1024U))
935 #define IS_DFSDM_FILTER_INTEGRATOR_OVS_RATIO(RATIO) ((1U <= (RATIO)) && ((RATIO) <= 256U))
936 #define IS_DFSDM_FILTER_AWD_DATA_SOURCE(DATA) (((DATA) == DFSDM_FILTER_AWD_FILTER_DATA) || \
937 ((DATA) == DFSDM_FILTER_AWD_CHANNEL_DATA))
938 #define IS_DFSDM_FILTER_AWD_THRESHOLD(VALUE) ((-8388608 <= (VALUE)) && ((VALUE) <= 8388607))
939 #define IS_DFSDM_BREAK_SIGNALS(VALUE) ((VALUE) <= 0x0FU)
940 #if defined(DFSDM2_Channel0)
941 #define IS_DFSDM_REGULAR_CHANNEL(CHANNEL) (((CHANNEL) == DFSDM_CHANNEL_0) || \
942 ((CHANNEL) == DFSDM_CHANNEL_1) || \
943 ((CHANNEL) == DFSDM_CHANNEL_2) || \
944 ((CHANNEL) == DFSDM_CHANNEL_3) || \
945 ((CHANNEL) == DFSDM_CHANNEL_4) || \
946 ((CHANNEL) == DFSDM_CHANNEL_5) || \
947 ((CHANNEL) == DFSDM_CHANNEL_6) || \
948 ((CHANNEL) == DFSDM_CHANNEL_7))
949 #define IS_DFSDM_INJECTED_CHANNEL(CHANNEL) (((CHANNEL) != 0U) && ((CHANNEL) <= 0x000F00FFU))
950 #else
951 #define IS_DFSDM_REGULAR_CHANNEL(CHANNEL) (((CHANNEL) == DFSDM_CHANNEL_0) || \
952 ((CHANNEL) == DFSDM_CHANNEL_1) || \
953 ((CHANNEL) == DFSDM_CHANNEL_2) || \
954 ((CHANNEL) == DFSDM_CHANNEL_3))
955 #define IS_DFSDM_INJECTED_CHANNEL(CHANNEL) (((CHANNEL) != 0U) && ((CHANNEL) <= 0x0003000FU))
956 #endif
957 #define IS_DFSDM_CONTINUOUS_MODE(MODE) (((MODE) == DFSDM_CONTINUOUS_CONV_OFF) || \
958 ((MODE) == DFSDM_CONTINUOUS_CONV_ON))
959 #if defined(DFSDM2_Channel0)
960 #define IS_DFSDM1_CHANNEL_INSTANCE(INSTANCE) (((INSTANCE) == DFSDM1_Channel0) || \
961 ((INSTANCE) == DFSDM1_Channel1) || \
962 ((INSTANCE) == DFSDM1_Channel2) || \
963 ((INSTANCE) == DFSDM1_Channel3))
964 #define IS_DFSDM1_FILTER_INSTANCE(INSTANCE) (((INSTANCE) == DFSDM1_Filter0) || \
965 ((INSTANCE) == DFSDM1_Filter1))
966 #endif /* DFSDM2_Channel0 */
968 #if defined(SYSCFG_MCHDLYCR_BSCKSEL)
969 #define IS_DFSDM_CLOCKIN_SELECTION(SELECTION) (((SELECTION) == HAL_DFSDM2_CKIN_PAD) || \
970 ((SELECTION) == HAL_DFSDM2_CKIN_DM) || \
971 ((SELECTION) == HAL_DFSDM1_CKIN_PAD) || \
972 ((SELECTION) == HAL_DFSDM1_CKIN_DM))
973 #define IS_DFSDM_CLOCKOUT_SELECTION(SELECTION) (((SELECTION) == HAL_DFSDM2_CKOUT_DFSDM2) || \
974 ((SELECTION) == HAL_DFSDM2_CKOUT_M27) || \
975 ((SELECTION) == HAL_DFSDM1_CKOUT_DFSDM1) || \
976 ((SELECTION) == HAL_DFSDM1_CKOUT_M27))
977 #define IS_DFSDM_DATAIN0_SRC_SELECTION(SELECTION) (((SELECTION) == HAL_DATAIN0_DFSDM2_PAD) || \
978 ((SELECTION) == HAL_DATAIN0_DFSDM2_DATAIN1) || \
979 ((SELECTION) == HAL_DATAIN0_DFSDM1_PAD) || \
980 ((SELECTION) == HAL_DATAIN0_DFSDM1_DATAIN1))
981 #define IS_DFSDM_DATAIN2_SRC_SELECTION(SELECTION) (((SELECTION) == HAL_DATAIN2_DFSDM2_PAD) || \
982 ((SELECTION) == HAL_DATAIN2_DFSDM2_DATAIN3) || \
983 ((SELECTION) == HAL_DATAIN2_DFSDM1_PAD) || \
984 ((SELECTION) == HAL_DATAIN2_DFSDM1_DATAIN3))
985 #define IS_DFSDM_DATAIN4_SRC_SELECTION(SELECTION) (((SELECTION) == HAL_DATAIN4_DFSDM2_PAD) || \
986 ((SELECTION) == HAL_DATAIN4_DFSDM2_DATAIN5))
987 #define IS_DFSDM_DATAIN6_SRC_SELECTION(SELECTION) (((SELECTION) == HAL_DATAIN6_DFSDM2_PAD) || \
988 ((SELECTION) == HAL_DATAIN6_DFSDM2_DATAIN7))
989 #define IS_DFSDM_BITSTREM_CLK_DISTRIBUTION(DISTRIBUTION) (((DISTRIBUTION) == HAL_DFSDM1_CLKIN0_TIM4OC2) || \
990 ((DISTRIBUTION) == HAL_DFSDM1_CLKIN2_TIM4OC2) || \
991 ((DISTRIBUTION) == HAL_DFSDM1_CLKIN1_TIM4OC1) || \
992 ((DISTRIBUTION) == HAL_DFSDM1_CLKIN3_TIM4OC1) || \
993 ((DISTRIBUTION) == HAL_DFSDM2_CLKIN0_TIM3OC4) || \
994 ((DISTRIBUTION) == HAL_DFSDM2_CLKIN4_TIM3OC4) || \
995 ((DISTRIBUTION) == HAL_DFSDM2_CLKIN1_TIM3OC3)|| \
996 ((DISTRIBUTION) == HAL_DFSDM2_CLKIN5_TIM3OC3) || \
997 ((DISTRIBUTION) == HAL_DFSDM2_CLKIN2_TIM3OC2) || \
998 ((DISTRIBUTION) == HAL_DFSDM2_CLKIN6_TIM3OC2) || \
999 ((DISTRIBUTION) == HAL_DFSDM2_CLKIN3_TIM3OC1)|| \
1000 ((DISTRIBUTION) == HAL_DFSDM2_CLKIN7_TIM3OC1))
1001 #define IS_DFSDM_DFSDM1_CLKOUT(CLKOUT) (((CLKOUT) == DFSDM1_CKOUT_DFSDM2_CKOUT) || \
1002 ((CLKOUT) == DFSDM1_CKOUT_DFSDM1))
1003 #define IS_DFSDM_DFSDM2_CLKOUT(CLKOUT) (((CLKOUT) == DFSDM2_CKOUT_DFSDM2_CKOUT) || \
1004 ((CLKOUT) == DFSDM2_CKOUT_DFSDM2))
1005 #define IS_DFSDM_DFSDM1_CLKIN(CLKIN) (((CLKIN) == DFSDM1_CKIN_DFSDM2_CKOUT) || \
1006 ((CLKIN) == DFSDM1_CKIN_PAD))
1007 #define IS_DFSDM_DFSDM2_CLKIN(CLKIN) (((CLKIN) == DFSDM2_CKIN_DFSDM2_CKOUT) || \
1008 ((CLKIN) == DFSDM2_CKIN_PAD))
1009 #define IS_DFSDM_DFSDM1_BIT_CLK(CLK) (((CLK) == DFSDM1_T4_OC2_BITSTREAM_CKIN0) || \
1010 ((CLK) == DFSDM1_T4_OC2_BITSTREAM_CKIN2) || \
1011 ((CLK) == DFSDM1_T4_OC1_BITSTREAM_CKIN3) || \
1012 ((CLK) == DFSDM1_T4_OC1_BITSTREAM_CKIN1) || \
1013 ((CLK) <= 0x30U))
1015 #define IS_DFSDM_DFSDM2_BIT_CLK(CLK) (((CLK) == DFSDM2_T3_OC4_BITSTREAM_CKIN0) || \
1016 ((CLK) == DFSDM2_T3_OC4_BITSTREAM_CKIN4) || \
1017 ((CLK) == DFSDM2_T3_OC3_BITSTREAM_CKIN5) || \
1018 ((CLK) == DFSDM2_T3_OC3_BITSTREAM_CKIN1) || \
1019 ((CLK) == DFSDM2_T3_OC2_BITSTREAM_CKIN6) || \
1020 ((CLK) == DFSDM2_T3_OC2_BITSTREAM_CKIN2) || \
1021 ((CLK) == DFSDM2_T3_OC1_BITSTREAM_CKIN3) || \
1022 ((CLK) == DFSDM2_T3_OC1_BITSTREAM_CKIN7)|| \
1023 ((CLK) <= 0x1E000U))
1025 #define IS_DFSDM_DFSDM1_DATA_DISTRIBUTION(DISTRIBUTION)(((DISTRIBUTION) == DFSDM1_DATIN0_TO_DATIN0_PAD )|| \
1026 ((DISTRIBUTION) == DFSDM1_DATIN0_TO_DATIN1_PAD) || \
1027 ((DISTRIBUTION) == DFSDM1_DATIN2_TO_DATIN2_PAD) || \
1028 ((DISTRIBUTION) == DFSDM1_DATIN2_TO_DATIN3_PAD)|| \
1029 ((DISTRIBUTION) <= 0xCU))
1031 #define IS_DFSDM_DFSDM2_DATA_DISTRIBUTION(DISTRIBUTION)(((DISTRIBUTION) == DFSDM2_DATIN0_TO_DATIN0_PAD)|| \
1032 ((DISTRIBUTION) == DFSDM2_DATIN0_TO_DATIN1_PAD)|| \
1033 ((DISTRIBUTION) == DFSDM2_DATIN2_TO_DATIN2_PAD)|| \
1034 ((DISTRIBUTION) == DFSDM2_DATIN2_TO_DATIN3_PAD)|| \
1035 ((DISTRIBUTION) == DFSDM2_DATIN4_TO_DATIN4_PAD)|| \
1036 ((DISTRIBUTION) == DFSDM2_DATIN4_TO_DATIN5_PAD)|| \
1037 ((DISTRIBUTION) == DFSDM2_DATIN6_TO_DATIN6_PAD)|| \
1038 ((DISTRIBUTION) == DFSDM2_DATIN6_TO_DATIN7_PAD)|| \
1039 ((DISTRIBUTION) <= 0x1D00U))
1040 #endif /* (SYSCFG_MCHDLYCR_BSCKSEL) */
1042 * @}
1044 /* End of private macros -----------------------------------------------------*/
1047 * @}
1051 * @}
1053 #endif /* STM32F412Zx || STM32F412Vx || STM32F412Rx || STM32F412Cx || STM32F413xx || STM32F423xx */
1054 #ifdef __cplusplus
1056 #endif
1058 #endif /* __STM32F4xx_HAL_DFSDM_H */
1060 /************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/