Create release.yml
[betaflight.git] / lib / main / STM32F4 / Drivers / STM32F4xx_StdPeriph_Driver / src / stm32f4xx_dfsdm.c
blob623561af2a0582551786350c2d234fa10ebafc24
1 /**
2 ******************************************************************************
3 * @file stm32f4xx_dfsdm.c
4 * @author MCD Application Team
5 * @version V1.7.1
6 * @date 20-May-2016
7 * @brief This file provides firmware functions to manage the following
8 * functionalities of Digital Filter for Sigma Delta modulator
9 * (DFSDM) peripheral:
10 * + Initialization functions.
11 * + Configuration functions.
12 * + Interrupts and flags management functions.
14 * @verbatim
16 ================================================================================
17 ##### How to use this driver #####
18 ================================================================================
19 [..]
21 @endverbatim
22 ******************************************************************************
23 * @attention
25 * <h2><center>&copy; COPYRIGHT 2016 STMicroelectronics</center></h2>
27 * Licensed under MCD-ST Liberty SW License Agreement V2, (the "License");
28 * You may not use this file except in compliance with the License.
29 * You may obtain a copy of the License at:
31 * http://www.st.com/software_license_agreement_liberty_v2
33 * Unless required by applicable law or agreed to in writing, software
34 * distributed under the License is distributed on an "AS IS" BASIS,
35 * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
36 * See the License for the specific language governing permissions and
37 * limitations under the License.
39 ******************************************************************************
42 /* Includes ------------------------------------------------------------------*/
43 #include "stm32f4xx_dfsdm.h"
44 #include "stm32f4xx_rcc.h"
46 /** @addtogroup STM32F4xx_StdPeriph_Driver
47 * @{
50 /** @defgroup DFSDM
51 * @brief DFSDM driver modules
52 * @{
54 #if defined(STM32F412xG)
56 /* External variables --------------------------------------------------------*/
57 /* Private typedef -----------------------------------------------------------*/
58 /* Private defines -----------------------------------------------------------*/
60 #define CHCFGR_INIT_CLEAR_MASK (uint32_t) 0xFFFE0F10
62 /* Private macros ------------------------------------------------------------*/
63 /* Private variables ---------------------------------------------------------*/
64 /* Private function prototypes -----------------------------------------------*/
65 /* Private functions ---------------------------------------------------------*/
67 /** @defgroup DFSDM_Private_Functions
68 * @{
71 /** @defgroup DFSDM_Group1 Initialization functions
72 * @brief Initialization functions
74 @verbatim
75 ===============================================================================
76 Initialization functions
77 ===============================================================================
78 This section provides functions allowing to:
79 - Deinitialize the DFSDM
80 - Initialize DFSDM serial channels transceiver
81 - Initialize DFSDM filter
83 @endverbatim
84 * @{
87 /**
88 * @brief Deinitializes the DFSDM peripheral registers to their default reset values.
89 * @param None.
90 * @retval None.
93 void DFSDM_DeInit(void)
95 /* Enable LPTx reset state */
96 RCC_APB2PeriphResetCmd(RCC_APB2Periph_DFSDM, ENABLE);
97 RCC_APB2PeriphResetCmd(RCC_APB2Periph_DFSDM, DISABLE);
101 * @brief Initializes the DFSDM serial channels transceiver according to the specified
102 * parameters in the DFSDM_TransceiverInit.
103 * @param DFSDM_Channelx: where x can be a value from 0 to 7 to select the DFSDM Channel.
104 * @param DFSDM_TransceiverInitStruct: pointer to a DFSDM_TransceiverInitTypeDef structure
105 * that contains the configuration information for the specified channel.
106 * @retval None
107 * @note It is mandatory to disable the selected channel to use this function.
109 void DFSDM_TransceiverInit(DFSDM_Channel_TypeDef* DFSDM_Channelx, DFSDM_TransceiverInitTypeDef* DFSDM_TransceiverInitStruct)
111 uint32_t tmpreg1 = 0;
112 uint32_t tmpreg2 = 0;
114 /* Check the parameters */
115 assert_param(IS_DFSDM_ALL_CHANNEL(DFSDM_Channelx));
116 assert_param(IS_DFSDM_INTERFACE(DFSDM_TransceiverInitStruct->DFSDM_Interface));
117 assert_param(IS_DFSDM_Input_MODE(DFSDM_TransceiverInitStruct->DFSDM_Input));
118 assert_param(IS_DFSDM_Redirection_STATE(DFSDM_TransceiverInitStruct->DFSDM_Redirection));
119 assert_param(IS_DFSDM_PACK_MODE(DFSDM_TransceiverInitStruct->DFSDM_PackingMode));
120 assert_param(IS_DFSDM_CLOCK(DFSDM_TransceiverInitStruct->DFSDM_Clock));
121 assert_param(IS_DFSDM_DATA_RIGHT_BIT_SHIFT(DFSDM_TransceiverInitStruct->DFSDM_DataRightShift));
122 assert_param(IS_DFSDM_OFFSET(DFSDM_TransceiverInitStruct->DFSDM_Offset));
123 assert_param(IS_DFSDM_CLK_DETECTOR_STATE(DFSDM_TransceiverInitStruct->DFSDM_CLKAbsenceDetector));
124 assert_param(IS_DFSDM_SC_DETECTOR_STATE(DFSDM_TransceiverInitStruct->DFSDM_ShortCircuitDetector));
126 /* Get the DFSDM Channelx CHCFGR1 value */
127 tmpreg1 = DFSDM_Channelx->CHCFGR1;
129 /* Clear SITP, CKABEN, SCDEN and SPICKSEL bits */
130 tmpreg1 &= CHCFGR_INIT_CLEAR_MASK;
132 /* Set or Reset SITP bits according to DFSDM_Interface value */
133 /* Set or Reset SPICKSEL bits according to DFSDM_Clock value */
134 /* Set or Reset DATMPX bits according to DFSDM_InputMode value */
135 /* Set or Reset CHINSEL bits according to DFSDM_Redirection value */
136 /* Set or Reset DATPACK bits according to DFSDM_PackingMode value */
137 /* Set or Reset CKABEN bit according to DFSDM_CLKAbsenceDetector value */
138 /* Set or Reset SCDEN bit according to DFSDM_ShortCircuitDetector value */
139 tmpreg1 |= (DFSDM_TransceiverInitStruct->DFSDM_Interface |
140 DFSDM_TransceiverInitStruct->DFSDM_Clock |
141 DFSDM_TransceiverInitStruct->DFSDM_Input |
142 DFSDM_TransceiverInitStruct->DFSDM_Redirection |
143 DFSDM_TransceiverInitStruct->DFSDM_PackingMode |
144 DFSDM_TransceiverInitStruct->DFSDM_CLKAbsenceDetector |
145 DFSDM_TransceiverInitStruct->DFSDM_ShortCircuitDetector);
147 /* Write to DFSDM Channelx CHCFGR1R */
148 DFSDM_Channelx->CHCFGR1 = tmpreg1;
150 /* Get the DFSDM Channelx CHCFGR2 value */
151 tmpreg2 = DFSDM_Channelx->CHCFGR2;
153 /* Clear DTRBS and OFFSET bits */
154 tmpreg2 &= ~(DFSDM_CHCFGR2_DTRBS | DFSDM_CHCFGR2_OFFSET);
156 /* Set or Reset DTRBS bits according to DFSDM_DataRightShift value */
157 /* Set or Reset OFFSET bits according to DFSDM_Offset value */
158 tmpreg2 |= (((DFSDM_TransceiverInitStruct->DFSDM_DataRightShift) <<3 ) |
159 ((DFSDM_TransceiverInitStruct->DFSDM_Offset) <<8 ));
161 /* Write to DFSDM Channelx CHCFGR1R */
162 DFSDM_Channelx->CHCFGR2 = tmpreg2;
166 * @brief Fills each DFSDM_TransceiverInitStruct member with its default value.
167 * @param DFSDM_TransceiverInitStruct : pointer to a DFSDM_TransceiverInitTypeDef structure
168 * which will be initialized.
169 * @retval None
171 void DFSDM_TransceiverStructInit(DFSDM_TransceiverInitTypeDef* DFSDM_TransceiverInitStruct)
173 /* SPI with rising edge to strobe data is selected as default serial interface */
174 DFSDM_TransceiverInitStruct->DFSDM_Interface = DFSDM_Interface_SPI_FallingEdge;
176 /* Clock coming from internal DFSDM_CKOUT output is selected as default serial clock */
177 DFSDM_TransceiverInitStruct->DFSDM_Clock = DFSDM_Clock_Internal;
179 /* No data right bit-shift is selected as default data right bit-shift */
180 DFSDM_TransceiverInitStruct->DFSDM_DataRightShift = 0x0;
182 /* No offset is selected as default offset */
183 DFSDM_TransceiverInitStruct->DFSDM_Offset = 0x0;
185 /* Clock Absence Detector is Enabled as default state */
186 DFSDM_TransceiverInitStruct->DFSDM_CLKAbsenceDetector = DFSDM_CLKAbsenceDetector_Enable;
190 * @brief Initializes the DFSDMx Filter according to the specified
191 * parameters in the DFSDM_FilterInitStruct.
192 * @param DFSDMx: where x can be a value from 0 to 1 to select the DFSDM Module.
193 * @param DFSDM_FilterInitStruct: pointer to a DFSDM_FilterInitTypeDef structure
194 * that contains the configuration information for the specified filter.
195 * @retval None
197 * @note It is mandatory to disable the selected filter to use this function.
199 void DFSDM_FilterInit(DFSDM_TypeDef* DFSDMx, DFSDM_FilterInitTypeDef* DFSDM_FilterInitStruct)
201 uint32_t tmpreg1 = 0;
203 /* Check the parameters */
204 assert_param(IS_DFSDM_ALL_FILTER(DFSDMx));
205 assert_param(IS_DFSDM_SINC_ORDER(DFSDM_FilterInitStruct->DFSDM_SincOrder));
206 assert_param(IS_DFSDM_SINC_OVRSMPL_RATIO(DFSDM_FilterInitStruct->DFSDM_FilterOversamplingRatio));
207 assert_param(IS_DFSDM_INTG_OVRSMPL_RATIO(DFSDM_FilterInitStruct->DFSDM_IntegratorOversamplingRatio));
209 /* Get the DFSDMx FCR value */
210 tmpreg1 = DFSDMx->FLTFCR;
212 /* Clear FORD, FOSR and IOSR bits */
213 tmpreg1 &= ~(DFSDM_FLTFCR_FORD | DFSDM_FLTFCR_FOSR | DFSDM_FLTFCR_IOSR);
215 /* Set or Reset FORD bits according to DFSDM_SincOrder value */
216 /* Set or Reset FOSR bits according to DFSDM_FilterOversamplingRatio value */
217 /* Set or Reset IOSR bits according to DFSDM_IntegratorOversamplingRatio value */
218 tmpreg1 |= (DFSDM_FilterInitStruct->DFSDM_SincOrder |
219 ((DFSDM_FilterInitStruct->DFSDM_FilterOversamplingRatio -1) << 16) |
220 (DFSDM_FilterInitStruct->DFSDM_IntegratorOversamplingRatio -1));
222 /* Write to DFSDMx FCR */
223 DFSDMx->FLTFCR = tmpreg1;
227 * @brief Fills each DFSDM_FilterInitStruct member with its default value.
228 * @param DFSDM_FilterInitStruct: pointer to a DFSDM_FilterInitTypeDef structure
229 * which will be initialized.
230 * @retval None
232 void DFSDM_FilterStructInit(DFSDM_FilterInitTypeDef* DFSDM_FilterInitStruct)
234 /* Order = 3 is selected as default sinc order */
235 DFSDM_FilterInitStruct->DFSDM_SincOrder = DFSDM_SincOrder_Sinc3;
237 /* Ratio = 64 is selected as default oversampling ratio */
238 DFSDM_FilterInitStruct->DFSDM_FilterOversamplingRatio = 64 ;
240 /* Ratio = 4 is selected as default integrator oversampling ratio */
241 DFSDM_FilterInitStruct->DFSDM_IntegratorOversamplingRatio = 4;
245 * @}
248 /** @defgroup DFSDM_Group2 Configuration functions
249 * @brief Configuration functions
251 @verbatim
252 ===============================================================================
253 Configuration functions
254 ===============================================================================
255 This section provides functions allowing to configure DFSDM:
256 - Enable/Disable (DFSDM peripheral, Channel, Filter)
257 - Configure Clock output
258 - Configure Injected/Regular channels for Conversion
259 - Configure short circuit detector
260 - Configure Analog watchdog filter
262 @endverbatim
263 * @{
267 * @brief Enables or disables the DFSDM peripheral.
268 * @param NewState: new state of the DFSDM interface.
269 * This parameter can be: ENABLE or DISABLE.
270 * @retval None
272 void DFSDM_Cmd(FunctionalState NewState)
274 /* Check the parameters */
275 assert_param(IS_FUNCTIONAL_STATE(NewState));
277 if (NewState != DISABLE)
279 /* Set the ENABLE bit */
280 DFSDM1_Channel0 -> CHCFGR1 |= DFSDM_CHCFGR1_DFSDMEN;
282 else
284 /* Reset the ENABLE bit */
285 DFSDM1_Channel0 -> CHCFGR1 &= ~(DFSDM_CHCFGR1_DFSDMEN);
290 * @brief Enables or disables the specified DFSDM serial channelx.
291 * @param DFSDM_Channelx: where x can be a value from 0 to 7 to select the DFSDM Channel.
292 * @param NewState: new state of the DFSDM serial channelx .
293 * This parameter can be: ENABLE or DISABLE.
294 * @retval None
296 void DFSDM_ChannelCmd(DFSDM_Channel_TypeDef* DFSDM_Channelx, FunctionalState NewState)
298 /* Check the parameters */
299 assert_param(IS_DFSDM_ALL_CHANNEL(DFSDM_Channelx));
300 assert_param(IS_FUNCTIONAL_STATE(NewState));
302 if (NewState != DISABLE)
304 /* Set the ENABLE bit */
305 DFSDM_Channelx->CHCFGR1 |= DFSDM_CHCFGR1_CHEN;
307 else
309 /* Reset the ENABLE bit */
310 DFSDM_Channelx->CHCFGR1 &= ~(DFSDM_CHCFGR1_CHEN);
315 * @brief Enables or disables the specified DFSDMx Filter.
316 * @param DFSDMx: where x can be 0, 1 to select the DFSDM module.
317 * @param NewState: new state of the selected DFSDM module.
318 * This parameter can be: ENABLE or DISABLE.
319 * @retval None
321 void DFSDM_FilterCmd(DFSDM_TypeDef* DFSDMx, FunctionalState NewState)
323 /* Check the parameters */
324 assert_param(IS_DFSDM_ALL_FILTER(DFSDMx));
325 assert_param(IS_FUNCTIONAL_STATE(NewState));
327 if (NewState != DISABLE)
329 /* Set the ENABLE bit */
330 DFSDMx->FLTCR1 |= DFSDM_FLTCR1_DFEN;
332 else
334 /* Reset the ENABLE bit */
335 DFSDMx->FLTCR1 &= ~(DFSDM_FLTCR1_DFEN);
340 * @brief Configures the Output serial clock divider.
341 * @param DFSDM_ClkOutDivision: Defines the divider for the output serial clock
342 * This parameter can be a value between 1 and 256.
343 * @retval None
344 * @note The output serial clock is stopped if the divider =1.
345 * By default the serial output clock is stopped.
347 void DFSDM_ConfigClkOutputDivider(uint32_t DFSDM_ClkOutDivision)
349 uint32_t tmpreg1 = 0;
351 /* Check the parameters */
352 assert_param(IS_DFSDM_CLOCK_OUT_DIVIDER(DFSDM_ClkOutDivision));
354 /* Get the DFSDM_Channel0 CHCFGR1 value */
355 tmpreg1 = DFSDM1_Channel0 -> CHCFGR1;
357 /* Clear the CKOUTDIV bits */
358 tmpreg1 &= (uint32_t)(~DFSDM_CHCFGR1_CKOUTDIV);
360 /* Set or Reset the CKOUTDIV bits */
361 tmpreg1 |= (uint32_t)((DFSDM_ClkOutDivision - 1) << 16);
363 /* Write to DFSDM Channel0 CHCFGR1 */
364 DFSDM1_Channel0 -> CHCFGR1 = tmpreg1;
368 * @brief Configures the Output serial clock source.
369 * @param DFSDM_ClkOutSource: Defines the divider for the output serial clock
370 * This parameter can be a value of:
371 * @arg DFSDM_ClkOutSource_SysClock
372 * @arg DFSDM_ClkOutSource_AudioClock
373 * @retval None
375 void DFSDM_ConfigClkOutputSource(uint32_t DFSDM_ClkOutSource)
377 uint32_t tmpreg1 = 0;
379 /* Check the parameters */
380 assert_param(IS_DFSDM_CLOCK_OUT_SOURCE(DFSDM_ClkOutSource));
382 /* Get the DFSDM_Channel0 CHCFGR1 value */
383 tmpreg1 = DFSDM1_Channel0 -> CHCFGR1;
385 /* Clear the CKOUTSRC bit */
386 tmpreg1 &= ~(DFSDM_CHCFGR1_CKOUTSRC);
388 /* Set or Reset the CKOUTSRC bit */
389 tmpreg1 |= DFSDM_ClkOutSource;
391 /* Write to DFSDM Channel0 CHCFGR1 */
392 DFSDM1_Channel0 -> CHCFGR1 = tmpreg1;
396 * @brief Enables or disables the specified Break_i siganl to the specified DFSDM_Channelx.
397 * @param DFSDM_Channelx: where x can be a value from 0 to 7 to select the DFSDM Channel.
398 * @param DFSDM_SCDBreak_i: where i can be a value from 0 to 3 to select the specified Break signal.
399 * @param NewState: new state of the selected DFSDM_SCDBreak_i.
400 * This parameter can be: ENABLE or DISABLE.
401 * @retval None
403 void DFSDM_ConfigBRKAnalogWatchDog(DFSDM_Channel_TypeDef* DFSDM_Channelx, uint32_t DFSDM_SCDBreak_i, FunctionalState NewState)
405 /* Check the parameters */
406 assert_param(IS_DFSDM_ALL_CHANNEL(DFSDM_Channelx));
407 assert_param(IS_DFSDM_SCD_BREAK_SIGNAL(DFSDM_SCDBreak_i));
408 assert_param(IS_FUNCTIONAL_STATE(NewState));
410 if (NewState != DISABLE)
412 /* Set the BKSCD[i] bit */
413 DFSDM_Channelx -> CHAWSCDR |= DFSDM_SCDBreak_i;
415 else
417 /* Reset the BKSCD[i] bit */
418 DFSDM_Channelx -> CHAWSCDR &= ~(DFSDM_SCDBreak_i);
423 * @brief Enables or disables the specified Break_i siganl to the specified DFSDM_Channelx.
424 * @param DFSDM_Channelx: where x can be a value from 0 to 7 to select the DFSDM Channel.
425 * @param DFSDM_SCDBreak_i: where i can be a value from 0 to 3 to select the specified Break signal.
426 * @param NewState: new state of the selected DFSDM_SCDBreak_i.
427 * This parameter can be: ENABLE or DISABLE.
428 * @retval None
430 void DFSDM_ConfigBRKShortCircuitDetector(DFSDM_Channel_TypeDef* DFSDM_Channelx, uint32_t DFSDM_SCDBreak_i, FunctionalState NewState)
432 /* Check the parameters */
433 assert_param(IS_DFSDM_ALL_CHANNEL(DFSDM_Channelx));
434 assert_param(IS_DFSDM_SCD_BREAK_SIGNAL(DFSDM_SCDBreak_i));
435 assert_param(IS_FUNCTIONAL_STATE(NewState));
437 if (NewState != DISABLE)
439 /* Set the BKSCD[i] bit */
440 DFSDM_Channelx -> CHAWSCDR |= DFSDM_SCDBreak_i;
442 else
444 /* Reset the BKSCD[i] bit */
445 DFSDM_Channelx -> CHAWSCDR &= ~(DFSDM_SCDBreak_i);
450 * @brief Defines the threshold counter for the short circuit detector for the selected DFSDM_Channelx.
451 * @param DFSDM_Channelx: where x can be a value from 0 to 7 to select the DFSDM Channel.
452 * @param DFSDM_SCDThreshold: The threshold counter, this parameter can be a value between 0 and 255.
453 * @retval None
455 void DFSDM_ConfigShortCircuitThreshold(DFSDM_Channel_TypeDef* DFSDM_Channelx, uint32_t DFSDM_SCDThreshold)
457 uint32_t tmpreg1 = 0;
459 /* Check the parameters */
460 assert_param(IS_DFSDM_ALL_CHANNEL(DFSDM_Channelx));
461 assert_param(IS_DFSDM_CSD_THRESHOLD_VALUE(DFSDM_SCDThreshold));
463 /* Get the DFSDM_Channelx AWSCDR value */
464 tmpreg1 = DFSDM_Channelx -> CHAWSCDR;
466 /* Clear the SCDT bits */
467 tmpreg1 &= ~(DFSDM_CHAWSCDR_SCDT);
469 /* Set or Reset the SCDT bits */
470 tmpreg1 |= DFSDM_SCDThreshold;
472 /* Write to DFSDM Channelx AWSCDR */
473 DFSDM_Channelx -> CHAWSCDR = tmpreg1;
477 * @brief Selects the channel to be guarded by the Analog watchdog for the selected DFSDMx,
478 * and select if the fast analog watchdog is enabled or not.
479 * @param DFSDMx: where x can be a value from 0 to 1 to select the DFSDM Module.
480 * @param DFSDM_AWDChannelx: where x can be a value from 0 to 7 to select the DFSDM Channel.
481 * @param DFSDM_AWDFastMode: The analog watchdog fast mode.
482 * This parameter can be a value of @ref DFSDM_AWD_Fast_Mode_Selection.
483 * @retval None
485 void DFSDM_ConfigAnalogWatchdog(DFSDM_TypeDef* DFSDMx, uint32_t DFSDM_AWDChannelx, uint32_t DFSDM_AWDFastMode)
487 uint32_t tmpreg1 = 0;
488 uint32_t tmpreg2 = 0;
490 /* Check the parameters */
491 assert_param(IS_DFSDM_ALL_FILTER(DFSDMx));
492 assert_param(IS_DFSDM_AWD_CHANNEL(DFSDM_AWDChannelx));
493 assert_param(IS_DFSDM_AWD_MODE(DFSDM_AWDFastMode));
495 /* Get the DFSDMx CR2 value */
496 tmpreg1 = DFSDMx -> FLTCR2;
498 /* Clear the AWDCH bits */
499 tmpreg1 &= ~(DFSDM_FLTCR2_AWDCH);
501 /* Set or Reset the AWDCH bits */
502 tmpreg1 |= DFSDM_AWDChannelx;
504 /* Write to DFSDMx CR2 Register */
505 DFSDMx -> FLTCR2 |= tmpreg1;
507 /* Get the DFSDMx CR1 value */
508 tmpreg2 = DFSDMx->FLTCR1;
510 /* Clear the AWFSEL bit */
511 tmpreg2 &= ~(DFSDM_FLTCR1_AWFSEL);
513 /* Set or Reset the AWFSEL bit */
514 tmpreg2 |= DFSDM_AWDFastMode;
516 /* Write to DFSDMx CR1 Register */
517 DFSDMx->FLTCR1 = tmpreg2;
521 * @brief Selects the channel to be guarded by the Analog watchdog of the selected DFSDMx, and the mode to be used.
522 * @param DFSDMx: where x can be a value from 0 to 1 to select the DFSDM Module.
523 * @param DFSDM_ExtremChannelx: where x can be a value from 0 to 7 to select the Channel to be connected
524 * to the Extremes detector.
525 * @retval None
527 void DFSDM_SelectExtremesDetectorChannel(DFSDM_TypeDef* DFSDMx, uint32_t DFSDM_ExtremChannelx)
529 uint32_t tmpreg1 = 0;
531 /* Check the parameters */
532 assert_param(IS_DFSDM_ALL_FILTER(DFSDMx));
533 assert_param(IS_DFSDM_EXTREM_CHANNEL(DFSDM_ExtremChannelx));
535 /* Get the DFSDMx CR2 value */
536 tmpreg1 = DFSDMx -> FLTCR2;
538 /* Clear the EXCH bits */
539 tmpreg1 &= ~(DFSDM_FLTCR2_EXCH);
541 /* Set or Reset the AWDCH bits */
542 tmpreg1 |= DFSDM_ExtremChannelx;
544 /* Write to DFSDMx CR2 Register */
545 DFSDMx -> FLTCR2 = tmpreg1;
549 * @brief Returns the regular conversion data by the DFSDMx.
550 * @param DFSDMx: where x can be a value from 0 to 1 to select the DFSDM Module.
551 * @retval The converted regular data.
552 * @note This function returns a signed value.
554 int32_t DFSDM_GetRegularConversionData(DFSDM_TypeDef* DFSDMx)
556 uint32_t reg = 0;
557 int32_t value = 0;
559 /* Check the parameters */
560 assert_param(IS_DFSDM_ALL_FILTER(DFSDMx));
562 /* Get value of data register for regular channel */
563 reg = DFSDMx -> FLTRDATAR;
565 /* Extract conversion value */
566 value = ((int32_t)((reg & 0xFFFFFF00) >> 8));
568 /* Return the conversion result */
569 return value;
573 * @brief Returns the injected conversion data by the DFSDMx.
574 * @param DFSDMx: where x can be a value from 0 to 1 to select the DFSDM Module.
575 * @retval The converted regular data.
576 * @note This function returns a signed value.
578 int32_t DFSDM_GetInjectedConversionData(DFSDM_TypeDef* DFSDMx)
580 uint32_t reg = 0;
581 int32_t value = 0;
583 /* Check the parameters */
584 assert_param(IS_DFSDM_ALL_FILTER(DFSDMx));
586 /* Get value of data register for regular channel */
587 reg = DFSDMx -> FLTJDATAR;
589 /* Extract conversion value */
590 value = ((int32_t)((reg & 0xFFFFFF00) >> 8));
592 /* Return the conversion result */
593 return value;
597 * @brief Returns the highest value converted by the DFSDMx.
598 * @param DFSDMx: where x can be a value from 0 to 1 to select the DFSDM Module.
599 * @retval The highest converted value.
600 * @note This function returns a signed value.
602 int32_t DFSDM_GetMaxValue(DFSDM_TypeDef* DFSDMx)
604 /* Check the parameters */
605 assert_param(IS_DFSDM_ALL_FILTER(DFSDMx));
607 /* Return the highest converted value */
608 return (((int32_t)(DFSDMx -> FLTEXMAX)) >> 8);
612 * @brief Returns the lowest value converted by the DFSDMx.
613 * @param DFSDMx: where x can be a value from 0 to 1 to select the DFSDM Module.
614 * @retval The lowest converted value.
615 * @note This function returns a signed value.
617 int32_t DFSDM_GetMinValue(DFSDM_TypeDef* DFSDMx)
619 /* Check the parameters */
620 assert_param(IS_DFSDM_ALL_FILTER(DFSDMx));
622 /* Return the lowest conversion value */
623 return (((int32_t)(DFSDMx ->FLTEXMIN )) >> 8);
627 * @brief Returns the number of channel on which is captured the highest converted data by the DFSDMx.
628 * @param DFSDMx: where x can be a value from 0 to 1 to select the DFSDM Module.
629 * @retval The highest converted value.
631 int32_t DFSDM_GetMaxValueChannel(DFSDM_TypeDef* DFSDMx)
633 /* Check the parameters */
634 assert_param(IS_DFSDM_ALL_FILTER(DFSDMx));
636 /* Return the highest converted value */
637 return ((DFSDMx -> FLTEXMAX) & (~DFSDM_FLTEXMAX_EXMAXCH));
641 * @brief Returns the number of channel on which is captured the lowest converted data by the DFSDMx.
642 * @param DFSDMx: where x can be a value from 0 to 1 to select the DFSDM Module.
643 * @retval The lowest converted value.
645 int32_t DFSDM_GetMinValueChannel(DFSDM_TypeDef* DFSDMx)
647 /* Check the parameters */
648 assert_param(IS_DFSDM_ALL_FILTER(DFSDMx));
650 /* Return the lowest converted value */
651 return ((DFSDMx -> FLTEXMIN) & (~DFSDM_FLTEXMIN_EXMINCH));
655 * @brief Returns the conversion time (in 28-bit timer unit) for DFSDMx.
656 * @param DFSDMx: where x can be a value from 0 to 1 to select the DFSDM Module.
657 * @retval Conversion time.
659 uint32_t DFSDM_GetConversionTime(DFSDM_TypeDef* DFSDMx)
661 /* Check the parameters */
662 assert_param(IS_DFSDM_ALL_FILTER(DFSDMx));
664 /* Return the lowest converted value */
665 return ((DFSDMx -> FLTCNVTIMR >> 4) & 0x0FFFFFFF);
669 * @brief Configures Sinc Filter for the Analog watchdog by setting
670 * the Sinc filter order and the Oversampling ratio for the specified DFSDM_Channelx.
671 * @param DFSDM_Channelx: where x can be a value from 0 to 7 to select the DFSDM Channel.
672 * @param DFSDM_AWDSincOrder: The Sinc Filter order this parameter can be a value of @ref DFSDM_AWD_Sinc_Order.
673 * @param DFSDM_AWDSincOverSampleRatio: The Filter Oversampling ratio, this parameter can be a value between 1 and 32.
674 * @retval None
676 void DFSDM_ConfigAWDFilter(DFSDM_Channel_TypeDef* DFSDM_Channelx, uint32_t DFSDM_AWDSincOrder, uint32_t DFSDM_AWDSincOverSampleRatio)
678 uint32_t tmpreg1 = 0;
680 /* Check the parameters */
681 assert_param(IS_DFSDM_ALL_CHANNEL(DFSDM_Channelx));
682 assert_param(IS_DFSDM_AWD_SINC_ORDER(DFSDM_AWDSincOrder));
683 assert_param(IS_DFSDM_AWD_OVRSMPL_RATIO(DFSDM_AWDSincOverSampleRatio));
685 /* Get the DFSDM_Channelx CHAWSCDR value */
686 tmpreg1 = DFSDM_Channelx -> CHAWSCDR;
688 /* Clear the FORD and FOSR bits */
689 tmpreg1 &= ~(DFSDM_CHAWSCDR_AWFORD | DFSDM_CHAWSCDR_AWFOSR);
691 /* Set or Reset the SCDT bits */
692 tmpreg1 |= (DFSDM_AWDSincOrder | ((DFSDM_AWDSincOverSampleRatio -1) << 16)) ;
694 /* Write to DFSDM Channelx CHAWSCDR */
695 DFSDM_Channelx -> CHAWSCDR = tmpreg1;
699 * @brief Returns the last Analog Watchdog Filter conversion result data for channelx.
700 * @param DFSDM_Channelx: where x can be a value from 0 to 7 to select the DFSDM Channel.
701 * @retval The Data conversion value.
703 uint32_t DFSDM_GetAWDConversionValue(DFSDM_Channel_TypeDef* DFSDM_Channelx)
705 /* Check the parameters */
706 assert_param(IS_DFSDM_ALL_CHANNEL(DFSDM_Channelx));
708 /* Return the last analog watchdog filter conversion value */
709 return DFSDM_Channelx -> CHWDATAR;
714 * @brief Configures the High Threshold and the Low threshold for the Analog watchdog of the selected DFSDMx.
715 * @param DFSDM_HighThreshold: High threshold value. This parameter can be value between 0 and 0xFFFFFF.
716 * @param DFSDM_LowThreshold: Low threshold value. This parameter can be value between 0 and 0xFFFFFF.
717 * @retval None.
718 * @note In case of channels transceivers monitoring (Analog Watchdog fast mode Enabled)),
719 * only the higher 16 bits define the 16-bit threshold compared with analog watchdog filter output.
722 void DFSDM_SetAWDThreshold(DFSDM_TypeDef* DFSDMx, uint32_t DFSDM_HighThreshold, uint32_t DFSDM_LowThreshold)
724 uint32_t tmpreg1 = 0;
725 uint32_t tmpreg2 = 0;
727 /* Check the parameters */
728 assert_param(IS_DFSDM_HIGH_THRESHOLD(DFSDM_HighThreshold));
729 assert_param(IS_DFSDM_LOW_THRESHOLD(DFSDM_LowThreshold));
731 /* Get the DFSDMx AWHTR value */
732 tmpreg1 = DFSDMx -> FLTAWHTR;
734 /* Clear the AWHT bits */
735 tmpreg1 &= ~(DFSDM_FLTAWHTR_AWHT);
737 /* Set or Reset the AWHT bits */
738 tmpreg1 |= (DFSDM_HighThreshold << 8 );
740 /* Write to DFSDMx AWHTR Register */
741 DFSDMx -> FLTAWHTR = tmpreg1;
743 /* Get the DFSDMx AWLTR value */
744 tmpreg2 = DFSDMx -> FLTAWLTR;
746 /* Clear the AWLTR bits */
747 tmpreg2 &= ~(DFSDM_FLTAWLTR_AWLT);
749 /* Set or Reset the AWLTR bits */
750 tmpreg2 |= (DFSDM_LowThreshold << 8 );
752 /* Write to DFSDMx AWLTR Register */
753 DFSDMx -> FLTAWLTR = tmpreg2;
757 * @brief Selects the injected channel for the selected DFSDMx.
758 * @param DFSDMx: where x can be a value from 0 to 1 to select the DFSDM Module.
759 * @param DFSDM_InjectedChannelx: where x can be a value from 0 to 7 to select the Channel to be configuraed as
760 * injected channel.
761 * @retval None
762 * @note User can select up to 8 channels.
764 void DFSDM_SelectInjectedChannel(DFSDM_TypeDef* DFSDMx, uint32_t DFSDM_InjectedChannelx)
766 uint32_t tmpreg1 = 0;
768 /* Check the parameters */
769 assert_param(IS_DFSDM_ALL_FILTER(DFSDMx));
770 assert_param(IS_DFSDM_INJECT_CHANNEL(DFSDM_InjectedChannelx));
772 /* Get the DFSDMx JCHGR value */
773 tmpreg1 = DFSDMx -> FLTJCHGR;
775 /* Clear the JCHGR bits */
776 tmpreg1 &= ~(DFSDM_FLTJCHGR_JCHG);
778 /* Set or Reset the JCHGR bits */
779 tmpreg1 |= DFSDM_InjectedChannelx;
781 /* Write to DFSDMx JCHGR Register */
782 DFSDMx -> FLTJCHGR |= tmpreg1;
786 * @brief Selects the regular channel for the selected DFSDMx.
787 * @param DFSDMx: where x can be a value from 0 to 1 to select the DFSDM Module.
788 * @param DFSDM_RegularChannelx: where x can be a value from 0 to 7 to select the Channel to be configurated as
789 * regular channel.
790 * @retval None
791 * @note User can select only one channel.
793 void DFSDM_SelectRegularChannel(DFSDM_TypeDef* DFSDMx, uint32_t DFSDM_RegularChannelx)
795 uint32_t tmpreg1 = 0;
797 /* Check the parameters */
798 assert_param(IS_DFSDM_ALL_FILTER(DFSDMx));
799 assert_param(IS_DFSDM_REGULAR_CHANNEL(DFSDM_RegularChannelx));
801 /* Get the DFSDMx CR1 value */
802 tmpreg1 = DFSDMx -> FLTCR1;
804 /* Clear the RCH bits */
805 tmpreg1 &= ~(DFSDM_FLTCR1_RCH);
807 /* Set or Reset the RCH bits */
808 tmpreg1 |= DFSDM_RegularChannelx;
810 /* Write to DFSDMx CR1 Register */
811 DFSDMx -> FLTCR1 = tmpreg1;
815 * @brief Starts a software start for the injected group of channels of the selected DFSDMx.
816 * @param DFSDMx: where x can be a value from 0 to 1 to select the DFSDM Module.
817 * @retval None
819 void DFSDM_StartSoftwareInjectedConversion(DFSDM_TypeDef* DFSDMx)
821 /* Check the parameters */
822 assert_param(IS_DFSDM_ALL_FILTER(DFSDMx));
824 /* Write 1 to DFSDMx CR1 RSWSTAR bit */
825 DFSDMx -> FLTCR1 |= DFSDM_FLTCR1_JSWSTART;
829 * @brief Starts a software start of the regular channel of the selected DFSDMx.
830 * @param DFSDMx: where x can be a value from 0 to 1 to select the DFSDM Module.
831 * @retval None
833 void DFSDM_StartSoftwareRegularConversion(DFSDM_TypeDef* DFSDMx)
835 /* Check the parameters */
836 assert_param(IS_DFSDM_ALL_FILTER(DFSDMx));
838 /* Write 1 to DFSDMx CR1 RSWSTAR bit */
839 DFSDMx -> FLTCR1 |= DFSDM_FLTCR1_RSWSTART;
843 * @brief Selects the Trigger signal to launch the injected conversions of the selected DFSDMx.
844 * @param DFSDMx: where x can be a value from 0 to 1 to select the DFSDM Module.
845 * @param DFSDM_InjectedTrigger: the trigger signal.
846 * This parameter can be a value of: @ref DFSDM_Injected_Trigger_signal
847 * @param DFSDM_TriggerEdge: the edge of the selected trigger
848 * This parameter can be a value of: @ref DFSDM_Trigger_Edge_selection
849 * @retval None.
850 * @note This function can be used only when the filter is disabled, use DFSDM_FilterCmd()
851 * to disable the filter.
853 void DFSDM_ConfigInjectedTrigger(DFSDM_TypeDef* DFSDMx, uint32_t DFSDM_Trigger, uint32_t DFSDM_TriggerEdge)
855 uint32_t tmpreg1 = 0;
857 /* Check the parameters */
858 assert_param(IS_DFSDM_ALL_FILTER(DFSDMx));
860 if (DFSDMx == DFSDM0)
862 assert_param(IS_DFSDM0_INJ_TRIGGER(DFSDM_Trigger));
864 else
866 assert_param(IS_DFSDM1_INJ_TRIGGER(DFSDM_Trigger));
869 assert_param(IS_DFSDM_TRIGGER_EDGE(DFSDM_TriggerEdge));
871 /* Get the DFSDMx CR1 value */
872 tmpreg1 = DFSDMx -> FLTCR1;
874 /* Clear the JEXTSEL & JEXTEN bits */
875 tmpreg1 &= ~(DFSDM_FLTCR1_JEXTSEL | DFSDM_FLTCR1_JEXTEN);
877 /* Set or Reset the JEXTSEL & JEXTEN bits */
878 tmpreg1 |= (DFSDM_Trigger | DFSDM_TriggerEdge);
880 /* Write to DFSDMx CR1 Register */
881 DFSDMx -> FLTCR1 = tmpreg1;
885 * @brief Starts an injected conversion synchronously when in DFSDM0
886 * an injected conversion started by software.
887 * @param DFSDMx: where x can be 0 or 1 to select the DFSDM Module.
888 * @retval None
889 * @note This function can be used only when the filter is disabled, use DFSDM_FilterCmd()
890 * to disable the filter.
892 void DFSDM_SynchronousFilter0InjectedStart(DFSDM_TypeDef* DFSDMx)
894 /* Check the parameters */
895 assert_param(IS_DFSDM_SYNC_FILTER(DFSDMx));
897 /* Write 1 to DFSDMx CR1 JSYNC bit */
898 DFSDMx -> FLTCR1 |= DFSDM_FLTCR1_JSYNC;
902 * @brief Starts a regular conversion synchronously when in DFSDM0
903 * a regular conversion started by software.
904 * @param DFSDMx: where x can be 0 or 1 to select the DFSDM Module.
905 * @retval None
906 * @note This function can be used only when the filter is disabled, use DFSDM_FilterCmd()
907 * to disable the filter.
909 void DFSDM_SynchronousFilter0RegularStart(DFSDM_TypeDef* DFSDMx)
911 /* Check the parameters */
912 assert_param(IS_DFSDM_SYNC_FILTER(DFSDMx));
914 /* Write 1 to DFSDMx CR1 RSYNC bit */
915 DFSDMx -> FLTCR1 |= DFSDM_FLTCR1_RSYNC;
919 * @brief Enables or Disables the continue mode for Regular conversion for the selected filter DFSDMx.
920 * @param DFSDMx: where x can be 0 or 1 to select the DFSDM Module.
921 * @param NewState: new state of the Continuous mode.
922 * This parameter can be: ENABLE or DISABLE.
923 * @retval None
925 void DFSDM_RegularContinuousModeCmd(DFSDM_TypeDef* DFSDMx, FunctionalState NewState)
927 /* Check the parameters */
928 assert_param(IS_DFSDM_ALL_FILTER(DFSDMx));
929 assert_param(IS_FUNCTIONAL_STATE(NewState));
931 if (NewState != DISABLE)
933 /* Enable the RCONT bit */
934 DFSDMx -> FLTCR1 |= DFSDM_FLTCR1_RCONT;
936 else
938 /* Disable the RCONT bit */
939 DFSDMx -> FLTCR1 &= ~(DFSDM_FLTCR1_RCONT);
944 * @brief Enables or Disables the Fast mode for the selected filter DFSDMx.
945 * @param DFSDMx: where x can be 0 or 1 to select the DFSDM Module.
946 * @param NewState: new state of the Fast mode.
947 * This parameter can be: ENABLE or DISABLE.
948 * @retval None
949 * @note If just a single channel is selected in continuous mode (either by executing a regular
950 * conversion or by executing a injected conversion with only one channel selected),
951 * the sampling rate can be increased several times by enabling the fast mode.
952 * @note This function can be used only when the filter is disabled, use DFSDM_FilterCmd()
953 * to disable the filter.
955 void DFSDM_FastModeCmd(DFSDM_TypeDef* DFSDMx, FunctionalState NewState)
957 /* Check the parameters */
958 assert_param(IS_DFSDM_ALL_FILTER(DFSDMx));
959 assert_param(IS_FUNCTIONAL_STATE(NewState));
961 if (NewState != DISABLE)
963 /* Enable the FAST bit */
964 DFSDMx -> FLTCR1 |= DFSDM_FLTCR1_FAST;
966 else
968 /* Disable the FAST bit */
969 DFSDMx -> FLTCR1 &= ~(DFSDM_FLTCR1_FAST);
974 * @brief Selects the injected conversions mode for the selected DFSDMx.
975 * Injected conversions can operates in Single mode or Scan mode.
976 * @param DFSDMx: where x can be a value from 0 to 1 to select the DFSDM Module.
977 * @param DFSDM_InjectConvMode: The injected conversion mode, this parameter can be:
978 * @arg DFSDM_InjectConvMode_Single
979 * @arg DFSDM_InjectConvMode_Scan
980 * @retval None.
981 * @note This function can be used only when the filter is disabled, use DFSDM_FilterCmd()
982 * to disable the filter.
984 void DFSDM_SelectInjectedConversionMode(DFSDM_TypeDef* DFSDMx, uint32_t DFSDM_InjectConvMode)
986 /* Check the parameters */
987 assert_param(IS_DFSDM_ALL_FILTER(DFSDMx));
988 assert_param(IS_DFSDM_INJ_CONV_MODE(DFSDM_InjectConvMode));
990 /* Clear the JSCAN bit */
991 DFSDMx -> FLTCR1 &= ~(DFSDM_FLTCR1_JSCAN);
993 /* Write to DFSDMx CR1 Register */
994 DFSDMx -> FLTCR1 |= DFSDM_InjectConvMode;
998 * @brief Enables or Disables the DMA to read data for the injected channel group of the selected filter DFSDMx.
999 * @param DFSDMx: where x can be 0 or 1 to select the DFSDM Module.
1000 * @param DFSDM_DMAConversionMode: Selects the mode to be configured for DMA read .
1001 * @arg DFSDM_DMAConversionMode_Regular: DMA channel Enabled/Disabled to read data for the regular conversion
1002 * @arg DFSDM_DMAConversionMode_Injected: DMA channel Enabled/Disabled to read data for the Injected conversion
1003 * @param NewState: new state of the DMA channel.
1004 * This parameter can be: ENABLE or DISABLE.
1005 * @retval None.
1006 * @note This function can be used only when the filter is disabled, use DFSDM_FilterCmd()
1007 * to disable the filter.
1009 void DFSDM_DMATransferConfig(DFSDM_TypeDef* DFSDMx, uint32_t DFSDM_DMAConversionMode, FunctionalState NewState)
1011 /* Check the parameters */
1012 assert_param(IS_DFSDM_ALL_FILTER(DFSDMx));
1013 assert_param(IS_DFSDM_CONVERSION_MODE(DFSDM_DMAConversionMode));
1014 assert_param(IS_FUNCTIONAL_STATE(NewState));
1016 if (NewState != DISABLE)
1018 /* Enable the JDMAEN or RDMAEN bit */
1019 DFSDMx -> FLTCR1 |= (DFSDM_FLTCR1_JDMAEN << DFSDM_DMAConversionMode) ;
1021 else
1023 /* Disable the JDMAEN or RDMAEN bit */
1024 DFSDMx -> FLTCR1 &= ~(DFSDM_FLTCR1_JDMAEN << DFSDM_DMAConversionMode);
1028 /** @defgroup DFSDM_Group3 Interrupts and flags management functions
1029 * @brief Interrupts and flags management functions
1031 @verbatim
1032 ===============================================================================
1033 Interrupts and flags management functions
1034 ===============================================================================
1035 This section provides functions allowing to configure the DFSDM Interrupts, get
1036 the status and clear flags bits.
1038 The LPT provides 7 Flags and Interrupts sources (2 flags and Interrupt sources
1039 are available only on LPT peripherals equipped with encoder mode interface)
1041 Flags and Interrupts sources:
1042 =============================
1043 1. End of injected conversion.
1044 2. End of regular conversion.
1045 3. Injected data overrun.
1046 4. Regular data overrun.
1047 5. Analog watchdog.
1048 6. Short circuit detector.
1049 7. Channel clock absence
1051 - To enable a specific interrupt source, use "DFSDM_ITConfig",
1052 "DFSDM_ITClockAbsenceCmd" and "DFSDM_ITShortCircuitDetectorCmd" functions.
1053 - To check if an interrupt was occurred, call "DFSDM_GetITStatus","DFSDM_GetClockAbsenceITStatusfunction"
1054 and "DFSDM_GetGetShortCircuitITStatus" functions and read returned values.
1055 - To get a flag status, call the "DFSDM_GetFlagStatus" ,"DFSDM_GetClockAbsenceFlagStatus" ,"DFSDM_GetShortCircuitFlagStatus"
1056 and "DFSDM_GetWatchdogFlagStatus" functions and read the returned value.
1057 - To clear a flag or an interrupt, use DFSDM_ClearFlag,DFSDM_ClearClockAbsenceFlag,
1058 DFSDM_ClearShortCircuitFlag,DFSDM_ClearAnalogWatchdogFlag functions with the
1059 corresponding flag (interrupt).
1061 @endverbatim
1062 * @{
1066 * @brief Enables or disables the specified DFSDMx interrupts.
1067 * @param DFSDMx: where x can be 0 or 1 to select the DFSDM peripheral.
1068 * @param DFSDM_IT: specifies the DFSDM interrupts sources to be enabled or disabled.
1069 * This parameter can be any combination of the following values:
1070 * @arg DFSDM_IT_JEOC: End of injected conversion Interrupt source
1071 * @arg DFSDM_IT_REOC: End of regular conversion Interrupt source
1072 * @arg DFSDM_IT_JOVR: Injected data overrun Interrupt source
1073 * @arg DFSDM_IT_ROVR: Regular data overrun Interrupt source
1074 * @arg DFSDM_IT_AWD : Analog watchdog Interrupt source
1075 * @param NewState: new state of the DFSDM interrupts.
1076 * This parameter can be: ENABLE or DISABLE.
1077 * @retval None
1079 void DFSDM_ITConfig(DFSDM_TypeDef* DFSDMx, uint32_t DFSDM_IT, FunctionalState NewState)
1081 /* Check the parameters */
1082 assert_param(IS_DFSDM_ALL_FILTER(DFSDMx));
1083 assert_param(IS_DFSDM_IT(DFSDM_IT));
1084 assert_param(IS_FUNCTIONAL_STATE(NewState));
1086 if (NewState != DISABLE)
1088 /* Enable the Interrupt sources */
1089 DFSDMx->FLTCR2 |= DFSDM_IT;
1091 else
1093 /* Disable the Interrupt sources */
1094 DFSDMx->FLTCR2 &= ~(DFSDM_IT);
1099 * @brief Enables or disables the Clock Absence Interrupt.
1100 * @param NewState: new state of the interrupt.
1101 * This parameter can be: ENABLE or DISABLE.
1102 * @retval None
1104 void DFSDM_ITClockAbsenceCmd(FunctionalState NewState)
1106 /* Check the parameters */
1107 assert_param(IS_FUNCTIONAL_STATE(NewState));
1109 if (NewState != DISABLE)
1111 /* Enable the Interrupt source */
1112 DFSDM0->FLTCR2 |= DFSDM_IT_CKAB;
1114 else
1116 /* Disable the Interrupt source */
1117 DFSDM0->FLTCR2 &= ~(DFSDM_IT_CKAB);
1122 * @brief Enables or disables the Short Circuit Detector Interrupt.
1123 * @param NewState: new state of the interrupt.
1124 * This parameter can be: ENABLE or DISABLE.
1125 * @retval None
1127 void DFSDM_ITShortCircuitDetectorCmd(FunctionalState NewState)
1129 /* Check the parameters */
1130 assert_param(IS_FUNCTIONAL_STATE(NewState));
1132 if (NewState != DISABLE)
1134 /* Enable the Interrupt source */
1135 DFSDM0->FLTCR2 |= DFSDM_IT_SCD;
1137 else
1139 /* Disable the Interrupt source */
1140 DFSDM0->FLTCR2 &= ~(DFSDM_IT_SCD);
1145 * @brief Checks whether the specified DFSDM flag is set or not.
1146 * @param DFSDMx: where x can be 0 or 1 to select the DFSDM peripheral.
1147 * @param LPT_FLAG: specifies the flag to check.
1148 * This parameter can be any combination of the following values:
1149 * @arg DFSDM_FLAG_JEOC: End of injected conversion Flag
1150 * @arg DFSDM_FLAG_REOC: End of regular conversion Flag
1151 * @arg DFSDM_FLAG_JOVR: Injected data overrun Flag
1152 * @arg DFSDM_FLAG_ROVR: Regular data overrun Flag
1153 * @arg DFSDM_FLAG_AWD: Analog watchdog Flag
1154 * @arg DFSDM_FLAG_JCIP: Injected conversion in progress status
1155 * @arg DFSDM_FLAG_RCIP: Regular conversion in progress status
1156 * @retval None
1158 FlagStatus DFSDM_GetFlagStatus(DFSDM_TypeDef* DFSDMx, uint32_t DFSDM_FLAG)
1160 ITStatus bitstatus = RESET;
1162 /* Check the parameters */
1163 assert_param(IS_DFSDM_ALL_FILTER(DFSDMx));
1164 assert_param(IS_DFSDM_FLAG(DFSDM_FLAG));
1166 if ((DFSDMx->FLTISR & DFSDM_FLAG) != RESET )
1168 bitstatus = SET;
1170 else
1172 bitstatus = RESET;
1174 return bitstatus;
1178 * @brief Checks whether the specified Clock Absence Channel flag is set or not.
1179 * @param DFSDM_FLAG_CLKAbsence: specifies the flag to check.
1180 * This parameter can be a value of @ref DFSDM_Clock_Absence_Flag_Definition
1181 * @retval None
1183 FlagStatus DFSDM_GetClockAbsenceFlagStatus(uint32_t DFSDM_FLAG_CLKAbsence)
1185 ITStatus bitstatus = RESET;
1187 /* Check the parameters */
1188 assert_param(IS_DFSDM_CLK_ABS_FLAG(DFSDM_FLAG_CLKAbsence));
1190 if ((DFSDM0->FLTISR & DFSDM_FLAG_CLKAbsence) != RESET)
1192 bitstatus = SET;
1194 else
1196 bitstatus = RESET;
1198 return bitstatus;
1202 * @brief Checks whether the specified Short Circuit Channel Detector flag is set or not.
1203 * @param DFSDM_FLAG_SCD: specifies the flag to check.
1204 * This parameter can be a value of @ref DFSDM_SCD_Flag_Definition
1205 * @retval None
1207 FlagStatus DFSDM_GetShortCircuitFlagStatus(uint32_t DFSDM_FLAG_SCD)
1209 ITStatus bitstatus = RESET;
1211 /* Check the parameters */
1212 assert_param(IS_DFSDM_SCD_FLAG(DFSDM_FLAG_SCD));
1214 if ((DFSDM0->FLTISR & DFSDM_FLAG_SCD) != RESET)
1216 bitstatus = SET;
1218 else
1220 bitstatus = RESET;
1222 return bitstatus;
1226 * @brief Checks whether the specified Watchdog threshold flag is set or not.
1227 * @param DFSDMx: where x can be 0 or 1 to select the DFSDM peripheral.
1228 * @param DFSDM_AWDChannelx: where x can be a value from 0 to 7 to select the DFSDM Channel.
1229 * @param DFSDM_Threshold: specifies the Threshold.
1230 * This parameter can be a value of @ref DFSDM_Threshold_Selection.
1231 * @retval None
1233 FlagStatus DFSDM_GetWatchdogFlagStatus(DFSDM_TypeDef* DFSDMx, uint32_t DFSDM_AWDChannelx, uint8_t DFSDM_Threshold)
1235 ITStatus bitstatus = RESET;
1237 /* Check the parameters */
1238 assert_param(IS_DFSDM_ALL_FILTER(DFSDMx));
1239 assert_param(IS_DFSDM_Threshold(DFSDM_Threshold));
1240 assert_param(IS_DFSDM_AWD_CHANNEL(DFSDM_AWDChannelx));
1242 if ((DFSDMx->FLTAWSR & ((DFSDM_AWDChannelx >> 16) << DFSDM_Threshold) ) != RESET)
1244 bitstatus = SET;
1246 else
1248 bitstatus = RESET;
1250 return bitstatus;
1254 * @brief Clears the DFSDMx's pending flag.
1255 * @param DFSDMx: where x can be 0 or 1 to select the DFSDM peripheral.
1256 * @param DFSDM_CLEARF: specifies the pending bit to clear.
1257 * This parameter can be any combination of the following values:
1258 * @arg DFSDM_CLEARF_JOVR: Injected data overrun Clear Flag
1259 * @arg DFSDM_CLEARF_ROVR: Regular data overrun Clear Flag
1260 * @retval None
1262 void DFSDM_ClearFlag(DFSDM_TypeDef* DFSDMx, uint32_t DFSDM_CLEARF)
1264 /* Check the parameters */
1265 assert_param(IS_DFSDM_ALL_FILTER(DFSDMx));
1266 assert_param(IS_DFSDM_CLEAR_FLAG(DFSDM_CLEARF));
1268 /* Clear the pending Flag Bit */
1269 DFSDMx->FLTICR |= DFSDM_CLEARF;
1273 * @brief Clears the DFSDMx's pending Clock Absence Channel flag.
1274 * @param DFSDM_CLEARF_CLKAbsence: specifies the pending bit to clear.
1275 * This parameter can be any combination of @ref DFSDM_Clear_ClockAbs_Flag_Definition
1276 * @retval None
1278 void DFSDM_ClearClockAbsenceFlag(uint32_t DFSDM_CLEARF_CLKAbsence)
1280 /* Check the parameters */
1281 assert_param(IS_DFSDM_CLK_ABS_CLEARF(DFSDM_CLEARF_CLKAbsence));
1283 /* Clear the IT pending Flag Bit */
1284 DFSDM0->FLTICR |= DFSDM_CLEARF_CLKAbsence;
1288 * @brief Clears the DFSDMx's pending Short circuit Channel flag.
1289 * @param DFSDM_CLEARF_SCD: specifies the pending bit to clear.
1290 * This parameter can be any combination of @ref DFSDM_Clear_Short_Circuit_Flag_Definition
1291 * @retval None
1293 void DFSDM_ClearShortCircuitFlag(uint32_t DFSDM_CLEARF_SCD)
1295 /* Check the parameters */
1296 assert_param(IS_DFSDM_SCD_CHANNEL_FLAG(DFSDM_CLEARF_SCD));
1298 /* Clear the pending Flag Bit */
1299 DFSDM0->FLTICR |= DFSDM_CLEARF_SCD;
1303 * @brief Clears the DFSDMx's pending Analog watchdog Channel flag.
1304 * @param DFSDMx: where x can be 0 or 1 to select the DFSDM peripheral.
1305 * @param DFSDM_AWDChannelx: where x can be a value from 0 to 7 to select the DFSDM Channel.
1306 * @param DFSDM_Threshold: specifies the Threshold.
1307 * This parameter can be a value of @ref DFSDM_Threshold_Selection.
1308 * @retval None
1310 void DFSDM_ClearAnalogWatchdogFlag(DFSDM_TypeDef* DFSDMx, uint32_t DFSDM_AWDChannelx, uint8_t DFSDM_Threshold)
1312 /* Check the parameters */
1313 assert_param(IS_DFSDM_ALL_FILTER(DFSDMx));
1314 assert_param(IS_DFSDM_Threshold(DFSDM_Threshold));
1315 assert_param(IS_DFSDM_AWD_CHANNEL(DFSDM_AWDChannelx));
1317 if ((DFSDMx->FLTAWSR & ((DFSDM_AWDChannelx >> 16) << DFSDM_Threshold) ) != RESET)
1319 /* Clear the pending Flag Bit */
1320 DFSDMx->FLTAWCFR |= (DFSDM_AWDChannelx >> 16) << DFSDM_Threshold;
1324 * @brief Check whether the specified DFSDM interrupt has occurred or not.
1325 * @param DFSDMx: where x can be 0 or 1 to select the DFSDM peripheral.
1326 * @param DFSDM_IT: specifies the DFSDM interrupt source to check.
1327 * @arg DFSDM_IT_JEOC: End of injected conversion Interrupt source
1328 * @arg DFSDM_IT_REOC: End of regular conversion Interrupt source
1329 * @arg DFSDM_IT_JOVR: Injected data overrun Interrupt source
1330 * @arg DFSDM_IT_ROVR: Regular data overrun Interrupt source
1331 * @arg DFSDM_IT_AWD : Analog watchdog Interrupt source
1332 * @retval The new state of DFSDM_IT (SET or RESET).
1334 ITStatus DFSDM_GetITStatus(DFSDM_TypeDef* DFSDMx, uint32_t DFSDM_IT)
1336 ITStatus bitstatus = RESET;
1337 uint32_t itstatus = 0x0, itenable = 0x0;
1339 /* Check the parameters */
1340 assert_param(IS_DFSDM_ALL_FILTER(DFSDMx));
1341 assert_param(IS_DFSDM_IT(DFSDM_IT));
1343 /* Get the Interrupt Status bit value */
1344 itstatus = DFSDMx->FLTISR & DFSDM_IT;
1346 /* Check if the Interrupt is enabled */
1347 itenable = DFSDMx->FLTCR2 & DFSDM_IT;
1349 if ((itstatus != RESET) && (itenable != RESET))
1351 bitstatus = SET;
1353 else
1355 bitstatus = RESET;
1357 return bitstatus;
1361 * @brief Check whether the specified Clock Absence channel interrupt has occurred or not.
1362 * @param DFSDM_IT_CLKAbsence: specifies on which channel check the interrupt source.
1363 * This parameter can be a value of @ref DFSDM_Clock_Absence_Interrupt_Definition.
1364 * @retval The new state of DFSDM_IT (SET or RESET).
1365 * @note Clock absence interrupt is handled only by DFSDM0.
1367 ITStatus DFSDM_GetClockAbsenceITStatus(uint32_t DFSDM_IT_CLKAbsence)
1369 ITStatus bitstatus = RESET;
1370 uint32_t itstatus = 0x0, itenable = 0x0;
1372 /* Check the parameters */
1373 assert_param(IS_DFSDM_CLK_ABS_IT(DFSDM_IT_CLKAbsence));
1375 /* Get the Interrupt Status bit value */
1376 itstatus = DFSDM0->FLTISR & DFSDM_IT_CLKAbsence;
1378 /* Check if the Interrupt is enabled */
1379 itenable = DFSDM0->FLTCR2 & DFSDM_IT_CKAB;
1381 if ((itstatus != RESET) && (itenable != RESET))
1383 bitstatus = SET;
1385 else
1387 bitstatus = RESET;
1389 return bitstatus;
1393 * @brief Check whether the specified Short Circuit channel interrupt has occurred or not.
1394 * @param DFSDM_IT_SCR: specifies on which channel check the interrupt source.
1395 * This parameter can be a value of @ref DFSDM_SCD_Interrupt_Definition.
1396 * @retval The new state of DFSDM_IT (SET or RESET).
1397 * @note Short circuit interrupt is handled only by DFSDM0.
1399 ITStatus DFSDM_GetGetShortCircuitITStatus(uint32_t DFSDM_IT_SCR)
1401 ITStatus bitstatus = RESET;
1402 uint32_t itstatus = 0x0, itenable = 0x0;
1404 /* Check the parameters */
1405 assert_param(IS_DFSDM_SCD_IT(DFSDM_IT_SCR));
1407 /* Get the Interrupt Status bit value */
1408 itstatus = DFSDM0->FLTISR & DFSDM_IT_SCR;
1410 /* Check if the Interrupt is enabled */
1411 itenable = DFSDM0->FLTCR2 & DFSDM_IT_SCD;
1413 if ((itstatus != RESET) && (itenable != RESET))
1415 bitstatus = SET;
1417 else
1419 bitstatus = RESET;
1421 return bitstatus;
1425 * @}
1429 * @}
1431 #endif /* STM32F412xG */
1434 * @}
1438 * @}
1441 /************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/